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

Commit e52643d

Browse files
committed
refactor(arm): Use primitives (moveShoulder / moveWrist) where possible.
1 parent 9271e0a commit e52643d

File tree

5 files changed

+130
-72
lines changed

5 files changed

+130
-72
lines changed

src/main/java/frc/robot/arm/Arm.java

Lines changed: 106 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,10 @@ public class Arm extends Subsystem {
3939
/** Wrist motor values. */
4040
private final WristMotorIOValues wristMotorValues = new WristMotorIOValues();
4141

42+
/** Arm goal and setpoint states. */
4243
private ArmState goal, setpoint;
44+
45+
/** Telemetry for the shoulder and wrist trapezoid profiles. */
4346
private final TrapezoidProfileTelemetry shoulderProfileTelemetry, wristProfileTelemetry;
4447

4548
/** Creates a new instance of the arm subsystem. */
@@ -54,14 +57,8 @@ private Arm() {
5457
shoulderMotor.configure();
5558
wristMotor.configure();
5659

57-
ArmState initialState = ArmState.INIT;
58-
59-
setPosition(initialState);
60-
61-
// Since setPosition also resets goal and setpoint, this is redundant, but will protect from
62-
// nullish errors
63-
goal = initialState;
64-
setpoint = initialState;
60+
setPosition(ArmState.INIT);
61+
clearProfile();
6562

6663
shoulderProfileTelemetry = new TrapezoidProfileTelemetry("arm/shoulderProfile");
6764
wristProfileTelemetry = new TrapezoidProfileTelemetry("arm/wristProfile");
@@ -92,8 +89,6 @@ public void periodic() {
9289
getMeasuredState().shoulder(), getSetpoint().shoulder(), getGoal().shoulder());
9390
wristProfileTelemetry.update(
9491
getMeasuredState().wrist(), getSetpoint().wrist(), getGoal().wrist());
95-
96-
setSetpoint(setpoint.nextSetpoint(goal));
9792
}
9893

9994
@Override
@@ -117,15 +112,13 @@ public void addToShuffleboard(ShuffleboardTab tab) {
117112
() -> Units.rotationsToDegrees(getSetpoint().shoulder().position));
118113
setpoint.addDouble(
119114
"Wrist Setpoint (deg)", () -> Units.rotationsToDegrees(getSetpoint().wrist().position));
120-
setpoint.addBoolean("At Setpoint?", this::atSetpoint);
121115

122116
ShuffleboardLayout goal = Telemetry.addColumn(tab, "Goal");
123117

124118
goal.addDouble(
125119
"Shoulder Setpoint (deg)", () -> Units.rotationsToDegrees(getGoal().shoulder().position));
126120
goal.addDouble(
127121
"Wrist Setpoint (deg)", () -> Units.rotationsToDegrees(getGoal().wrist().position));
128-
goal.addBoolean("At Goal?", this::atGoal);
129122

130123
ShuffleboardLayout voltages = Telemetry.addColumn(tab, "Voltages");
131124

@@ -146,12 +139,25 @@ public void addToShuffleboard(ShuffleboardTab tab) {
146139
() -> wristMotorValues.accelerationRotationsPerSecondPerSecond);
147140
}
148141

142+
/**
143+
* Sets the position of the arm to the supplied state.
144+
*
145+
* @param state the state containing the position of the arm.
146+
*/
149147
public void setPosition(ArmState state) {
150148
shoulderMotor.setPosition(state.shoulder().position);
151149
wristMotor.setPosition(state.wrist().position);
150+
}
152151

153-
goal = state;
154-
setpoint = state;
152+
/**
153+
* Resets the goal and setpoints of the arm to the arm's current position. Commands the arm to
154+
* hold its current position.
155+
*/
156+
public void clearProfile() {
157+
ArmState position = getMeasuredState().position();
158+
159+
goal = position;
160+
setpoint = position;
155161
}
156162

157163
/**
@@ -173,62 +179,124 @@ public ArmState getMeasuredState() {
173179
return new ArmState(measuredShoulderState, measuredWristState);
174180
}
175181

176-
public ArmState getGoal() {
177-
return goal;
182+
/**
183+
* Returns true if the arm is at a given state.
184+
*
185+
* @param state the state to compare to.
186+
* @return true if the arm is at a given state.
187+
*/
188+
public boolean at(ArmState state) {
189+
return getMeasuredState().at(state);
178190
}
179191

