@@ -34,6 +34,7 @@ public class DriveSubsystem extends SubsystemBase {
34
34
private double maxTurnSpeed ;
35
35
private DriveType driveType ;
36
36
private DifferentialDrive differentialDrive ;
37
+ private DifferentialDrive followDifferentialDrive ;
37
38
38
39
/**
39
40
* <p> The list of PWM Spark Max motor controllers controlling the differential
@@ -97,6 +98,8 @@ public class DriveSubsystem extends SubsystemBase {
97
98
private double clampedXAxis ;
98
99
private double clampedYAxis ;
99
100
private double clampedTurn ;
101
+ private double currentYAxis ;
102
+ private double currentTurn ;
100
103
101
104
/**
102
105
* Intended to be owned by the RobotContainer and to be used by
@@ -129,16 +132,29 @@ public DriveSubsystem(InputSubsystem inputSubsystem, DriveType driveType) {
129
132
// will be moving in the opposite directions.
130
133
SparkMaxConfig commonConfig = new SparkMaxConfig ();
131
134
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 ));
142
158
break ;
143
159
}
144
160
case SWERVE_DRIVE : {
@@ -289,8 +305,8 @@ void disable() {
289
305
*/
290
306
public void drive (double xAxis , double yAxis , double turn ) {
291
307
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 );
294
310
}
295
311
296
312
/**
@@ -300,13 +316,13 @@ public void drive(double xAxis, double yAxis, double turn) {
300
316
public void periodic () {
301
317
switch (driveType ) {
302
318
case DIFFERENTIAL_DRIVE :
303
-
304
319
// If the joystick is being moved, then the shuffleboard will be
305
320
// prevented from setting anything. This is to prevent the
306
321
// problem of the arcadeDrive() overriding the values that the
307
322
// shuffleboard sets.
308
323
if (DriverStation .isTeleopEnabled ()) {
309
324
if (input .getForwardBack () != 0 || input .getTurn () != 0 ) {
325
+ System .out .println (input .getForwardBack ());
310
326
this .drive (input .getLeftRight (), input .getForwardBack (), input .getTurn ());
311
327
canShuffleBoardActuate = false ;
312
328
} else if (!canShuffleBoardActuate ) {
@@ -333,11 +349,32 @@ public void periodic() {
333
349
if (Math .abs (clampedYAxis ) < Constants .MathConstants .EPSILON &&
334
350
Math .abs (clampedTurn ) < Constants .MathConstants .EPSILON ) {
335
351
differentialDrive .arcadeDrive (0.0 , 0.0 );
352
+ followDifferentialDrive .arcadeDrive (0.0 , 0.0 );
353
+ System .out .println ("stopped." );
336
354
} 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 );
338
370
}
339
371
}
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
+
341
378
break ;
342
379
case SWERVE_DRIVE :
343
380
// Convert the human input into a ChassisSpeeds object giving us
0 commit comments