Skip to content
This repository has been archived by the owner on May 19, 2024. It is now read-only.

Commit

Permalink
perm(arm): Slow down movements.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Feb 13, 2024
1 parent 0997839 commit 6787503
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 6 deletions.
3 changes: 1 addition & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -81,8 +81,7 @@ private void configureBindings() {
.rightTrigger()
.whileTrue(Commands.parallel(arm.to(ArmState.SHOOT)).andThen(shooter.shoot()));

operatorController.rightBumper().whileTrue(intake.outtake()).whileTrue(shooter.shoot());
operatorController.rightTrigger().whileTrue(shooter.smartShoot());
operatorController.rightBumper().whileTrue(shooter.shoot());

operatorController.a().onTrue(Commands.runOnce(() -> arm.setGoal(ArmState.AMP)));
operatorController.b().onTrue(Commands.runOnce(() -> arm.setGoal(ArmState.STOW)));
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/arm/ArmConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ public static class ShoulderMotorConstants {
public static final Rotation2d MINIMUM_ANGLE = Rotation2d.fromDegrees(12.5);

/** Maximum angle of the shoulder joint. */
public static final Rotation2d MAXIMUM_ANGLE = Rotation2d.fromDegrees(115);
public static final Rotation2d MAXIMUM_ANGLE = Rotation2d.fromDegrees(90);

/** Tolerance of the shoulder joint. */
public static final Rotation2d TOLERANCE = Rotation2d.fromDegrees(5.0);
Expand All @@ -36,11 +36,11 @@ public static class ShoulderMotorConstants {
public static final double KP = 36.0;

/** Maximum speed of the shoulder joint in rotations per second. */
public static final double MAXIMUM_SPEED = 1.5;
public static final double MAXIMUM_SPEED = 1.0;

/** Maximum acceleration of the shoulder joint in rotations per second per second. */
public static final double MAXIMUM_ACCELERATION =
MotionProfileCalculator.calculateAcceleration(MAXIMUM_SPEED, 0.3);
MotionProfileCalculator.calculateAcceleration(MAXIMUM_SPEED, 0.5);

/** Maximum speed and acceleration of the shoulder joint. */
public static final TrapezoidProfile.Constraints CONSTRAINTS =
Expand Down Expand Up @@ -77,7 +77,7 @@ public static class ElbowMotorConstants {
public static final double KP = 48.0;

/** Maximum speed of the shoulder joint in rotations per second. */
public static final double MAXIMUM_SPEED = 2.0;
public static final double MAXIMUM_SPEED = 1.5;

/** Maximum acceleration of the shoulder joint in rotations per second per second. */
public static final double MAXIMUM_ACCELERATION =
Expand Down

0 comments on commit 6787503

Please sign in to comment.