File tree Expand file tree Collapse file tree 3 files changed +19
-20
lines changed
src/main/java/com/stuypulse/robot Expand file tree Collapse file tree 3 files changed +19
-20
lines changed Original file line number Diff line number Diff line change @@ -27,7 +27,7 @@ public enum Mechanism {
27
27
SWERVE_TURN ,
28
28
SWERVE_DRIVE ,
29
29
TANK_DRIVE ,
30
- FLYWHEEL ,
30
+ FLYWHEEL , // must use conversion of 60 in SysID for velocity
31
31
ELEVATOR ,
32
32
SINGLE_JOINTED_ARM ,
33
33
DOUBLE_JOINTED_ARM_JOINT_ONE ,
Original file line number Diff line number Diff line change 10
10
11
11
import com .stuypulse .robot .constants .Ports ;
12
12
13
- import edu .wpi .first .math .util .Units ;
14
13
import edu .wpi .first .wpilibj2 .command .SubsystemBase ;
15
14
16
15
import com .revrobotics .CANSparkLowLevel .MotorType ;
@@ -38,11 +37,11 @@ public Flywheel() {
38
37
}
39
38
40
39
public double getVelocity () {
41
- return Units . rotationsPerMinuteToRadiansPerSecond ( encoder .getVelocity () );
40
+ return encoder .getVelocity ();
42
41
}
43
42
44
43
public double getPosition () {
45
- return Units . rotationsToRadians ( encoder .getPosition () );
44
+ return encoder .getPosition ();
46
45
}
47
46
48
47
public double getVoltage () {
Original file line number Diff line number Diff line change @@ -23,22 +23,22 @@ public class FlywheelSysID extends AbstractSysID {
23
23
public FlywheelSysID () {
24
24
this .flywheel = new Flywheel ();
25
25
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 ));
42
42
}
43
43
44
44
@ Override
You can’t perform that action at this time.
0 commit comments