21
21
import edu .wpi .first .math .numbers .N3 ;
22
22
import edu .wpi .first .math .trajectory .Trajectory ;
23
23
import edu .wpi .first .math .util .Units ;
24
- import edu .wpi .first .wpilibj .Alert ;
24
+ import edu .wpi .first .wpilibj .* ;
25
25
import edu .wpi .first .wpilibj .Alert .AlertType ;
26
- import edu .wpi .first .wpilibj .Notifier ;
27
- import edu .wpi .first .wpilibj .Timer ;
28
26
import edu .wpi .first .wpilibj .smartdashboard .Field2d ;
29
27
import edu .wpi .first .wpilibj .smartdashboard .SmartDashboard ;
30
28
import java .util .ArrayList ;
34
32
import java .util .Optional ;
35
33
import java .util .concurrent .locks .Lock ;
36
34
import java .util .concurrent .locks .ReentrantLock ;
35
+
37
36
import org .ironmaple .simulation .SimulatedArena ;
38
37
import org .ironmaple .simulation .drivesims .SwerveDriveSimulation ;
39
38
import org .ironmaple .simulation .drivesims .SwerveModuleSimulation ;
51
50
import swervelib .telemetry .SwerveDriveTelemetry ;
52
51
import swervelib .telemetry .SwerveDriveTelemetry .TelemetryVerbosity ;
53
52
53
+ import static edu .wpi .first .units .Units .*;
54
+
54
55
/**
55
56
* Swerve Drive class representing and controlling the swerve drive.
56
57
*/
@@ -199,48 +200,51 @@ public SwerveDrive(
199
200
kinematics = new SwerveDriveKinematics (config .moduleLocationsMeters );
200
201
odometryThread = new Notifier (this ::updateOdometry );
201
202
203
+ this .swerveModules = config .modules ;
204
+
202
205
// Create an integrator for angle if the robot is being simulated to emulate an IMU
203
206
// If the robot is real, instantiate the IMU instead.
204
207
if (SwerveDriveTelemetry .isSimulation )
205
208
{
206
- simIMU = new SwerveIMUSimulation ();
207
- imuReadingCache = new Cache <>(simIMU ::getGyroRotation3d , 5L );
209
+ DriveTrainSimulationConfig simulationConfig = DriveTrainSimulationConfig .Default ()
210
+ .withBumperSize (
211
+ Meters .of (config .getTracklength ()).plus (Inches .of (5 )),
212
+ Meters .of (config .getTrackwidth ()).plus (Inches .of (5 )))
213
+ .withRobotMass (Kilograms .of (config .physicalCharacteristics .robotMassKg ))
214
+ .withCustomModuleTranslations (config .moduleLocationsMeters )
215
+ .withGyro (config .getGyroSim ())
216
+ .withSwerveModule (() -> new SwerveModuleSimulation (
217
+ config .getDriveMotorSim (),
218
+ config .getAngleMotorSim (),
219
+ config .physicalCharacteristics .conversionFactor .drive .gearRatio ,
220
+ config .physicalCharacteristics .conversionFactor .angle .gearRatio ,
221
+ Amps .of (config .physicalCharacteristics .driveMotorCurrentLimit ),
222
+ Amps .of (20 ),
223
+ Volts .of (config .physicalCharacteristics .driveFrictionVoltage ),
224
+ Volts .of (config .physicalCharacteristics .angleFrictionVoltage ),
225
+ Inches .of (config .physicalCharacteristics .conversionFactor .drive .diameter /2 ),
226
+ KilogramSquareMeters .of (0.02 ),
227
+ config .physicalCharacteristics .wheelGripCoefficientOfFriction ));
228
+
229
+ mapleSimDrive = new SwerveDriveSimulation (simulationConfig , startingPose );
230
+
231
+ // feed module simulation instances to modules
232
+ for (int i = 0 ; i < swerveModules .length ; i ++)
233
+ {
234
+ this .swerveModules [i ].configureModuleSimulation (mapleSimDrive .getModules ()[i ]);
235
+ }
208
236
209
- // Setup MapleSim
210
- SwerveModuleSimulation simModule = new SwerveModuleSimulation (config .getDriveMotorSim (),
211
- config .getAngleMotorSim (),
212
- config .physicalCharacteristics .driveMotorCurrentLimit ,
213
- config .physicalCharacteristics .conversionFactor .drive .gearRatio ,
214
- config .physicalCharacteristics .conversionFactor .angle .gearRatio ,
215
- config .physicalCharacteristics .driveFrictionVoltage ,
216
- config .physicalCharacteristics .angleFrictionVoltage ,
217
- config .physicalCharacteristics .wheelGripCoefficientOfFriction ,
218
- config .physicalCharacteristics .conversionFactor .drive .diameter /
219
- 2 ,
220
- config .physicalCharacteristics .steerRotationalInertia );
221
- DriveTrainSimulationConfig simCfg = new DriveTrainSimulationConfig (config .physicalCharacteristics .robotMassKg ,
222
- config .getTracklength () +
223
- Units .inchesToMeters (5 ),
224
- config .getTrackwidth () +
225
- Units .inchesToMeters (5 ),
226
- config .getTracklength (),
227
- config .getTrackwidth (),
228
- () -> {
229
- return simModule ;
230
- },
231
- config .getGyroSim ());
232
- mapleSimDrive = new SwerveDriveSimulation (simCfg , startingPose );
233
237
// register the drivetrain simulation
234
238
SimulatedArena .getInstance ().addDriveTrainSimulation (mapleSimDrive );
235
- } else
236
- {
239
+
240
+ simIMU = new SwerveIMUSimulation (mapleSimDrive .getGyroSimulation ());
241
+ imuReadingCache = new Cache <>(simIMU ::getGyroRotation3d , 5L );
242
+ } else {
237
243
imu = config .imu ;
238
244
imu .factoryDefault ();
239
245
imuReadingCache = new Cache <>(imu ::getRotation3d , 5L );
240
246
}
241
247
242
- this .swerveModules = config .modules ;
243
-
244
248
// odometry = new SwerveDriveOdometry(kinematics, getYaw(), getModulePositions());
245
249
swerveDrivePoseEstimator =
246
250
new SwerveDrivePoseEstimator (
@@ -287,7 +291,7 @@ public SwerveDrive(
287
291
SwerveDriveTelemetry .measuredStatesObj = new SwerveModuleState [SwerveDriveTelemetry .moduleCount ];
288
292
}
289
293
290
- odometryThread . startPeriodic (SwerveDriveTelemetry .isSimulation ? 0.01 : 0.02 );
294
+ setOdometryPeriod (SwerveDriveTelemetry .isSimulation ? 0.004 : 0.02 );
291
295
292
296
checkIfTunerXCompatible ();
293
297
@@ -344,6 +348,7 @@ private void checkIfTunerXCompatible()
344
348
public void setOdometryPeriod (double period )
345
349
{
346
350
odometryThread .stop ();
351
+ SimulatedArena .overrideSimulationTimings (Seconds .of (period ), 1 );
347
352
odometryThread .startPeriodic (period );
348
353
}
349
354
@@ -353,6 +358,7 @@ public void setOdometryPeriod(double period)
353
358
public void stopOdometryThread ()
354
359
{
355
360
odometryThread .stop ();
361
+ SimulatedArena .overrideSimulationTimings (Seconds .of (TimedRobot .kDefaultPeriod ), 5 );
356
362
}
357
363
358
364
/**
@@ -699,7 +705,7 @@ public void setChassisSpeeds(ChassisSpeeds chassisSpeeds)
699
705
}
700
706
701
707
/**
702
- * Gets the current pose (position and rotation) of the robot, as reported by odometry.
708
+ * Gets the measured pose (position and rotation) of the robot, as reported by odometry.
703
709
*
704
710
* @return The robot's pose
705
711
*/
@@ -713,7 +719,25 @@ public Pose2d getPose()
713
719
}
714
720
715
721
/**
716
- * Gets the current field-relative velocity (x, y and omega) of the robot
722
+ * Gets the actual pose of the drivetrain during simulation
723
+ *
724
+ * @return an optional Pose2d, representing the drivetrain pose during simulation, or an empty optional when running on real robot
725
+ * */
726
+ public Optional <Pose2d > getSimulationDriveTrainPose ()
727
+ {
728
+ if (SwerveDriveTelemetry .isSimulation )
729
+ {
730
+ odometryLock .lock ();
731
+ Pose2d simulationPose = mapleSimDrive .getSimulatedDriveTrainPose ();
732
+ odometryLock .unlock ();
733
+ return Optional .of (simulationPose );
734
+ }
735
+
736
+ return Optional .empty ();
737
+ }
738
+
739
+ /**
740
+ * Gets the measured field-relative robot velocity (x, y and omega)
717
741
*
718
742
* @return A ChassisSpeeds object of the current field-relative velocity
719
743
*/
@@ -727,6 +751,26 @@ public ChassisSpeeds getFieldVelocity()
727
751
kinematics .toChassisSpeeds (getStates ()), getOdometryHeading ().unaryMinus ());
728
752
}
729
753
754
+ /**
755
+ * Gets the actual field-relative robot velocity (x, y and omega) during simulation
756
+ *
757
+ * @return An optional ChassisSpeeds representing the actual field-relative velocity of the robot, or an empty optional when running on real robot
758
+ * @deprecated for testing version of maple-sim only
759
+ */
760
+ @ Deprecated
761
+ public Optional <ChassisSpeeds > getSimulationFieldVelocity ()
762
+ {
763
+ if (SwerveDriveTelemetry .isSimulation )
764
+ {
765
+ odometryLock .lock ();
766
+ ChassisSpeeds simulationFieldRelativeVelocity = mapleSimDrive .getDriveTrainSimulatedChassisSpeedsFieldRelative ();
767
+ odometryLock .unlock ();
768
+ return Optional .of (simulationFieldRelativeVelocity );
769
+ }
770
+
771
+ return Optional .empty ();
772
+ }
773
+
730
774
/**
731
775
* Gets the current robot-relative velocity (x, y and omega) of the robot
732
776
*
@@ -737,6 +781,26 @@ public ChassisSpeeds getRobotVelocity()
737
781
return kinematics .toChassisSpeeds (getStates ());
738
782
}
739
783
784
+ /**
785
+ * Gets the actual robot-relative robot velocity (x, y and omega) during simulation
786
+ *
787
+ * @return An optional ChassisSpeeds representing the actual robot-relative velocity of the robot, or an empty optional when running on real robot
788
+ * @deprecated for testing version of maple-sim only
789
+ */
790
+ @ Deprecated
791
+ public Optional <ChassisSpeeds > getSimulationRobotVelocity ()
792
+ {
793
+ if (SwerveDriveTelemetry .isSimulation )
794
+ {
795
+ odometryLock .lock ();
796
+ ChassisSpeeds simulationFieldRelativeVelocity = mapleSimDrive .getDriveTrainSimulatedChassisSpeedsRobotRelative ();
797
+ odometryLock .unlock ();
798
+ return Optional .of (simulationFieldRelativeVelocity );
799
+ }
800
+
801
+ return Optional .empty ();
802
+ }
803
+
740
804
/**
741
805
* Resets odometry to the given pose. Gyro angle and module positions do not need to be reset when calling this
742
806
* method. However, if either gyro angle or module position is reset, this must be called in order for odometry to
@@ -748,8 +812,13 @@ public void resetOdometry(Pose2d pose)
748
812
{
749
813
odometryLock .lock ();
750
814
swerveDrivePoseEstimator .resetPosition (getYaw (), getModulePositions (), pose );
815
+ if (SwerveDriveTelemetry .isSimulation )
816
+ {
817
+ mapleSimDrive .setSimulationWorldPose (pose );
818
+ }
751
819
odometryLock .unlock ();
752
820
kinematics .toSwerveModuleStates (ChassisSpeeds .fromFieldRelativeSpeeds (0 , 0 , 0 , getYaw ()));
821
+
753
822
}
754
823
755
824
/**
@@ -1048,13 +1117,17 @@ public void updateOdometry()
1048
1117
// Update odometry
1049
1118
swerveDrivePoseEstimator .update (getYaw (), getModulePositions ());
1050
1119
1120
+ if (SwerveDriveTelemetry .isSimulation )
1121
+ {
1122
+ SimulatedArena .getInstance ().simulationPeriodic ();
1123
+ }
1124
+
1051
1125
// Update angle accumulator if the robot is simulated
1052
1126
if (SwerveDriveTelemetry .verbosity .ordinal () >= TelemetryVerbosity .INFO .ordinal ())
1053
1127
{
1054
1128
Pose2d [] modulePoses = getSwerveModulePoses (swerveDrivePoseEstimator .getEstimatedPosition ());
1055
1129
if (SwerveDriveTelemetry .isSimulation )
1056
1130
{
1057
- SimulatedArena .getInstance ().simulationPeriodic ();
1058
1131
simIMU .updateOdometry (
1059
1132
kinematics ,
1060
1133
getStates (),
@@ -1073,7 +1146,14 @@ public void updateOdometry()
1073
1146
1074
1147
if (SwerveDriveTelemetry .verbosity .ordinal () >= TelemetryVerbosity .POSE .ordinal ())
1075
1148
{
1076
- field .setRobotPose (swerveDrivePoseEstimator .getEstimatedPosition ());
1149
+ if (SwerveDriveTelemetry .isSimulation )
1150
+ {
1151
+ field .setRobotPose (mapleSimDrive .getSimulatedDriveTrainPose ());
1152
+ field .getObject ("OdometryPose" ).setPose (swerveDrivePoseEstimator .getEstimatedPosition ());
1153
+ } else
1154
+ {
1155
+ field .setRobotPose (swerveDrivePoseEstimator .getEstimatedPosition ());
1156
+ }
1077
1157
}
1078
1158
1079
1159
double sumVelocity = 0 ;
0 commit comments