Skip to content

Commit 071ebe6

Browse files
committed
fixed formatting and added number to pos tolerance(NOT FINALIZED NUMBER)
1 parent 1919ce2 commit 071ebe6

File tree

3 files changed

+9
-8
lines changed

3 files changed

+9
-8
lines changed

src/main/java/org/carlmontrobotics/Constants.java

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -74,11 +74,13 @@ public static final class Arm {
7474
MAX_FF_VEL_RAD_P_S, MAX_FF_ACCEL_RAD_P_S);
7575
// other0;
7676

77-
//public static final double MARGIN_OF_ERROR = Math.PI / 18;
77+
// public static final double MARGIN_OF_ERROR = Math.PI / 18;
7878

7979
// Boundaries
8080
public static final double ARM_TELEOP_MAX_GOAL_DIFF_FROM_CURRENT_RAD = 0; // placeholder
81-
public static final double POS_TOLERANCE_RAD = 0; // placeholder
81+
public static final double POS_TOLERANCE_RAD = Units.degreesToRadians(195); // placeholder //Whether or not this is the actual account
82+
// idk TODO: test on actual encoder without a conversion
83+
// factor
8284
public static final double VEL_TOLERANCE_RAD_P_SEC = 0; // placeholder
8385
public static final double UPPER_ANGLE_LIMIT_RAD = Units.degreesToRadians(70);
8486
public static final double LOWER_ANGLE_LIMIT_RAD = Units.degreesToRadians(0);

src/main/java/org/carlmontrobotics/RobotContainer.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ private void setBindingsManipulator() {
8080
// 3 setpositions of arm on letterpad
8181
// Up is Speaker, down is ground, right is Amp
8282
// right joystick used for manual arm control
83-
//COMMENT THESE OUT DURING SYSID TESTING
83+
// COMMENT THESE OUT DURING SYSID TESTING
8484
// Speaker Buttons
8585
new JoystickButton(manipulatorController, Constants.OI.Manipulator.RAISE_TO_SPEAKER_POD_BUTTON)
8686
.onTrue(new InstantCommand(() -> {
@@ -112,7 +112,7 @@ private void setBindingsManipulator() {
112112
.onTrue(new InstantCommand(() -> {
113113
arm.setArmTarget(CLIMBER_DOWN_ANGLE_RAD);
114114
}));
115-
//----------------------------------------------------------------------
115+
// ----------------------------------------------------------------------
116116
}
117117

118118
public Command getAutonomousCommand() {

src/main/java/org/carlmontrobotics/subsystems/Arm.java

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -166,10 +166,9 @@ private void driveArm() {
166166
armFeedVolts = armFeed.calculate(getCurrentArmGoal().position, 0);
167167
}
168168
armPIDMaster.setReference(setPoint.position, CANSparkBase.ControlType.kVelocity, 0, armFeedVolts);
169-
if (armAtSetpoint() || getArmPos() > setPoint.position){
170-
armPIDMaster.setIZone(Double.POSITIVE_INFINITY);//turns off pid once it reaches the setpoint
171-
}
172-
else {
169+
if (armAtSetpoint() || getArmPos() > setPoint.position) {
170+
armPIDMaster.setIZone(Double.POSITIVE_INFINITY);// turns off pid once it reaches the setpoint
171+
} else {
173172
armPIDMaster.setIZone(IZONE);
174173
}
175174

0 commit comments

Comments
 (0)