Skip to content

Commit be3feb0

Browse files
committed
2 parents e75a246 + e6591b8 commit be3feb0

File tree

4 files changed

+157
-33
lines changed

4 files changed

+157
-33
lines changed

src/main/java/frc/robot/Constants.java

+13-4
Original file line numberDiff line numberDiff line change
@@ -161,11 +161,20 @@ public static class ArmConstants {
161161
// CAN IDs; this way, we can avoid any conflicts.
162162
public static final int LEFT_LIFT_CAN_ID = 20;
163163
public static final int RIGHT_LIFT_CAN_ID = 21;
164-
public static final int LEFT_ALGAE_CAN_ID = 22;
165-
public static final int RIGHT_ALGAE_CAN_ID = 23;
166-
public static final int CORAL_INTAKE_CAN_ID = 24;
164+
public static final int LEFT_CORAL_CAN_ID = 22;
165+
public static final int RIGHT_CORAL_CAN_ID = 23;
166+
public static final int ALGAE_INTAKE_CAN_ID = 24;
167+
168+
/**
169+
* The heights of each stage will be in terms of rotations, which need to updated with testing.
170+
*/
171+
public static final double DEFAULT_HEIGHT = 0;
172+
public static final double LIFT_HEIGHT_1 = 1;
173+
public static final double LIFT_HEIGHT_2 = 2;
174+
public static final double LIFT_HEIGHT_3 = 3;
167175

168-
public static final double LIFT_SPEED = 0;
176+
public static final double LIFT_SPEED = 1.0;
177+
public static final double CORAL_INTAKE_SPEED = 0.3;
169178
}
170179

171180
}

src/main/java/frc/robot/RobotContainer.java

+2
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
import frc.robot.Constants.DriveConstants.DriveType;
1010
import frc.robot.commands.Autos;
1111
import frc.robot.commands.ExampleCommand;
12+
import frc.robot.subsystems.ArmSubsystem;
1213
import frc.robot.subsystems.DriveSubsystem;
1314
import frc.robot.subsystems.ExampleSubsystem;
1415
import frc.robot.subsystems.InputSubsystem;
@@ -31,6 +32,7 @@ public class RobotContainer {
3132
private final ExampleSubsystem m_exampleSubsystem = new ExampleSubsystem();
3233
private final InputSubsystem m_inputSubsystem = new InputSubsystem();
3334
private final DriveSubsystem m_driveSubsystem = new DriveSubsystem(m_inputSubsystem, DriveType.DIFFERENTIAL_DRIVE);
35+
private final ArmSubsystem m_armSubsystem = new ArmSubsystem(m_inputSubsystem);
3436

3537
// Replace with CommandPS4Controller or CommandJoystick if needed
3638
private final CommandXboxController m_driverController = new CommandXboxController(
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,15 @@
11
package frc.robot.subsystems;
22

3+
import com.revrobotics.RelativeEncoder;
34
import com.revrobotics.servohub.ServoHub.ResetMode;
5+
import com.revrobotics.spark.SparkClosedLoopController;
46
import com.revrobotics.spark.SparkMax;
7+
import com.revrobotics.spark.SparkBase.ControlType;
58
import com.revrobotics.spark.SparkBase.PersistMode;
69
import com.revrobotics.spark.SparkLowLevel.MotorType;
10+
import com.revrobotics.spark.config.ClosedLoopConfig;
711
import com.revrobotics.spark.config.SparkMaxConfig;
12+
import com.revrobotics.spark.config.ClosedLoopConfig.FeedbackSensor;
813
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
914

1015
import edu.wpi.first.util.sendable.SendableBuilder;
@@ -14,6 +19,8 @@
1419

1520
public class ArmSubsystem extends SubsystemBase {
1621

22+
private InputSubsystem input;
23+
1724
/**
1825
* Controls the left motor of the 4 bar lift.
1926
*/
@@ -26,46 +33,51 @@ public class ArmSubsystem extends SubsystemBase {
2633
private SparkMax RightLift;
2734

2835
/**
29-
* Left algae intake motor.
36+
* Left coral intake motor.
3037
*/
31-
private SparkMax LeftAlgae;
38+
private SparkMax LeftCoral;
3239

3340
/**
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.
3643
*/
37-
private SparkMax RightAlgae;
44+
private SparkMax RightCoral;
3845

39-
/**
40-
* Coral intake motor
41-
*/
42-
private SparkMax CoralIntake;
4346

44-
public ArmSubsystem() {
47+
private RelativeEncoder leftLiftEncoder;
48+
49+
private SparkClosedLoopController pidController;
50+
51+
public ArmSubsystem(InputSubsystem inputSubsystem) {
52+
input = inputSubsystem;
4553
LeftLift = new SparkMax(Constants.ArmConstants.LEFT_LIFT_CAN_ID, MotorType.kBrushless);
4654
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();
5061

5162
// The idle mode of the coral intake and lift motors are set to brake to prevent them from
5263
// continuing to move after the movement is halted. The algae config idle mode is set to
5364
// coast due to the motors being in control of flywheels, meaning that the flywheels will
5465
// slowly spin to a halt rather than fully stopping immediately.
5566
SparkMaxConfig liftConfig = new SparkMaxConfig();
5667
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+
5971
SparkMaxConfig coralConfig = new SparkMaxConfig();
6072
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);
6376

6477
LeftLift.configure(liftConfig, com.revrobotics.spark.SparkBase.ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
6578
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);
6981
}
7082

7183
@Override
@@ -75,15 +87,17 @@ public void initSendable(SendableBuilder builder) {
7587
// as they are following them. As such, we only get the speed of the
7688
// leader, the LeftMotor. The right motor will be spinning in the opposite direction though.
7789
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));
8091
initSendable(builder);
8192
}
8293

8394
@Override
8495
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+
}
87101
}
88102

