Skip to content

Commit 9b5467b

Browse files
committed
Switch flywheel to log rotations
1 parent 90afb7e commit 9b5467b

File tree

3 files changed

+19
-20
lines changed

3 files changed

+19
-20
lines changed

src/main/java/com/stuypulse/robot/constants/Settings.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ public enum Mechanism {
2727
SWERVE_TURN,
2828
SWERVE_DRIVE,
2929
TANK_DRIVE,
30-
FLYWHEEL,
30+
FLYWHEEL, // must use conversion of 60 in SysID for velocity
3131
ELEVATOR,
3232
SINGLE_JOINTED_ARM,
3333
DOUBLE_JOINTED_ARM_JOINT_ONE,

src/main/java/com/stuypulse/robot/subsystems/flywheel/Flywheel.java

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -10,7 +10,6 @@
1010

1111
import com.stuypulse.robot.constants.Ports;
1212

13-
import edu.wpi.first.math.util.Units;
1413
import edu.wpi.first.wpilibj2.command.SubsystemBase;
1514

1615
import com.revrobotics.CANSparkLowLevel.MotorType;
@@ -38,11 +37,11 @@ public Flywheel() {
3837
}
3938

4039
public double getVelocity() {
41-
return Units.rotationsPerMinuteToRadiansPerSecond(encoder.getVelocity());
40+
return encoder.getVelocity();
4241
}
4342

4443
public double getPosition() {
45-
return Units.rotationsToRadians(encoder.getPosition());
44+
return encoder.getPosition();
4645
}
4746

4847
public double getVoltage() {

src/main/java/com/stuypulse/robot/subsystems/flywheel/FlywheelSysID.java

Lines changed: 16 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -23,22 +23,22 @@ public class FlywheelSysID extends AbstractSysID {
2323
public FlywheelSysID() {
2424
this.flywheel = new Flywheel();
2525
this.flywheelRoutine =
26-
new SysIdRoutine(
27-
new SysIdRoutine.Config(),
28-
new SysIdRoutine.Mechanism(
29-
(Measure<Voltage> voltage) -> {
30-
flywheel.setVoltage(voltage.in(Units.Volts));
31-
},
32-
(log) -> {
33-
log.motor(flywheel.getName())
34-
.voltage(Units.Volts.of(flywheel.getVoltage()))
35-
.angularPosition(
36-
Units.Radians.of(flywheel.getPosition()))
37-
.angularVelocity(
38-
Units.RadiansPerSecond.of(
39-
flywheel.getVelocity()));
40-
},
41-
this));
26+
new SysIdRoutine(
27+
new SysIdRoutine.Config(),
28+
new SysIdRoutine.Mechanism(
29+
(Measure<Voltage> voltage) -> {
30+
flywheel.setVoltage(voltage.in(Units.Volts));
31+
},
32+
(log) -> {
33+
log.motor(flywheel.getName())
34+
.voltage(Units.Volts.of(flywheel.getVoltage()))
35+
.angularPosition(
36+
Units.Rotations.of(flywheel.getPosition()))
37+
.angularVelocity(
38+
Units.RotationsPerSecond.of(
39+
flywheel.getVelocity()));
40+
},
41+
this));
4242
}
4343

4444
@Override

0 commit comments

Comments
 (0)