Skip to content

Commit 25fe42a

Browse files
committed
Mars Climate Orbiter 🤦
Assumed wheel radius value was in inches, so converted it to meters... problem is it was already in meters. Oops. This made the code think the wheel was tiny, hence needing to apply huge angular velocity to make the chassis run at the expected speed. Yeah... modified: src/main/deploy/pathplanner/paths/Consistancy Test.path modified: src/main/java/frc/robot/Constants.java modified: src/main/java/frc/robot/commands/ChoreoAutoController.java modified: src/main/java/frc/robot/commands/DriveCommands.java modified: src/main/java/frc/robot/subsystems/drive/Drive.java modified: src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java modified: src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java modified: src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java modified: src/main/java/frc/robot/subsystems/drive/SwerveConstants.java renamed: vendordeps/ReduxLib-2025.0.0.json -> vendordeps/ReduxLib-2025.0.1.json
1 parent 15e34bd commit 25fe42a

File tree

10 files changed

+45
-45
lines changed

10 files changed

+45
-45
lines changed

src/main/deploy/pathplanner/paths/Consistancy Test.path

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -8,8 +8,8 @@
88
},
99
"prevControl": null,
1010
"nextControl": {
11-
"x": 9.29,
12-
"y": 6.22
11+
"x": 9.141987426415538,
12+
"y": 6.318675049056306
1313
},
1414
"isLocked": false,
1515
"linkedName": null
@@ -33,7 +33,7 @@
3333
"pointTowardsZones": [],
3434
"eventMarkers": [],
3535
"globalConstraints": {
36-
"maxVelocity": 1.0,
36+
"maxVelocity": 0.5,
3737
"maxAcceleration": 1.0,
3838
"maxAngularVelocity": 540.0,
3939
"maxAngularAcceleration": 720.0,

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

Lines changed: 6 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -139,10 +139,6 @@ public static final class DrivebaseConstants {
139139
public static final double kMaxLinearAccel = 4.0; // m/s/s
140140
public static final double kMaxAngularAccel = Units.degreesToRadians(720);
141141

142-
// Drive and Turn PID constants used for PathPlanner
143-
public static final PIDConstants drivePID = new PIDConstants(5.0, 0.0, 0.0);
144-
public static final PIDConstants steerPID = new PIDConstants(5.0, 0.0, 0.0);
145-
146142
// Hold time on motor brakes when disabled
147143
public static final double kWheelLockTime = 10; // seconds
148144

@@ -239,10 +235,9 @@ public static class OperatorConstants {
239235
/** Autonomous Action Constants ****************************************** */
240236
public static final class AutoConstants {
241237

242-
// PathPlanner Translation PID constants
243-
public static final PIDConstants kAutoDrivePID = new PIDConstants(0.7, 0, 0);
244-
// PathPlanner Rotation PID constants
245-
public static final PIDConstants kAutoSteerPID = new PIDConstants(0.4, 0, 0.01);
238+
// Drive and Turn PID constants used for PathPlanner
239+
public static final PIDConstants kPPdrivePID = new PIDConstants(5.0, 0.0, 0.0);
240+
public static final PIDConstants kPPsteerPID = new PIDConstants(5.0, 0.0, 0.0);
246241

247242
// PathPlanner Config constants
248243
public static final RobotConfig kPathPlannerConfig =
@@ -261,6 +256,9 @@ public static final class AutoConstants {
261256
// Alternatively, we can build this from the PathPlanner GUI:
262257
// public static final RobotConfig kPathPlannerConfig = RobotConfig.fromGUISettings();
263258

259+
// Drive and Turn PID constants used for Chorep
260+
public static final PIDConstants kChoreoDrivePID = new PIDConstants(10.0, 0.0, 0.0);
261+
public static final PIDConstants kChoreoSteerPID = new PIDConstants(7.5, 0.0, 0.0);
264262
}
265263

266264
/** Vision Constants (Assuming PhotonVision) ***************************** */

src/main/java/frc/robot/commands/ChoreoAutoController.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -27,11 +27,11 @@
2727
public class ChoreoAutoController implements Consumer<SwerveSample> {
2828
private final Drive drive; // drive subsystem
2929
private final PIDController xController =
30-
new PIDController(kAutoDrivePID.kP, 0.0, kAutoDrivePID.kD);
30+
new PIDController(kChoreoDrivePID.kP, kChoreoDrivePID.kI, kChoreoDrivePID.kD);
3131
private final PIDController yController =
32-
new PIDController(kAutoDrivePID.kP, 0.0, kAutoDrivePID.kD);
32+
new PIDController(kChoreoDrivePID.kP, kChoreoDrivePID.kI, kChoreoDrivePID.kD);
3333
private final PIDController headingController =
34-
new PIDController(kAutoSteerPID.kP, 0.0, kAutoSteerPID.kD);
34+
new PIDController(kChoreoSteerPID.kP, kChoreoSteerPID.kI, kChoreoSteerPID.kD);
3535

3636
public ChoreoAutoController(Drive drive) {
3737
this.drive = drive;

src/main/java/frc/robot/commands/DriveCommands.java

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030
import edu.wpi.first.wpilibj.Timer;
3131
import edu.wpi.first.wpilibj2.command.Command;
3232
import edu.wpi.first.wpilibj2.command.Commands;
33+
import frc.robot.Constants.AutoConstants;
3334
import frc.robot.Constants.DrivebaseConstants;
3435
import frc.robot.Constants.OperatorConstants;
3536
import frc.robot.subsystems.drive.Drive;
@@ -125,9 +126,9 @@ public static Command fieldRelativeDriveAtAngle(
125126
// Create PID controller
126127
ProfiledPIDController angleController =
127128
new ProfiledPIDController(
128-
DrivebaseConstants.steerPID.kP,
129-
DrivebaseConstants.steerPID.kI,
130-
DrivebaseConstants.steerPID.kD,
129+
AutoConstants.kPPsteerPID.kP,
130+
AutoConstants.kPPsteerPID.kI,
131+
AutoConstants.kPPsteerPID.kD,
131132
new TrapezoidProfile.Constraints(
132133
DrivebaseConstants.kMaxAngularSpeed, DrivebaseConstants.kMaxAngularAccel));
133134
angleController.enableContinuousInput(-Math.PI, Math.PI);

src/main/java/frc/robot/subsystems/drive/Drive.java

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -150,8 +150,7 @@ public Drive() {
150150
this::resetPose,
151151
this::getChassisSpeeds,
152152
(speeds, feedforwards) -> runVelocity(speeds),
153-
new PPHolonomicDriveController(
154-
DrivebaseConstants.drivePID, DrivebaseConstants.steerPID),
153+
new PPHolonomicDriveController(AutoConstants.kPPdrivePID, AutoConstants.kPPsteerPID),
155154
AutoConstants.kPathPlannerConfig,
156155
() -> DriverStation.getAlliance().orElse(Alliance.Blue) == Alliance.Red,
157156
this);

src/main/java/frc/robot/subsystems/drive/ModuleIOBlended.java

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,7 @@
5353
import edu.wpi.first.units.measure.Current;
5454
import edu.wpi.first.units.measure.Voltage;
5555
import frc.robot.Constants;
56-
import frc.robot.Constants.DrivebaseConstants;
56+
import frc.robot.Constants.AutoConstants;
5757
import frc.robot.util.PhoenixUtil;
5858
import frc.robot.util.SparkUtil;
5959
import java.util.Queue;
@@ -205,9 +205,9 @@ public ModuleIOBlended(int module) {
205205
.positionWrappingEnabled(true)
206206
.positionWrappingInputRange(turnPIDMinInput, turnPIDMaxInput)
207207
.pidf(
208-
DrivebaseConstants.steerPID.kP,
209-
DrivebaseConstants.steerPID.kI,
210-
DrivebaseConstants.steerPID.kD,
208+
AutoConstants.kPPsteerPID.kP,
209+
AutoConstants.kPPsteerPID.kI,
210+
AutoConstants.kPPsteerPID.kD,
211211
0.0);
212212
turnConfig
213213
.signals

src/main/java/frc/robot/subsystems/drive/ModuleIOSpark.java

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@
3737
import edu.wpi.first.math.MathUtil;
3838
import edu.wpi.first.math.filter.Debouncer;
3939
import edu.wpi.first.math.geometry.Rotation2d;
40-
import frc.robot.Constants.DrivebaseConstants;
40+
import frc.robot.Constants.AutoConstants;
4141
import java.util.Queue;
4242
import java.util.function.DoubleSupplier;
4343

@@ -135,9 +135,9 @@ public ModuleIOSpark(int module) {
135135
.closedLoop
136136
.feedbackSensor(FeedbackSensor.kPrimaryEncoder)
137137
.pidf(
138-
DrivebaseConstants.drivePID.kP,
139-
DrivebaseConstants.drivePID.kI,
140-
DrivebaseConstants.drivePID.kD,
138+
AutoConstants.kPPdrivePID.kP,
139+
AutoConstants.kPPdrivePID.kI,
140+
AutoConstants.kPPdrivePID.kD,
141141
0.0);
142142
driveConfig
143143
.signals
@@ -175,9 +175,9 @@ public ModuleIOSpark(int module) {
175175
.positionWrappingEnabled(true)
176176
.positionWrappingInputRange(turnPIDMinInput, turnPIDMaxInput)
177177
.pidf(
178-
DrivebaseConstants.steerPID.kP,
179-
DrivebaseConstants.steerPID.kI,
180-
DrivebaseConstants.steerPID.kD,
178+
AutoConstants.kPPsteerPID.kP,
179+
AutoConstants.kPPsteerPID.kI,
180+
AutoConstants.kPPsteerPID.kD,
181181
0.0);
182182
turnConfig
183183
.signals

src/main/java/frc/robot/subsystems/drive/ModuleIOSparkCANcoder.java

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -42,7 +42,7 @@
4242
import edu.wpi.first.math.util.Units;
4343
import edu.wpi.first.units.measure.Angle;
4444
import edu.wpi.first.units.measure.AngularVelocity;
45-
import frc.robot.Constants.DrivebaseConstants;
45+
import frc.robot.Constants.AutoConstants;
4646
import java.util.Queue;
4747
import java.util.function.DoubleSupplier;
4848

@@ -155,9 +155,9 @@ public ModuleIOSparkCANcoder(int module) {
155155
.closedLoop
156156
.feedbackSensor(FeedbackSensor.kPrimaryEncoder)
157157
.pidf(
158-
DrivebaseConstants.drivePID.kP,
159-
DrivebaseConstants.drivePID.kI,
160-
DrivebaseConstants.drivePID.kD,
158+
AutoConstants.kPPdrivePID.kP,
159+
AutoConstants.kPPdrivePID.kI,
160+
AutoConstants.kPPdrivePID.kD,
161161
0.0);
162162
driveConfig
163163
.signals
@@ -195,9 +195,9 @@ public ModuleIOSparkCANcoder(int module) {
195195
.positionWrappingEnabled(true)
196196
.positionWrappingInputRange(turnPIDMinInput, turnPIDMaxInput)
197197
.pidf(
198-
DrivebaseConstants.steerPID.kP,
199-
DrivebaseConstants.steerPID.kI,
200-
DrivebaseConstants.steerPID.kD,
198+
AutoConstants.kPPsteerPID.kP,
199+
AutoConstants.kPPsteerPID.kI,
200+
AutoConstants.kPPsteerPID.kD,
201201
0.0);
202202
turnConfig
203203
.signals

src/main/java/frc/robot/subsystems/drive/SwerveConstants.java

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,7 @@ public class SwerveConstants {
3333
public static final double kDriveGearRatio;
3434
public static final double kSteerGearRatio;
3535
public static final double kWheelRadiusInches;
36+
public static final double kWheelRadiusMeters;
3637
public static final String kCANbusName;
3738
public static final int kPigeonId;
3839
public static final double kSteerInertia;
@@ -112,7 +113,8 @@ public class SwerveConstants {
112113
kCoupleRatio = TunerConstants.FrontLeft.CouplingGearRatio;
113114
kDriveGearRatio = TunerConstants.FrontLeft.DriveMotorGearRatio;
114115
kSteerGearRatio = TunerConstants.FrontLeft.SteerMotorGearRatio;
115-
kWheelRadiusInches = TunerConstants.FrontLeft.WheelRadius;
116+
kWheelRadiusMeters = TunerConstants.FrontLeft.WheelRadius;
117+
kWheelRadiusInches = Units.metersToInches(kWheelRadiusMeters);
116118
kCANbusName = TunerConstants.DrivetrainConstants.CANBusName;
117119
kPigeonId = TunerConstants.DrivetrainConstants.Pigeon2Id;
118120
kSteerInertia = TunerConstants.FrontLeft.SteerInertia;
@@ -197,6 +199,7 @@ public class SwerveConstants {
197199
kDriveGearRatio = YagslConstants.kDriveGearRatio;
198200
kSteerGearRatio = YagslConstants.kSteerGearRatio;
199201
kWheelRadiusInches = YagslConstants.kWheelRadiusInches;
202+
kWheelRadiusMeters = Units.inchesToMeters(kWheelRadiusInches);
200203
kCANbusName = YagslConstants.kCANbusName;
201204
kPigeonId = YagslConstants.kPigeonId;
202205
kSteerInertia = YagslConstants.kSteerInertia;
@@ -286,7 +289,6 @@ public class SwerveConstants {
286289
Math.max(
287290
Math.hypot(kBLXPosMeters, kBLYPosMeters), Math.hypot(kBRXPosMeters, kBRYPosMeters)));
288291
public static final double kDriveBaseRadiusInches = Units.metersToInches(kDriveBaseRadiusMeters);
289-
public static final double kWheelRadiusMeters = Units.inchesToMeters(kWheelRadiusInches);
290292

291293
// Are we on the CANivore or not?
292294
public static final double kOdometryFrequency =
Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
{
2-
"fileName": "ReduxLib-2025.0.0.json",
2+
"fileName": "ReduxLib-2025.0.1.json",
33
"name": "ReduxLib",
4-
"version": "2025.0.0",
4+
"version": "2025.0.1",
55
"frcYear": "2025",
66
"uuid": "151ecca8-670b-4026-8160-cdd2679ef2bd",
77
"mavenUrls": [
@@ -12,14 +12,14 @@
1212
{
1313
"groupId": "com.reduxrobotics.frc",
1414
"artifactId": "ReduxLib-java",
15-
"version": "2025.0.0"
15+
"version": "2025.0.1"
1616
}
1717
],
1818
"jniDependencies": [
1919
{
2020
"groupId": "com.reduxrobotics.frc",
2121
"artifactId": "ReduxLib-driver",
22-
"version": "2025.0.0",
22+
"version": "2025.0.1",
2323
"isJar": false,
2424
"skipInvalidPlatforms": true,
2525
"validPlatforms": [
@@ -36,7 +36,7 @@
3636
{
3737
"groupId": "com.reduxrobotics.frc",
3838
"artifactId": "ReduxLib-cpp",
39-
"version": "2025.0.0",
39+
"version": "2025.0.1",
4040
"libName": "ReduxLib",
4141
"headerClassifier": "headers",
4242
"sourcesClassifier": "sources",
@@ -54,7 +54,7 @@
5454
{
5555
"groupId": "com.reduxrobotics.frc",
5656
"artifactId": "ReduxLib-driver",
57-
"version": "2025.0.0",
57+
"version": "2025.0.1",
5858
"libName": "ReduxCore",
5959
"headerClassifier": "headers",
6060
"sharedLibrary": true,

0 commit comments

Comments
 (0)