89103
}

src/main/java/frc/robot/subsystems/InputSubsystem.java

+104-5
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
package frc.robot.subsystems;
22

3+
import com.revrobotics.RelativeEncoder;
4+
35
import edu.wpi.first.math.MathUtil;
46
import edu.wpi.first.math.filter.SlewRateLimiter;
57
import edu.wpi.first.util.sendable.SendableBuilder;
@@ -70,11 +72,14 @@ public class InputSubsystem extends SubsystemBase {
7072
*/
7173
private double lastCheckTimeSeconds;
7274

75+
int currentHeight;
76+
7377
public InputSubsystem() {
7478
xboxController = null;
7579
mainJoystick = null;
7680
secondaryJoystick = null;
7781
lastCheckTimeSeconds = Timer.getFPGATimestamp() - JOYSTICK_POLLING_INTERVAL_SECONDS; // Force initial check
82+
currentHeight = 0;
7883
}
7984

8085
/**
@@ -176,11 +181,105 @@ public double getTurn() {
176181
return m_rotLimiter.calculate(turn);
177182
}
178183

179-
180-
// public double getLiftSpeed() {
181-
// double liftOut = (xboxController != null && xboxController.isConnected() && xboxController.getBButton() ? Constants.ArmConstants.LIFT_SPEED : 0);
182-
// return liftOut;
183-
// }
184+
/**
185+
* A function to return the number of desired rotations of the lift motors based on user input.
186+
* - Stage 0 represents base height of the lift when idle, which is equal to the height of the trough.
187+
* - Each additional stage (up to the top) represents the next level of the coral branch.
188+
* - Lift stage 1 -> coral level 2
189+
* - Lift stage 2 -> coral level 3
190+
* - Lift stage 3 -> coral level 4
191+
*
192+
* - Each time the user presses one of the lift triggering buttons,
193+
* the lift will automatically transition between the stages.
194+
*/
195+
public double getDesiredPosition() {
196+
double[] liftHeights = {
197+
Constants.ArmConstants.DEFAULT_HEIGHT,
198+
Constants.ArmConstants.LIFT_HEIGHT_1,
199+
Constants.ArmConstants.LIFT_HEIGHT_2,
200+
Constants.ArmConstants.LIFT_HEIGHT_3};
201+
202+
203+
if(xboxController != null &&xboxController.isConnected() == true) {
204+
if(xboxController.getBButtonPressed() && currentHeight <= liftHeights.length) {
205+
currentHeight++;
206+
} else if(xboxController.getAButtonPressed() && currentHeight >= 0) {
207+
currentHeight--;
208+
}
209+
}
210+
211+
if(mainJoystick != null && mainJoystick.isConnected() && secondaryJoystick != null && secondaryJoystick.isConnected()) {
212+
if(secondaryJoystick.getRawButtonPressed(6) && currentHeight <= liftHeights.length) {
213+
currentHeight++;
214+
} else if(secondaryJoystick.getRawButtonPressed(4) && currentHeight >= 0) {
215+
currentHeight--;
216+
}
217+
} else if(mainJoystick != null && mainJoystick.isConnected()) {
218+
if(mainJoystick.getRawButtonPressed(6) && currentHeight <= liftHeights.length) {
219+
currentHeight++;
220+
} else if(mainJoystick.getRawButtonPressed(4) && currentHeight >= 0) {
221+
currentHeight--;
222+
}
223+
}
224+
225+
return liftHeights[currentHeight];
226+
}
227+
228+
/**
229+
* This is a separte method of controlling the lift of the ArmSubsystem.
230+
* It will move the lift at a constant speed as long as the player is holding down the desired movement button.
231+
* The speed of the lift is dependent on the constant LIFT_SPEED in Constants.java.
232+
*/
233+
public double getArmMovement() {
234+
if(xboxController != null &&xboxController.isConnected() == true) {
235+
if(xboxController.getPOV() > -10 && xboxController.getPOV() < 10) {
236+
return Constants.ArmConstants.LIFT_SPEED;
237+
} else if (xboxController.getPOV() > 170 && xboxController.getPOV() < 190) {
238+
return Constants.ArmConstants.LIFT_SPEED * -1;
239+
}
240+
}
241+
242+
if(mainJoystick != null && mainJoystick.isConnected() && secondaryJoystick != null && secondaryJoystick.isConnected()) {
243+
if(secondaryJoystick.getRawButtonPressed(5)) {
244+
return Constants.ArmConstants.LIFT_SPEED;
245+
} else if(secondaryJoystick.getRawButtonPressed(3)) {
246+
return Constants.ArmConstants.LIFT_SPEED * -1;
247+
}
248+
} else if(mainJoystick != null && mainJoystick.isConnected()) {
249+
if(mainJoystick.getRawButtonPressed(5)) {
250+
return Constants.ArmConstants.LIFT_SPEED;
251+
} else if(mainJoystick.getRawButtonPressed(3)) {
252+
return Constants.ArmConstants.LIFT_SPEED * -1;
253+
}
254+
}
255+
256+
return 0;
257+
}
258+
259+
260+
/**
261+
* Returns whether or not the coral flywheels should be moving based on whether or not the player
262+
* is pressing the right trigger/right bumper button.
263+
*/
264+
public boolean isCoralIntakeActivated() {
265+
if(xboxController != null &&xboxController.isConnected() == true) {
266+
if(xboxController.getRightBumperButton()) {
267+
return true;
268+
}
269+
}
270+
271+
if(mainJoystick != null && mainJoystick.isConnected() && secondaryJoystick != null && secondaryJoystick.isConnected()) {
272+
if(secondaryJoystick.getTrigger()) {
273+
return true;
274+
}
275+
} else if(mainJoystick != null && mainJoystick.isConnected()) {
276+
if(mainJoystick.getTrigger()) {
277+
return true;
278+
}
279+
}
280+
281+
return false;
282+
}
184283

185284
/**
186285
* A function called every few seconds meant to detect when xbox controllers

0 commit comments

Comments
 (0)