6
6
import com .revrobotics .CANSparkBase .IdleMode ;
7
7
import com .revrobotics .CANSparkLowLevel .MotorType ;
8
8
import com .revrobotics .RelativeEncoder ;
9
- import edu .wpi .first .math .controller .SimpleMotorFeedforward ;
9
+ import edu .wpi .first .math .controller .ArmFeedforward ;
10
10
import edu .wpi .first .math .geometry .Rotation2d ;
11
11
import edu .wpi .first .math .trajectory .TrapezoidProfile ;
12
+ import edu .wpi .first .wpilibj .DigitalInput ;
12
13
import edu .wpi .first .wpilibj2 .command .Command ;
13
14
import edu .wpi .first .wpilibj2 .command .SubsystemBase ;
14
15
import edu .wpi .first .wpilibj2 .command .sysid .SysIdRoutine ;
15
16
import frc .robot .Constants ;
16
17
import frc .robot .telemetry .tunable .TunableTelemetryProfiledPIDController ;
17
- import frc .robot .telemetry .types .DoubleTelemetryEntry ;
18
18
import frc .robot .telemetry .types .EventTelemetryEntry ;
19
19
import frc .robot .telemetry .wrappers .TelemetryCANSparkMax ;
20
20
import frc .robot .utils .Alert ;
@@ -28,8 +28,6 @@ public class SlapdownSubsystem extends SubsystemBase {
28
28
private static final Alert feederMotorAlert =
29
29
new Alert ("Slapdown feeder motor had a fault initializing" , Alert .AlertType .ERROR );
30
30
31
- private DoubleTelemetryEntry rotationEncoderEntry =
32
- new DoubleTelemetryEntry ("/slapdown/encoders" , true );
33
31
private final TelemetryCANSparkMax feederMotor =
34
32
new TelemetryCANSparkMax (
35
33
FEEDER_MOTOR_ID ,
@@ -42,6 +40,7 @@ public class SlapdownSubsystem extends SubsystemBase {
42
40
MotorType .kBrushless ,
43
41
"/slapdown/rotation/motor" ,
44
42
Constants .MiscConstants .TUNING_MODE );
43
+
45
44
private final SysIdRoutine slapdownRotationSysId =
46
45
new SysIdRoutine (
47
46
new SysIdRoutine .Config (),
@@ -50,18 +49,20 @@ public class SlapdownSubsystem extends SubsystemBase {
50
49
null , // No log consumer, since data is recorded by URCL
51
50
this ));
52
51
53
- private final SimpleMotorFeedforward rotationFF ;
52
+ private final ArmFeedforward rotationFF = ROTATION_FF_GAINS . createArmFeedforward () ;
54
53
private final TunableTelemetryProfiledPIDController rotationController =
55
54
new TunableTelemetryProfiledPIDController (
56
55
"/slapdown/rotation/controller" , ROTATION_GAINS , ROTATION_TRAP_GAINS );
56
+
57
57
private final RelativeEncoder rotationEncoder ;
58
58
59
+ private final DigitalInput rotationLimitSwitch = new DigitalInput (ROTATION_LIMIT_SWITCH_ID );
60
+
59
61
private final EventTelemetryEntry slapdownEventEntry =
60
62
new EventTelemetryEntry ("/slapdown/events" );
61
63
62
64
public SlapdownSubsystem () {
63
65
rotationEncoder = rotationMotor .getEncoder ();
64
- rotationFF = ROTATION_FF_GAINS .createFeedforward ();
65
66
configMotors ();
66
67
67
68
setDefaultCommand (stopAllCommand ());
@@ -226,9 +227,11 @@ public Command stopAllCommand() {
226
227
227
228
@ Override
228
229
public void periodic () {
230
+ if (rotationLimitSwitch .get ()) {
231
+ rotationEncoder .setPosition (ROTATION_UP_ANGLE );
232
+ }
233
+
229
234
rotationMotor .logValues ();
230
235
feederMotor .logValues ();
231
-
232
- rotationEncoderEntry .append (getPosition ());
233
236
}
234
237
}
0 commit comments