Skip to content

Commit cbbfdcf

Browse files
committed
feat: create arm public interface for managing componenets
Signed-off-by: Dasun Abeykoon <[email protected]>
1 parent 700229c commit cbbfdcf

File tree

1 file changed

+73
-0
lines changed
  • src/main/java/org/frc6423/robot/subsystems/arm

1 file changed

+73
-0
lines changed
Lines changed: 73 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,73 @@
1+
package org.frc6423.robot.subsystems.arm;
2+
3+
import java.util.function.DoubleSupplier;
4+
5+
import org.frc6423.lib.drivers.LoggedSubsystem;
6+
import org.frc6423.lib.subsystems.RollerIO;
7+
import org.frc6423.monologue.Annotations.FlattenedLogged;
8+
9+
import edu.wpi.first.units.measure.Angle;
10+
import edu.wpi.first.wpilibj2.command.Command;
11+
12+
/** Public interface of the {@link Arm} subsystem */
13+
public class Arm extends LoggedSubsystem {
14+
@FlattenedLogged private final ArmPivot pivot;
15+
@FlattenedLogged private final ArmRoller roller;
16+
17+
public Arm(ArmPivotIO pivotIO, RollerIO rollerIO) {
18+
this.pivot = new ArmPivot(pivotIO);
19+
this.roller = new ArmRoller(rollerIO);
20+
}
21+
22+
/**
23+
* @return true when arm is at setpoint angle
24+
*/
25+
public boolean atPose() {
26+
return pivot.atPose();
27+
}
28+
29+
/**
30+
* Set the goal angle of the arm
31+
*
32+
* @param angle {@link Angle} representing the desired angle
33+
* @return {@link Command}
34+
*/
35+
public Command goToAngle(Angle angle) {
36+
return pivot.goToAngle(angle);
37+
}
38+
39+
/**
40+
* Hold pivot at its current position for the duration of this command's life
41+
*
42+
* @return {@link Command}
43+
*/
44+
public Command hold() {
45+
return pivot.hold();
46+
}
47+
48+
/**
49+
* Run roller at specified voltage
50+
*
51+
* @param volts desired voltage
52+
* @return {@link Command}
53+
*/
54+
public Command runRollerVolts(DoubleSupplier volts) {
55+
return roller.runRollerVolts(volts);
56+
}
57+
58+
/**
59+
* Run roller at specified voltage
60+
*
61+
* @param volts desired voltage
62+
* @return {@link Command}
63+
*/
64+
public Command runRollerVolts(double volts) {
65+
return roller.runRollerVolts(volts);
66+
}
67+
68+
@Override
69+
public void close() throws Exception {
70+
pivot.close();
71+
roller.close();
72+
}
73+
}

0 commit comments

Comments
 (0)