Skip to content

Commit d2fc185

Browse files
authored
add aquila constants and move sim constants to Constants.java (#100)
* start * add constants * format * fix compilation? * here ya go * ill deal with that later 👍 * idk
1 parent e06f6f2 commit d2fc185

File tree

5 files changed

+140
-134
lines changed

5 files changed

+140
-134
lines changed

build.gradle

Lines changed: 42 additions & 41 deletions
Original file line numberDiff line numberDiff line change
@@ -151,48 +151,49 @@ tasks.withType(JavaCompile) {
151151
}
152152

153153
// Create version file
154-
project.compileJava.dependsOn(createVersionFile)
155-
gversion {
156-
srcDir = "src/main/java/"
157-
classPackage = "frc.robot"
158-
className = "BuildConstants"
159-
dateFormat = "yyyy-MM-dd HH:mm:ss z"
160-
timeZone = "America/New_York"
161-
indent = " "
162-
}
163-
154+
// project.compileJava.dependsOn(createVersionFile)
155+
// gversion {
156+
// srcDir = "src/main/java/"
157+
// classPackage = "frc.robot"
158+
// className = "BuildConstants"
159+
// dateFormat = "yyyy-MM-dd HH:mm:ss z"
160+
// timeZone = "America/New_York"
161+
// indent = " "
162+
// }
163+
164+
// TODO: set this shit up
164165
// Create commit with working changes on event branches
165-
task(eventDeploy) {
166-
doLast {
167-
if (project.gradle.startParameter.taskNames.any({ it.toLowerCase().contains("deploy") })) {
168-
def branchPrefix = "event"
169-
def branch = 'git branch --show-current'.execute().text.trim()
170-
def commitMessage = "Update at '${new Date().toString()}'"
171-
172-
if (branch.startsWith(branchPrefix)) {
173-
exec {
174-
workingDir(projectDir)
175-
executable 'git'
176-
args 'add', '-A'
177-
}
178-
exec {
179-
workingDir(projectDir)
180-
executable 'git'
181-
args 'commit', '-m', commitMessage
182-
ignoreExitValue = true
183-
}
184-
185-
println "Committed to branch: '$branch'"
186-
println "Commit message: '$commitMessage'"
187-
} else {
188-
println "Not on an event branch, skipping commit"
189-
}
190-
} else {
191-
println "Not running deploy task, skipping commit"
192-
}
193-
}
194-
}
195-
createVersionFile.dependsOn(eventDeploy)
166+
// task(eventDeploy) {
167+
// doLast {
168+
// if (project.gradle.startParameter.taskNames.any({ it.toLowerCase().contains("deploy") })) {
169+
// def branchPrefix = "event"
170+
// def branch = 'git branch --show-current'.execute().text.trim()
171+
// def commitMessage = "Update at '${new Date().toString()}'"
172+
173+
// if (branch.startsWith(branchPrefix)) {
174+
// exec {
175+
// workingDir(projectDir)
176+
// executable 'git'
177+
// args 'add', '-A'
178+
// }
179+
// exec {
180+
// workingDir(projectDir)
181+
// executable 'git'
182+
// args 'commit', '-m', commitMessage
183+
// ignoreExitValue = true
184+
// }
185+
186+
// println "Committed to branch: '$branch'"
187+
// println "Commit message: '$commitMessage'"
188+
// } else {
189+
// println "Not on an event branch, skipping commit"
190+
// }
191+
// } else {
192+
// println "Not running deploy task, skipping commit"
193+
// }
194+
// }
195+
// }
196+
// createVersionFile.dependsOn(eventDeploy)
196197

197198
// Spotless formatting
198199
project.compileJava.dependsOn(spotlessApply)

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

Lines changed: 83 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,10 @@
11
package frc.robot;
22

3+
import edu.wpi.first.math.system.plant.DCMotor;
34
import edu.wpi.first.math.util.Units;
5+
import frc.robot.subsystems.swerve.SwerveConstants.*;
6+
import frc.robot.subsystems.swerve.SwerveConstants.DriveConstants;
7+
import frc.robot.subsystems.swerve.SwerveConstants.ModuleConstants;
48

59
public final class Constants {
610

@@ -43,6 +47,85 @@ public static final class HardwareConstants {
4347
public static final double MIN_FALCON_DEADBAND = 0.001;
4448
}
4549

50+
/**
51+
* stores the constants and PID configs for chassis because we want an all-real simulation for the
52+
* chassis, the numbers are required to be considerably precise
53+
*/
54+
public class SimulationConstants {
55+
/**
56+
* numbers that needs to be changed to fit each robot TODO: change these numbers to match your
57+
* robot
58+
*/
59+
public static final double WHEEL_COEFFICIENT_OF_FRICTION = 0.95,
60+
ROBOT_MASS_KG = 60; // with bumpers
61+
62+
/** TODO: change motor type to match your robot */
63+
public static final DCMotor DRIVE_MOTOR = DCMotor.getKrakenX60(1),
64+
STEER_MOTOR = DCMotor.getFalcon500(1);
65+
66+
public static final double WHEEL_RADIUS_METERS = ModuleConstants.WHEEL_DIAMETER_METERS / 2.0,
67+
DRIVE_GEAR_RATIO = ModuleConstants.DRIVE_GEAR_RATIO,
68+
STEER_GEAR_RATIO = 11.0,
69+
TIME_ROBOT_STOP_ROTATING_SECONDS = 0.06,
70+
STEER_FRICTION_VOLTAGE = 0.12,
71+
DRIVE_FRICTION_VOLTAGE = ModuleConstants.DRIVE_S,
72+
DRIVE_INERTIA = 0.01,
73+
STEER_INERTIA = 0.01;
74+
75+
/* adjust current limit */
76+
public static final double DRIVE_CURRENT_LIMIT = ModuleConstants.DRIVE_STATOR_LIMIT;
77+
// public static final double STEER_CURRENT_LIMIT = ModuleConstants.ST;
78+
79+
/* equations that calculates some constants for the simulator (don't modify) */
80+
private static final double GRAVITY_CONSTANT = 9.81;
81+
public static final double DRIVE_BASE_RADIUS = DriveConstants.MODULE_TRANSLATIONS[0].getNorm(),
82+
/* friction_force = normal_force * coefficient_of_friction */
83+
MAX_FRICTION_ACCELERATION = GRAVITY_CONSTANT * WHEEL_COEFFICIENT_OF_FRICTION,
84+
MAX_FRICTION_FORCE_PER_MODULE =
85+
MAX_FRICTION_ACCELERATION * ROBOT_MASS_KG / DriveConstants.MODULE_TRANSLATIONS.length,
86+
/* force = torque / distance */
87+
MAX_PROPELLING_FORCE_NEWTONS =
88+
DRIVE_MOTOR.getTorque(DRIVE_CURRENT_LIMIT) * DRIVE_GEAR_RATIO / WHEEL_RADIUS_METERS,
89+
/* floor_speed = wheel_angular_velocity * wheel_radius */
90+
CHASSIS_MAX_VELOCITY =
91+
DRIVE_MOTOR.freeSpeedRadPerSec
92+
/ DRIVE_GEAR_RATIO
93+
* WHEEL_RADIUS_METERS, // calculate using choreo
94+
CHASSIS_MAX_ACCELERATION_MPS_SQ =
95+
Math.min(
96+
MAX_FRICTION_ACCELERATION, // cannot exceed max friction
97+
MAX_PROPELLING_FORCE_NEWTONS / ROBOT_MASS_KG),
98+
CHASSIS_MAX_ANGULAR_VELOCITY_RAD_PER_SEC = CHASSIS_MAX_VELOCITY / DRIVE_BASE_RADIUS,
99+
CHASSIS_MAX_ANGULAR_ACCELERATION_RAD_PER_SEC_SQ =
100+
CHASSIS_MAX_ACCELERATION_MPS_SQ / DRIVE_BASE_RADIUS,
101+
CHASSIS_FRICTIONAL_ANGULAR_ACCELERATION =
102+
CHASSIS_MAX_ANGULAR_VELOCITY_RAD_PER_SEC / TIME_ROBOT_STOP_ROTATING_SECONDS;
103+
104+
/* for collision detection in simulation */
105+
public static final double BUMPER_WIDTH_METERS = Units.inchesToMeters(34.5),
106+
BUMPER_LENGTH_METERS = Units.inchesToMeters(36),
107+
/* https://en.wikipedia.org/wiki/Friction#Coefficient_of_friction */
108+
BUMPER_COEFFICIENT_OF_FRICTION = 0.75,
109+
/* https://simple.wikipedia.org/wiki/Coefficient_of_restitution */
110+
BUMPER_COEFFICIENT_OF_RESTITUTION = 0.08;
111+
112+
/* Gyro Sim */
113+
public static final double GYRO_ANGULAR_ACCELERATION_THRESHOLD_SKIDDING_RAD_PER_SEC_SQ = 100;
114+
public static final double SKIDDING_AMOUNT_AT_THRESHOLD_RAD = Math.toRadians(1.2);
115+
/*
116+
* https://store.ctr-electronics.com/pigeon-2/
117+
* for a well-installed one with vibration reduction, only 0.4 degree
118+
* but most teams just install it directly on the rigid chassis frame (including my team :D)
119+
* so at least 1.2 degrees of drifting in 1 minutes for an average angular velocity of 60 degrees/second
120+
* which is the average velocity during normal swerve-circular-offense
121+
* */
122+
public static final double NORMAL_GYRO_DRIFT_IN_1_MIN_Std_Dev_RAD = Math.toRadians(1.2);
123+
public static final double AVERAGE_VELOCITY_RAD_PER_SEC_DURING_TEST = Math.toRadians(60);
124+
125+
public static final int SIMULATION_TICKS_IN_1_PERIOD = 5;
126+
public static final double SIMULATED_PERIOD_SECONDS = 0.02;
127+
}
128+
46129
/**
47130
* This is where constants used to describe the game's field go. This will have the dimensions of
48131
* the field, but also the coordinates of obstacles, game pieces, or other places of interest.

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

Lines changed: 13 additions & 91 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,6 @@
44
import com.ctre.phoenix6.signals.SensorDirectionValue;
55
import edu.wpi.first.math.geometry.Translation2d;
66
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
7-
import edu.wpi.first.math.system.plant.DCMotor;
87
import edu.wpi.first.math.trajectory.TrapezoidProfile;
98
import edu.wpi.first.math.trajectory.TrapezoidProfile.Constraints;
109
import edu.wpi.first.math.util.Units;
@@ -82,19 +81,18 @@ public static final class DriveConstants {
8281
public static final InvertedValue REAR_RIGHT_DRIVE_ENCODER_REVERSED =
8382
InvertedValue.CounterClockwise_Positive;
8483

85-
public static final double MAX_ANGULAR_SPEED_RADIANS_PER_SECOND = 6 * Math.PI;
86-
public static final double LOW_ANGULAR_SPEED_RADIANS_PER_SECOND = 3 * Math.PI;
84+
public static final double MAX_ANGULAR_SPEED_RADIANS_PER_SECOND = 20;
85+
public static final double LOW_ANGULAR_SPEED_RADIANS_PER_SECOND = 5;
8786

88-
public static final double MAX_SPEED_METERS_PER_SECOND = 4.5;
87+
public static final double MAX_SPEED_METERS_PER_SECOND = 6.95;
8988
public static final double MAX_SHOOT_SPEED_METERS_PER_SECOND = 3;
9089

9190
public static final double HEADING_ACCEPTABLE_ERROR_RADIANS = Units.degreesToRadians(2.5);
9291
public static final double HEADING_ACCEPTABLE_ERROR_MOVING_RADIANS = Units.degreesToRadians(4);
9392
}
9493

9594
public class ModuleConstants {
96-
public static final double DRIVE_GEAR_RATIO = 7.13;
97-
public static final double TURN_GEAR_RATIO = 11.3142;
95+
public static final double DRIVE_GEAR_RATIO = 4.59;
9896
public static final double WHEEL_DIAMETER_METERS = Units.inchesToMeters(3.774788522800778);
9997

10098
public static final double WHEEL_CIRCUMFERENCE_METERS = WHEEL_DIAMETER_METERS * Math.PI;
@@ -105,27 +103,29 @@ public class ModuleConstants {
105103
public static final double DRIVE_SUPPLY_LIMIT = 45.0;
106104
public static final double DRIVE_STATOR_LIMIT = 50.0;
107105

108-
public static final double TURN_P = 15;
106+
public static final double TURN_P = 116;
109107
public static final double TURN_I = 0.0;
110-
public static final double TURN_D = 0.0;
108+
public static final double TURN_D = 0.64;
111109

112-
public static final double TURN_S = 0;
110+
public static final double TURN_S = 0.0;
113111
public static final double TURN_V = 0.0;
114112
public static final double TURN_A = 0.0;
115113

116114
public static final double MAX_ANGULAR_SPEED_ROTATIONS_PER_SECOND = 30;
117115
public static final double MAX_ANGULAR_ACCELERATION_ROTATIONS_PER_SECOND_SQUARED = 24;
118116

119-
public static final double DRIVE_P = 0.345;
117+
public static final double DRIVE_P = 0.417;
120118
public static final double DRIVE_I = 0.0;
121119
public static final double DRIVE_D = 0.0;
122120

123-
public static final double DRIVE_S = 0.151315113225759;
121+
public static final double DRIVE_S = 0.16;
124122
// These values were gotten using recalc, then converted to the correct units & were confirmed
125123
// through testing and characterization
126124
// https://www.reca.lc/drive?appliedVoltageRamp=%7B%22s%22%3A1200%2C%22u%22%3A%22V%2Fs%22%7D&batteryAmpHours=%7B%22s%22%3A18%2C%22u%22%3A%22A%2Ah%22%7D&batteryResistance=%7B%22s%22%3A0.018%2C%22u%22%3A%22Ohm%22%7D&batteryVoltageAtRest=%7B%22s%22%3A12.6%2C%22u%22%3A%22V%22%7D&efficiency=97&filtering=1&gearRatioMax=%7B%22magnitude%22%3A15%2C%22ratioType%22%3A%22Reduction%22%7D&gearRatioMin=%7B%22magnitude%22%3A3%2C%22ratioType%22%3A%22Reduction%22%7D&maxSimulationTime=%7B%22s%22%3A4%2C%22u%22%3A%22s%22%7D&maxSpeedAccelerationThreshold=%7B%22s%22%3A0.15%2C%22u%22%3A%22ft%2Fs2%22%7D&motor=%7B%22quantity%22%3A4%2C%22name%22%3A%22Kraken%20X60%2A%22%7D&motorCurrentLimit=%7B%22s%22%3A60%2C%22u%22%3A%22A%22%7D&numCyclesPerMatch=24&peakBatteryDischarge=20&ratio=%7B%22magnitude%22%3A4.59%2C%22ratioType%22%3A%22Reduction%22%7D&sprintDistance=%7B%22s%22%3A25%2C%22u%22%3A%22ft%22%7D&swerve=1&targetTimeToGoal=%7B%22s%22%3A2%2C%22u%22%3A%22s%22%7D&throttleResponseMax=0.99&throttleResponseMin=0.5&weightAuxilliary=%7B%22s%22%3A24%2C%22u%22%3A%22lbs%22%7D&weightDistributionFrontBack=0.5&weightDistributionLeftRight=0.5&weightInspected=%7B%22s%22%3A125%2C%22u%22%3A%22lbs%22%7D&wheelBaseLength=%7B%22s%22%3A27%2C%22u%22%3A%22in%22%7D&wheelBaseWidth=%7B%22s%22%3A20%2C%22u%22%3A%22in%22%7D&wheelCOFDynamic=0.9&wheelCOFLateral=1.1&wheelCOFStatic=1.1&wheelDiameter=%7B%22s%22%3A4%2C%22u%22%3A%22in%22%7D
127-
public static final double DRIVE_V = 0.027285425272591; // = 0.1203 V*s/m
128-
public static final double DRIVE_A = 0.000261387517243; // = 0.02225 V*s^2/m
125+
public static final double DRIVE_V =
126+
1.73 * WHEEL_CIRCUMFERENCE_METERS / DRIVE_GEAR_RATIO; // = 0.1203 V*s/m
127+
public static final double DRIVE_A =
128+
0.32 * WHEEL_CIRCUMFERENCE_METERS / DRIVE_GEAR_RATIO; // = 0.02225 V*s^2/m
129129
}
130130

131131
public static final class TrajectoryConstants {
@@ -170,84 +170,6 @@ public static final class TrajectoryConstants {
170170
new Constraints(DriveConstants.MAX_ANGULAR_SPEED_RADIANS_PER_SECOND, 2);
171171
}
172172

173-
/**
174-
* stores the constants and PID configs for chassis because we want an all-real simulation for the
175-
* chassis, the numbers are required to be considerably precise
176-
*/
177-
public class SimulationConstants {
178-
/**
179-
* numbers that needs to be changed to fit each robot TODO: change these numbers to match your
180-
* robot
181-
*/
182-
public static final double WHEEL_COEFFICIENT_OF_FRICTION = 0.95,
183-
ROBOT_MASS_KG = 40; // with bumpers
184-
185-
/** TODO: change motor type to match your robot */
186-
public static final DCMotor DRIVE_MOTOR = DCMotor.getKrakenX60(1),
187-
STEER_MOTOR = DCMotor.getFalcon500(1);
188-
189-
public static final double WHEEL_RADIUS_METERS = ModuleConstants.WHEEL_DIAMETER_METERS / 2.0,
190-
DRIVE_GEAR_RATIO = ModuleConstants.DRIVE_GEAR_RATIO,
191-
STEER_GEAR_RATIO = 16.0,
192-
TIME_ROBOT_STOP_ROTATING_SECONDS = 0.06,
193-
STEER_FRICTION_VOLTAGE = 0.12,
194-
DRIVE_FRICTION_VOLTAGE = ModuleConstants.DRIVE_S,
195-
DRIVE_INERTIA = 0.01,
196-
STEER_INERTIA = 0.01;
197-
198-
/* adjust current limit */
199-
public static final double DRIVE_CURRENT_LIMIT = ModuleConstants.DRIVE_STATOR_LIMIT;
200-
// public static final double STEER_CURRENT_LIMIT = ModuleConstants.ST;
201-
202-
/* equations that calculates some constants for the simulator (don't modify) */
203-
private static final double GRAVITY_CONSTANT = 9.81;
204-
public static final double DRIVE_BASE_RADIUS = DriveConstants.MODULE_TRANSLATIONS[0].getNorm(),
205-
/* friction_force = normal_force * coefficient_of_friction */
206-
MAX_FRICTION_ACCELERATION = GRAVITY_CONSTANT * WHEEL_COEFFICIENT_OF_FRICTION,
207-
MAX_FRICTION_FORCE_PER_MODULE =
208-
MAX_FRICTION_ACCELERATION * ROBOT_MASS_KG / DriveConstants.MODULE_TRANSLATIONS.length,
209-
/* force = torque / distance */
210-
MAX_PROPELLING_FORCE_NEWTONS =
211-
DRIVE_MOTOR.getTorque(DRIVE_CURRENT_LIMIT) * DRIVE_GEAR_RATIO / WHEEL_RADIUS_METERS,
212-
/* floor_speed = wheel_angular_velocity * wheel_radius */
213-
CHASSIS_MAX_VELOCITY =
214-
DRIVE_MOTOR.freeSpeedRadPerSec
215-
/ DRIVE_GEAR_RATIO
216-
* WHEEL_RADIUS_METERS, // calculate using choreo
217-
CHASSIS_MAX_ACCELERATION_MPS_SQ =
218-
Math.min(
219-
MAX_FRICTION_ACCELERATION, // cannot exceed max friction
220-
MAX_PROPELLING_FORCE_NEWTONS / ROBOT_MASS_KG),
221-
CHASSIS_MAX_ANGULAR_VELOCITY_RAD_PER_SEC = CHASSIS_MAX_VELOCITY / DRIVE_BASE_RADIUS,
222-
CHASSIS_MAX_ANGULAR_ACCELERATION_RAD_PER_SEC_SQ =
223-
CHASSIS_MAX_ACCELERATION_MPS_SQ / DRIVE_BASE_RADIUS,
224-
CHASSIS_FRICTIONAL_ANGULAR_ACCELERATION =
225-
CHASSIS_MAX_ANGULAR_VELOCITY_RAD_PER_SEC / TIME_ROBOT_STOP_ROTATING_SECONDS;
226-
227-
/* for collision detection in simulation */
228-
public static final double BUMPER_WIDTH_METERS = Units.inchesToMeters(34.5),
229-
BUMPER_LENGTH_METERS = Units.inchesToMeters(36),
230-
/* https://en.wikipedia.org/wiki/Friction#Coefficient_of_friction */
231-
BUMPER_COEFFICIENT_OF_FRICTION = 0.75,
232-
/* https://simple.wikipedia.org/wiki/Coefficient_of_restitution */
233-
BUMPER_COEFFICIENT_OF_RESTITUTION = 0.08;
234-
235-
/* Gyro Sim */
236-
public static final double GYRO_ANGULAR_ACCELERATION_THRESHOLD_SKIDDING_RAD_PER_SEC_SQ = 100;
237-
public static final double SKIDDING_AMOUNT_AT_THRESHOLD_RAD = Math.toRadians(1.2);
238-
/*
239-
* https://store.ctr-electronics.com/pigeon-2/
240-
* for a well-installed one with vibration reduction, only 0.4 degree
241-
* but most teams just install it directly on the rigid chassis frame (including my team :D)
242-
* so at least 1.2 degrees of drifting in 1 minutes for an average angular velocity of 60 degrees/second
243-
* which is the average velocity during normal swerve-circular-offense
244-
* */
245-
public static final double NORMAL_GYRO_DRIFT_IN_1_MIN_Std_Dev_RAD = Math.toRadians(1.2);
246-
public static final double AVERAGE_VELOCITY_RAD_PER_SEC_DURING_TEST = Math.toRadians(60);
247-
248-
public static final int SIMULATION_TICKS_IN_1_PERIOD = 5;
249-
}
250-
251173
public static final ModuleConfig[] moduleConfigs =
252174
new ModuleConfig[] {
253175
new ModuleConfig(

src/main/java/frc/robot/subsystems/swerve/SwerveModule.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,8 @@
1212
// import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
1313
import edu.wpi.first.wpilibj2.command.CommandScheduler;
1414
import edu.wpi.first.wpilibj2.command.SubsystemBase;
15+
import frc.robot.Constants.SimulationConstants;
1516
import frc.robot.subsystems.swerve.SwerveConstants.ModuleConstants;
16-
import frc.robot.subsystems.swerve.SwerveConstants.SimulationConstants;
1717
import frc.robot.subsystems.swerve.moduleIO.ModuleInputsAutoLogged;
1818
import frc.robot.subsystems.swerve.moduleIO.ModuleInterface;
1919
import org.littletonrobotics.junction.Logger;

src/main/java/frc/robot/subsystems/swerve/odometryThread/OdometryThread.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,10 +5,10 @@
55
import edu.wpi.first.units.measure.Angle;
66
import frc.robot.Constants;
77
import frc.robot.Constants.HardwareConstants;
8+
import frc.robot.Constants.SimulationConstants;
89
import frc.robot.Robot;
910
import frc.robot.extras.util.DeviceCANBus;
1011
import frc.robot.extras.util.TimeUtil;
11-
import frc.robot.subsystems.swerve.SwerveConstants.SimulationConstants;
1212
import java.util.ArrayList;
1313
import java.util.List;
1414
import java.util.Queue;

0 commit comments

Comments
 (0)