180-
public boolean atGoal() {
181-
return atSetpoint() && setpoint.at(goal);
192+
/**
193+
* Returns the arm's goal.
194+
*
195+
* @return the arm's goal.
196+
*/
197+
public ArmState getGoal() {
198+
return this.goal;
182199
}
183200

201+
/**
202+
* Sets the arm's goal.
203+
*
204+
* <p>Calling this method does not alter the arm's motion; it simply updates a value used for
205+
* telemetry.
206+
*
207+
* @param goal the arm's goal.
208+
*/
184209
public void setGoal(ArmState goal) {
185210
this.goal = goal;
186211
}
187212

213+
/**
214+
* Returns the arm's setpoint.
215+
*
216+
* @return the arm's setpoint.
217+
*/
188218
public ArmState getSetpoint() {
189-
return setpoint;
219+
return this.setpoint;
190220
}
191221

192-
public boolean atSetpoint() {
193-
return getMeasuredState().at(setpoint);
194-
}
195-
196-
private void setSetpoint(ArmState setpoint) {
222+
/**
223+
* Sets the arm's setpoint.
224+
*
225+
* <p>Calling this method does not alter the arm's motion; it simply updates a value used for
226+
* telemetry.
227+
*
228+
* @param setpoint the arm's setpoint.
229+
*/
230+
public void setSetpoint(ArmState setpoint) {
197231
this.setpoint = setpoint;
232+
}
198233

234+
/**
235+
* Applies a setpoint to the arm's controllers.
236+
*
237+
* <p>Calling this method alters the arm's motion.
238+
*
239+
* @param setpoint the arm's setpoint.
240+
*/
241+
public void applySetpoint(ArmState setpoint) {
199242
shoulderMotor.setSetpoint(setpoint.shoulder().position, setpoint.shoulder().velocity);
200243
wristMotor.setSetpoint(setpoint.wrist().position, setpoint.wrist().velocity);
201244
}
202245

203-
private MoveShoulderCommand moveShoulder(ArmState goal) {
246+
/**
247+
* Returns a command that moves the shoulder to a goal's shoulder position.
248+
*
249+
* @param goal the goal position to move to.
250+
* @return a command that moves the shoulder to a goal's shoulder position.
251+
*/
252+
private Command shoulderTo(ArmState goal) {
204253
return new MoveShoulderCommand(goal);
205254
}
206255

207-
public MoveWristCommand moveWrist(ArmState goal) {
256+
/**
257+
* Returns a command that moves the wrist to a goal's wrist position.
258+
*
259+
* @param goal the goal position to move to.
260+
* @return a command that moves the wrist to a goal's wrist position.
261+
*/
262+
public Command wristTo(ArmState goal) {
208263
return new MoveWristCommand(goal);
209264
}
210265

211-
public Command moveShoulderThenWrist(ArmState goal) {
212-
return moveShoulder(goal).andThen(moveWrist(goal));
213-
}
214-
215-
public Command moveWristThenShoulder(ArmState goal) {
216-
return moveWrist(goal).andThen(moveShoulder(goal));
266+
/**
267+
* Returns a command that moves the arm to the amp position.
268+
*
269+
* @return a comamnd that moves the arm to the amp position.
270+
*/
271+
public Command amp() {
272+
return shoulderTo(ArmState.AMP).andThen(wristTo(ArmState.AMP));
217273
}
218274

219-
public Command amp() {
220-
return moveShoulderThenWrist(ArmState.AMP);
275+
/**
276+
* Returns a command that moves the arm to the stow position.
277+
*
278+
* @return a command that moves the arm to the stow position.
279+
*/
280+
public Command stow() {
281+
return wristTo(ArmState.STOW).andThen(shoulderTo(ArmState.STOW));
221282
}
222283

284+
/**
285+
* Returns a command that moves the arm to the stow position and resets the position of the arm.
286+
*
287+
* <p>When the limit switch detects that the arm is in the stow position, the arm position is
288+
* reset to be equal to the stow position.
289+
*
290+
* @return a command that moves the arm to the stow position and resets the position of the arm.
291+
*/
223292
public Command home() {
224-
return moveWrist(ArmState.STOW)
225-
.andThen(moveShoulder(ArmState.STOW).until(() -> limitSwitchValues.isPressed))
293+
return wristTo(ArmState.STOW)
294+
.andThen(shoulderTo(ArmState.STOW).until(() -> limitSwitchValues.isPressed))
226295
.finallyDo(
227296
interrupted -> {
228297
if (!interrupted) {
229298
setPosition(ArmState.STOW);
230299
}
231-
})
232-
.withTimeout(3.0);
300+
});
233301
}
234302
}

src/main/java/frc/robot/arm/ArmState.java

Lines changed: 0 additions & 25 deletions
Original file line numberDiff line numberDiff line change
@@ -152,29 +152,4 @@ public ArmState nextWristSetpoint(ArmState goal) {
152152
WristMotorConstants.MOTION_PROFILE.calculate(
153153
RobotConstants.PERIODIC_DURATION, this.wrist, goal.wrist));
154154
}
155-
156-
/**
157-
* Returns the next overall setpoint of the arm's movement.
158-
*
159-
* @param goal the arm's goal state.
160-
* @return the next overall setpoint.
161-
*/
162-
public ArmState nextSetpoint(ArmState goal) {
163-
boolean shooterOnBottom = Rotation2d.fromRotations(wrist.position).getDegrees() < 0.0;
164-
boolean shooterNeedsToBeOnTop =
165-
Rotation2d.fromRotations(goal.wrist.position).getDegrees() > 0.0;
166-
boolean shooterOnWrongSide = shooterOnBottom && shooterNeedsToBeOnTop;
167-
168-
if (shooterOnWrongSide && !atWristGoal(goal)) {
169-
return nextWristSetpoint(goal);
170-
}
171-
172-
if (!atShoulderGoal(goal)) {
173-
return nextShoulderSetpoint(goal);
174-
} else if (!atWristGoal(goal)) {
175-
return nextWristSetpoint(goal);
176-
}
177-
178-
return this;
179-
}
180155
}

src/main/java/frc/robot/arm/MoveShoulderCommand.java

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,13 +24,22 @@ public void initialize() {
2424
before = arm.getMeasuredState().position();
2525

2626
arm.setGoal(shoulderGoal.withWrist(before.wrist()));
27+
arm.setSetpoint(before);
28+
}
29+
30+
@Override
31+
public void execute() {
32+
ArmState nextSetpoint = arm.getSetpoint().nextShoulderSetpoint(shoulderGoal);
33+
34+
arm.setSetpoint(nextSetpoint);
35+
arm.applySetpoint(nextSetpoint);
2736
}
2837

2938
@Override
3039
public void end(boolean interrupted) {
3140
ArmState after = arm.getMeasuredState().position();
3241

33-
// Since only the shoulder should have moved, assume that the wrist is in the same position as
42+
// Since only the shoulder *should* have moved, assume that the wrist is in the same position as
3443
// it was at the start of the command
3544
arm.setPosition(after.withWrist(before.wrist()));
3645
}

src/main/java/frc/robot/arm/MoveWristCommand.java

Lines changed: 10 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,13 +24,22 @@ public void initialize() {
2424
before = arm.getMeasuredState().position();
2525

2626
arm.setGoal(wristGoal.withShoulder(before.shoulder()));
27+
arm.setSetpoint(before);
28+
}
29+
30+
@Override
31+
public void execute() {
32+
ArmState nextSetpoint = arm.getSetpoint().nextWristSetpoint(wristGoal);
33+
34+
arm.setSetpoint(nextSetpoint);
35+
arm.applySetpoint(nextSetpoint);
2736
}
2837

2938
@Override
3039
public void end(boolean interrupted) {
3140
ArmState after = arm.getMeasuredState().position();
3241

33-
// Since only the wrist should have moved, assume that the shoulder is in the same position as
42+
// Since only the wrist *should* have moved, assume that the shoulder is in the same position as
3443
// it was at the start of the command
3544
arm.setPosition(after.withShoulder(before.shoulder()));
3645
}

src/main/java/frc/robot/auto/Auto.java

Lines changed: 4 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -135,8 +135,7 @@ public Command readyIntake() {
135135
double seconds = 3.0;
136136

137137
return Commands.parallel(
138-
Commands.waitUntil(intake::isNotStowed)
139-
.andThen(arm.moveShoulderThenWrist(ArmState.INTAKE)),
138+
Commands.waitUntil(intake::isNotStowed).andThen(arm.wristTo(ArmState.INTAKE)),
140139
intake.out())
141140
.withTimeout(seconds);
142141
}
@@ -149,18 +148,16 @@ public Command stow() {
149148
double seconds = 2.0;
150149

151150
return Commands.parallel(
152-
arm.moveWristThenShoulder(ArmState.STOW),
153-
Commands.waitUntil(() -> arm.getMeasuredState().at(ArmState.STOW))
154-
.withTimeout(2.0)
155-
.andThen(intake.in()))
151+
arm.stow(),
152+
Commands.waitUntil(() -> arm.at(ArmState.STOW)).withTimeout(2.0).andThen(intake.in()))
156153
.withTimeout(seconds);
157154
}
158155

159156
public Command readyShoot() {
160157
double seconds = 3.0;
161158

162159
return Commands.parallel(
163-
Commands.waitUntil(intake::isNotStowed).andThen(arm.moveWrist(ArmState.SHOOT)),
160+
Commands.waitUntil(intake::isNotStowed).andThen(arm.wristTo(ArmState.SHOOT)),
164161
intake.out())
165162
.withTimeout(seconds);
166163
}

0 commit comments

Comments
 (0)