1
1
package frc .robot .subsystems ;
2
2
3
+ import com .revrobotics .RelativeEncoder ;
3
4
import com .revrobotics .servohub .ServoHub .ResetMode ;
5
+ import com .revrobotics .spark .SparkClosedLoopController ;
4
6
import com .revrobotics .spark .SparkMax ;
7
+ import com .revrobotics .spark .SparkBase .ControlType ;
5
8
import com .revrobotics .spark .SparkBase .PersistMode ;
6
9
import com .revrobotics .spark .SparkLowLevel .MotorType ;
10
+ import com .revrobotics .spark .config .ClosedLoopConfig ;
7
11
import com .revrobotics .spark .config .SparkMaxConfig ;
12
+ import com .revrobotics .spark .config .ClosedLoopConfig .FeedbackSensor ;
8
13
import com .revrobotics .spark .config .SparkBaseConfig .IdleMode ;
9
14
10
15
import edu .wpi .first .util .sendable .SendableBuilder ;
14
19
15
20
public class ArmSubsystem extends SubsystemBase {
16
21
22
+ private InputSubsystem input ;
23
+
17
24
/**
18
25
* Controls the left motor of the 4 bar lift.
19
26
*/
@@ -26,46 +33,51 @@ public class ArmSubsystem extends SubsystemBase {
26
33
private SparkMax RightLift ;
27
34
28
35
/**
29
- * Left algae intake motor.
36
+ * Left coral intake motor.
30
37
*/
31
- private SparkMax LeftAlgae ;
38
+ private SparkMax LeftCoral ;
32
39
33
40
/**
34
- * Right algae intake motor. Similar to the lift motors,
35
- * this will be a follower of the left algae intake motor.
41
+ * Right coral intake motor. Similar to the lift motors,
42
+ * this will be a follower of the left coral intake motor.
36
43
*/
37
- private SparkMax RightAlgae ;
44
+ private SparkMax RightCoral ;
38
45
39
- /**
40
- * Coral intake motor
41
- */
42
- private SparkMax CoralIntake ;
43
46
44
- public ArmSubsystem () {
47
+ private RelativeEncoder leftLiftEncoder ;
48
+
49
+ private SparkClosedLoopController pidController ;
50
+
51
+ public ArmSubsystem (InputSubsystem inputSubsystem ) {
52
+ input = inputSubsystem ;
45
53
LeftLift = new SparkMax (Constants .ArmConstants .LEFT_LIFT_CAN_ID , MotorType .kBrushless );
46
54
RightLift = new SparkMax (Constants .ArmConstants .RIGHT_LIFT_CAN_ID , MotorType .kBrushless );
47
- LeftAlgae = new SparkMax (Constants .ArmConstants .LEFT_ALGAE_CAN_ID , MotorType .kBrushless );
48
- RightAlgae = new SparkMax (Constants .ArmConstants .RIGHT_ALGAE_CAN_ID , MotorType .kBrushless );
49
- CoralIntake = new SparkMax (Constants .ArmConstants .CORAL_INTAKE_CAN_ID , MotorType .kBrushless );
55
+ LeftCoral = new SparkMax (Constants .ArmConstants .LEFT_CORAL_CAN_ID , MotorType .kBrushless );
56
+ RightCoral = new SparkMax (Constants .ArmConstants .RIGHT_CORAL_CAN_ID , MotorType .kBrushless );
57
+
58
+ leftLiftEncoder = LeftLift .getEncoder ();
59
+
60
+ pidController = LeftLift .getClosedLoopController ();
50
61
51
62
// The idle mode of the coral intake and lift motors are set to brake to prevent them from
52
63
// continuing to move after the movement is halted. The algae config idle mode is set to
53
64
// coast due to the motors being in control of flywheels, meaning that the flywheels will
54
65
// slowly spin to a halt rather than fully stopping immediately.
55
66
SparkMaxConfig liftConfig = new SparkMaxConfig ();
56
67
liftConfig .idleMode (IdleMode .kBrake );
57
- SparkMaxConfig algaeConfig = new SparkMaxConfig ();
58
- algaeConfig .idleMode (IdleMode .kCoast );
68
+ liftConfig .closedLoop .pid (0.1 , 0 , 0 );
69
+ liftConfig .closedLoop .feedbackSensor (FeedbackSensor .kPrimaryEncoder );
70
+
59
71
SparkMaxConfig coralConfig = new SparkMaxConfig ();
60
72
coralConfig .idleMode (IdleMode .kBrake );
61
- liftConfig .follow (Constants .ArmConstants .LEFT_LIFT_CAN_ID );
62
- algaeConfig .follow (Constants .ArmConstants .LEFT_ALGAE_CAN_ID );
73
+
74
+ liftConfig .follow (Constants .ArmConstants .LEFT_LIFT_CAN_ID , true );
75
+ coralConfig .follow (Constants .ArmConstants .LEFT_CORAL_CAN_ID , true );
63
76
64
77
LeftLift .configure (liftConfig , com .revrobotics .spark .SparkBase .ResetMode .kResetSafeParameters , PersistMode .kPersistParameters );
65
78
RightLift .configure (liftConfig , com .revrobotics .spark .SparkBase .ResetMode .kResetSafeParameters , PersistMode .kPersistParameters );
66
- LeftAlgae .configure (algaeConfig , com .revrobotics .spark .SparkBase .ResetMode .kResetSafeParameters , PersistMode .kPersistParameters );
67
- RightAlgae .configure (algaeConfig , com .revrobotics .spark .SparkBase .ResetMode .kResetSafeParameters , PersistMode .kPersistParameters );
68
- CoralIntake .configure (coralConfig , com .revrobotics .spark .SparkBase .ResetMode .kResetSafeParameters , PersistMode .kPersistParameters );
79
+ LeftCoral .configure (coralConfig , com .revrobotics .spark .SparkBase .ResetMode .kResetSafeParameters , PersistMode .kPersistParameters );
80
+ RightCoral .configure (coralConfig , com .revrobotics .spark .SparkBase .ResetMode .kResetSafeParameters , PersistMode .kPersistParameters );
69
81
}
70
82
71
83
@ Override
@@ -75,15 +87,17 @@ public void initSendable(SendableBuilder builder) {
75
87
// as they are following them. As such, we only get the speed of the
76
88
// leader, the LeftMotor. The right motor will be spinning in the opposite direction though.
77
89
builder .addDoubleProperty ("Lift" , () -> LeftLift .get (), (armSpeed ) -> LeftLift .set (armSpeed ));
78
- builder .addDoubleProperty ("Algae" , () -> LeftAlgae .get (), (intakeSpeed ) -> LeftAlgae .set (intakeSpeed ));
79
- builder .addDoubleProperty ("CoralIntake" , () -> CoralIntake .get (), (intakeSpeed ) -> CoralIntake .set (intakeSpeed ));
90
+ builder .addDoubleProperty ("Coral" , () -> LeftCoral .get (), (intakeSpeed ) -> LeftCoral .set (intakeSpeed ));
80
91
initSendable (builder );
81
92
}
82
93
83
94
@ Override
84
95
public void periodic () {
85
-
86
-
96
+ //pidController.setReference(input.getDesiredPosition(), ControlType.kPosition); --> possible other control scheme
97
+ LeftLift .set (input .getArmMovement ());
98
+ if (input .isCoralIntakeActivated ()) {
99
+ LeftCoral .set (Constants .ArmConstants .CORAL_INTAKE_SPEED );
100
+ }
87
101
}
88
102
89
103
}
0 commit comments