Skip to content

Commit 9a578ee

Browse files
committed
Saving state of working drive
We temporarily altered the configs of the drive motors, and we ended up changing the follower configurations to 2 differential drives, with one being the "follower" differential drive. - Movement for the differential drive current functions properly - We changed clamped speeds of the turning and moving - The speed values still are subject to change
1 parent 885a453 commit 9a578ee

File tree

3 files changed

+58
-22
lines changed

3 files changed

+58
-22
lines changed

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

+5-6
Original file line numberDiff line numberDiff line change
@@ -84,10 +84,10 @@ public enum DriveType {
8484
* <p> This list will be null if we are using a differential drive. </p>
8585
*/
8686
public enum WheelIndex {
87-
FRONT_LEFT(0),
88-
FRONT_RIGHT(1),
89-
BACK_RIGHT(2),
90-
BACK_LEFT(3);
87+
FRONT_LEFT(2),
88+
FRONT_RIGHT(3),
89+
BACK_RIGHT(0),
90+
BACK_LEFT(1);
9191

9292
public final int label;
9393

@@ -163,7 +163,6 @@ public static class ArmConstants {
163163
public static final int RIGHT_LIFT_CAN_ID = 21;
164164
public static final int LEFT_CORAL_CAN_ID = 22;
165165
public static final int RIGHT_CORAL_CAN_ID = 23;
166-
public static final int ALGAE_INTAKE_CAN_ID = 24;
167166

168167
/**
169168
* The heights of each stage will be in terms of rotations, which need to updated with testing.
@@ -173,7 +172,7 @@ public static class ArmConstants {
173172
public static final double LIFT_HEIGHT_2 = 2;
174173
public static final double LIFT_HEIGHT_3 = 3;
175174

176-
public static final double LIFT_SPEED = 1.0;
175+
public static final double LIFT_SPEED = 0.8;
177176
public static final double CORAL_INTAKE_SPEED = 0.3;
178177
}
179178

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

+52-15
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@ public class DriveSubsystem extends SubsystemBase {
3434
private double maxTurnSpeed;
3535
private DriveType driveType;
3636
private DifferentialDrive differentialDrive;
37+
private DifferentialDrive followDifferentialDrive;
3738

3839
/**
3940
* <p> The list of PWM Spark Max motor controllers controlling the differential
@@ -97,6 +98,8 @@ public class DriveSubsystem extends SubsystemBase {
9798
private double clampedXAxis;
9899
private double clampedYAxis;
99100
private double clampedTurn;
101+
private double currentYAxis;
102+
private double currentTurn;
100103

101104
/**
102105
* Intended to be owned by the RobotContainer and to be used by
@@ -129,16 +132,29 @@ public DriveSubsystem(InputSubsystem inputSubsystem, DriveType driveType) {
129132
// will be moving in the opposite directions.
130133
SparkMaxConfig commonConfig = new SparkMaxConfig();
131134
commonConfig.idleMode(IdleMode.kBrake);
132-
SparkMaxConfig leftConfig = new SparkMaxConfig();
133-
SparkMaxConfig rightConfig = new SparkMaxConfig();
134-
leftConfig.follow(FRONT_LEFT_ID).apply(commonConfig);
135-
rightConfig.follow(FRONT_RIGHT_ID).apply(commonConfig);
136-
differentialDriveMotors.get(DriveConstants.WheelIndex.FRONT_LEFT.label).configure(leftConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
137-
differentialDriveMotors.get(DriveConstants.WheelIndex.BACK_LEFT.label).configure(leftConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
138-
differentialDriveMotors.get(DriveConstants.WheelIndex.FRONT_RIGHT.label).configure(rightConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
139-
differentialDriveMotors.get(DriveConstants.WheelIndex.BACK_RIGHT.label).configure(rightConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
140-
differentialDrive = new DifferentialDrive(differentialDriveMotors.get(FRONT_LEFT_ID),
141-
differentialDriveMotors.get(FRONT_RIGHT_ID));
135+
SparkMaxConfig leftFollowerConfig = new SparkMaxConfig();
136+
SparkMaxConfig rightFollowerConfig = new SparkMaxConfig();
137+
138+
SparkMaxConfig tempConfig = new SparkMaxConfig();
139+
tempConfig.idleMode(IdleMode.kBrake);
140+
tempConfig.inverted(true);
141+
142+
leftFollowerConfig.follow(FRONT_LEFT_ID, true).apply(commonConfig);
143+
rightFollowerConfig.follow(FRONT_RIGHT_ID).apply(commonConfig);
144+
differentialDriveMotors.get(2).configure(commonConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
145+
differentialDriveMotors.get(3).configure(commonConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
146+
differentialDriveMotors.get(0).configure(tempConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
147+
differentialDriveMotors.get(1).configure(tempConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
148+
149+
// differentialDriveMotors.get(DriveConstants.WheelIndex.FRONT_LEFT.label).configure(commonConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
150+
// differentialDriveMotors.get(DriveConstants.WheelIndex.BACK_LEFT.label).configure(commonConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
151+
// differentialDriveMotors.get(DriveConstants.WheelIndex.FRONT_RIGHT.label).configure(commonConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
152+
// differentialDriveMotors.get(DriveConstants.WheelIndex.BACK_RIGHT.label).configure(commonConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
153+
154+
differentialDrive = new DifferentialDrive(differentialDriveMotors.get(2),
155+
differentialDriveMotors.get(0));
156+
followDifferentialDrive = new DifferentialDrive(differentialDriveMotors.get(3),
157+
differentialDriveMotors.get(1));
142158
break;
143159
}
144160
case SWERVE_DRIVE: {
@@ -289,8 +305,8 @@ void disable() {
289305
*/
290306
public void drive(double xAxis, double yAxis, double turn) {
291307
clampedXAxis = MathUtil.clamp(xAxis, -1.0, 1.0);
292-
clampedYAxis = MathUtil.clamp(yAxis, -1.0, 1.0);
293-
clampedTurn = MathUtil.clamp(turn, -1.0, 1.0);
308+
clampedYAxis = MathUtil.clamp(yAxis, -0.8, 0.8);
309+
clampedTurn = MathUtil.clamp(turn, -0.5, 0.5);
294310
}
295311

296312
/**
@@ -300,13 +316,13 @@ public void drive(double xAxis, double yAxis, double turn) {
300316
public void periodic() {
301317
switch (driveType) {
302318
case DIFFERENTIAL_DRIVE:
303-
304319
// If the joystick is being moved, then the shuffleboard will be
305320
// prevented from setting anything. This is to prevent the
306321
// problem of the arcadeDrive() overriding the values that the
307322
// shuffleboard sets.
308323
if (DriverStation.isTeleopEnabled()) {
309324
if (input.getForwardBack() != 0 || input.getTurn() != 0) {
325+
System.out.println(input.getForwardBack());
310326
this.drive(input.getLeftRight(), input.getForwardBack(), input.getTurn());
311327
canShuffleBoardActuate = false;
312328
} else if (!canShuffleBoardActuate) {
@@ -333,11 +349,32 @@ public void periodic() {
333349
if (Math.abs(clampedYAxis) < Constants.MathConstants.EPSILON &&
334350
Math.abs(clampedTurn) < Constants.MathConstants.EPSILON) {
335351
differentialDrive.arcadeDrive(0.0, 0.0);
352+
followDifferentialDrive.arcadeDrive(0.0, 0.0);
353+
System.out.println("stopped.");
336354
} else {
337-
differentialDrive.arcadeDrive(clampedYAxis, clampedTurn);
355+
// Limit the amount that the yAxis and turn values are changed
356+
// by calculating the difference between the target value, clampedYAxis
357+
// and the current value, currentYAxis. Then clamping the difference to
358+
// a threshold and adding the clamped difference to the current value.
359+
double diffYAxis = clampedYAxis - currentYAxis;
360+
diffYAxis = MathUtil.clamp(diffYAxis, -0.05, 0.05);
361+
currentYAxis += diffYAxis;
362+
363+
double diffTurn = clampedTurn - currentTurn;
364+
diffTurn = MathUtil.clamp(diffTurn, -0.25, 0.25);
365+
currentTurn += diffTurn;
366+
367+
differentialDrive.arcadeDrive(currentYAxis, currentTurn);
368+
followDifferentialDrive.arcadeDrive(currentYAxis, currentTurn);
369+
System.out.println("y-axis: " + clampedYAxis + " turn: " + clampedTurn);
338370
}
339371
}
340-
372+
//differentialDriveMotors.get(2).set(0.2);
373+
//differentialDriveMotors.get(3).set(0.2);
374+
375+
// differentialDriveMotors.get(0).set(0.2);
376+
// differentialDriveMotors.get(1).set(0.2);
377+
341378
break;
342379
case SWERVE_DRIVE:
343380
// Convert the human input into a ChassisSpeeds object giving us

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

+1-1
Original file line numberDiff line numberDiff line change
@@ -150,7 +150,7 @@ public double getForwardBack() {
150150
MathUtil.applyDeadband(joystickForwardBack, Constants.OperatorConstants.JOYSTICK_DEAD_ZONE);
151151

152152
forwardBack = MathUtil.clamp(forwardBack, -1.0, 1.0);
153-
153+
154154
return m_yspeedLimiter.calculate(forwardBack);
155155
}
156156

0 commit comments

Comments
 (0)