Skip to content

Commit 59806b1

Browse files
Merge pull request #251 from Shenzhen-Robotics-Alliance/beta
Add Maple-Sim
2 parents 0eb6e9a + b794dda commit 59806b1

File tree

9 files changed

+210
-115
lines changed

9 files changed

+210
-115
lines changed

IronMaple-License.md

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,15 @@
1+
<p align="center">
2+
<img src="https://github.com/Shenzhen-Robotics-Alliance/maple-sim/raw/main/docs/media/team_logo.png" width="20%" alt="team logo"/>
3+
<img src="https://github.com/Shenzhen-Robotics-Alliance/maple-sim/raw/main/docs/media/icon.png" width="79%" alt="project logo"/>
4+
</p>
5+
6+
#### This project uses [maple-sim](https://github.com/Shenzhen-Robotics-Alliance/maple-sim) for simulation.
7+
If you encounter any bugs related to drivetrain physics simulation, please [submit an issue to maple-sim](https://github.com/Shenzhen-Robotics-Alliance/maple-sim/issues/new/choose).
8+
9+
## MIT License, Copyright (c) 2024 Team5516 "Iron Maple"
10+
11+
**Permission is hereby granted, free of charge, to any person obtaining a copyof this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:**
12+
13+
> #### The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
14+
15+
*THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.*

build.gradle

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -99,4 +99,4 @@ wpi.java.configureTestTasks(test)
9999
// Configure string concat to always inline compile
100100
tasks.withType(JavaCompile) {
101101
options.compilerArgs.add '-XDstringConcat=inline'
102-
}
102+
}

src/main/java/frc/robot/RobotContainer.java

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -96,6 +96,10 @@ public RobotContainer()
9696
*/
9797
private void configureBindings()
9898
{
99+
if (Robot.isSimulation())
100+
{
101+
driverXbox.start().onTrue(Commands.runOnce(() -> drivebase.resetOdometry(new Pose2d(3, 3, new Rotation2d()))));
102+
}
99103
if (DriverStation.isTest())
100104
{
101105
driverXbox.b().whileTrue(drivebase.sysIdDriveMotorCommand());

src/main/java/frc/robot/subsystems/swervedrive/Vision.java

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -129,10 +129,16 @@ public static Pose2d getAprilTagPose(int aprilTag, Transform2d robotOffset)
129129
*/
130130
public void updatePoseEstimation(SwerveDrive swerveDrive)
131131
{
132-
if (SwerveDriveTelemetry.isSimulation)
132+
if (SwerveDriveTelemetry.isSimulation && swerveDrive.getSimulationDriveTrainPose().isPresent())
133133
{
134-
visionSim.update(swerveDrive.getPose());
135-
134+
/*
135+
* In the maple-sim, odometry is simulated using encoder values, accounting for factors like skidding and drifting.
136+
* As a result, the odometry may not always be 100% accurate.
137+
* However, the vision system should be able to provide a reasonably accurate pose estimation, even when odometry is incorrect.
138+
* (This is why teams implement vision system to correct odometry.)
139+
* Therefore, we must ensure that the actual robot pose is provided in the simulator when updating the vision simulation during the simulation.
140+
*/
141+
visionSim.update(swerveDrive.getSimulationDriveTrainPose().get());
136142
}
137143
for (Cameras camera : Cameras.values())
138144
{

src/main/java/swervelib/SwerveDrive.java

Lines changed: 118 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -21,10 +21,8 @@
2121
import edu.wpi.first.math.numbers.N3;
2222
import edu.wpi.first.math.trajectory.Trajectory;
2323
import edu.wpi.first.math.util.Units;
24-
import edu.wpi.first.wpilibj.Alert;
24+
import edu.wpi.first.wpilibj.*;
2525
import edu.wpi.first.wpilibj.Alert.AlertType;
26-
import edu.wpi.first.wpilibj.Notifier;
27-
import edu.wpi.first.wpilibj.Timer;
2826
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
2927
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
3028
import java.util.ArrayList;
@@ -34,6 +32,7 @@
3432
import java.util.Optional;
3533
import java.util.concurrent.locks.Lock;
3634
import java.util.concurrent.locks.ReentrantLock;
35+
3736
import org.ironmaple.simulation.SimulatedArena;
3837
import org.ironmaple.simulation.drivesims.SwerveDriveSimulation;
3938
import org.ironmaple.simulation.drivesims.SwerveModuleSimulation;
@@ -51,6 +50,8 @@
5150
import swervelib.telemetry.SwerveDriveTelemetry;
5251
import swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity;
5352

53+
import static edu.wpi.first.units.Units.*;
54+
5455
/**
5556
* Swerve Drive class representing and controlling the swerve drive.
5657
*/
@@ -199,48 +200,51 @@ public SwerveDrive(
199200
kinematics = new SwerveDriveKinematics(config.moduleLocationsMeters);
200201
odometryThread = new Notifier(this::updateOdometry);
201202

203+
this.swerveModules = config.modules;
204+
202205
// Create an integrator for angle if the robot is being simulated to emulate an IMU
203206
// If the robot is real, instantiate the IMU instead.
204207
if (SwerveDriveTelemetry.isSimulation)
205208
{
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+
}
208236

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);
233237
// register the drivetrain simulation
234238
SimulatedArena.getInstance().addDriveTrainSimulation(mapleSimDrive);
235-
} else
236-
{
239+
240+
simIMU = new SwerveIMUSimulation(mapleSimDrive.getGyroSimulation());
241+
imuReadingCache = new Cache<>(simIMU::getGyroRotation3d, 5L);
242+
} else {
237243
imu = config.imu;
238244
imu.factoryDefault();
239245
imuReadingCache = new Cache<>(imu::getRotation3d, 5L);
240246
}
241247

242-
this.swerveModules = config.modules;
243-
244248
// odometry = new SwerveDriveOdometry(kinematics, getYaw(), getModulePositions());
245249
swerveDrivePoseEstimator =
246250
new SwerveDrivePoseEstimator(
@@ -287,7 +291,7 @@ public SwerveDrive(
287291
SwerveDriveTelemetry.measuredStatesObj = new SwerveModuleState[SwerveDriveTelemetry.moduleCount];
288292
}
289293

290-
odometryThread.startPeriodic(SwerveDriveTelemetry.isSimulation ? 0.01 : 0.02);
294+
setOdometryPeriod(SwerveDriveTelemetry.isSimulation ? 0.004 : 0.02);
291295

292296
checkIfTunerXCompatible();
293297

@@ -344,6 +348,7 @@ private void checkIfTunerXCompatible()
344348
public void setOdometryPeriod(double period)
345349
{
346350
odometryThread.stop();
351+
SimulatedArena.overrideSimulationTimings(Seconds.of(period), 1);
347352
odometryThread.startPeriodic(period);
348353
}
349354

@@ -353,6 +358,7 @@ public void setOdometryPeriod(double period)
353358
public void stopOdometryThread()
354359
{
355360
odometryThread.stop();
361+
SimulatedArena.overrideSimulationTimings(Seconds.of(TimedRobot.kDefaultPeriod), 5);
356362
}
357363

358364
/**
@@ -699,7 +705,7 @@ public void setChassisSpeeds(ChassisSpeeds chassisSpeeds)
699705
}
700706

701707
/**
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.
703709
*
704710
* @return The robot's pose
705711
*/
@@ -713,7 +719,25 @@ public Pose2d getPose()
713719
}
714720

715721
/**
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)
717741
*
718742
* @return A ChassisSpeeds object of the current field-relative velocity
719743
*/
@@ -727,6 +751,26 @@ public ChassisSpeeds getFieldVelocity()
727751
kinematics.toChassisSpeeds(getStates()), getOdometryHeading().unaryMinus());
728752
}
729753

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+
730774
/**
731775
* Gets the current robot-relative velocity (x, y and omega) of the robot
732776
*
@@ -737,6 +781,26 @@ public ChassisSpeeds getRobotVelocity()
737781
return kinematics.toChassisSpeeds(getStates());
738782
}
739783

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+
740804
/**
741805
* Resets odometry to the given pose. Gyro angle and module positions do not need to be reset when calling this
742806
* 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)
748812
{
749813
odometryLock.lock();
750814
swerveDrivePoseEstimator.resetPosition(getYaw(), getModulePositions(), pose);
815+
if (SwerveDriveTelemetry.isSimulation)
816+
{
817+
mapleSimDrive.setSimulationWorldPose(pose);
818+
}
751819
odometryLock.unlock();
752820
kinematics.toSwerveModuleStates(ChassisSpeeds.fromFieldRelativeSpeeds(0, 0, 0, getYaw()));
821+
753822
}
754823

755824
/**
@@ -1048,13 +1117,17 @@ public void updateOdometry()
10481117
// Update odometry
10491118
swerveDrivePoseEstimator.update(getYaw(), getModulePositions());
10501119

1120+
if (SwerveDriveTelemetry.isSimulation)
1121+
{
1122+
SimulatedArena.getInstance().simulationPeriodic();
1123+
}
1124+
10511125
// Update angle accumulator if the robot is simulated
10521126
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.INFO.ordinal())
10531127
{
10541128
Pose2d[] modulePoses = getSwerveModulePoses(swerveDrivePoseEstimator.getEstimatedPosition());
10551129
if (SwerveDriveTelemetry.isSimulation)
10561130
{
1057-
SimulatedArena.getInstance().simulationPeriodic();
10581131
simIMU.updateOdometry(
10591132
kinematics,
10601133
getStates(),
@@ -1073,7 +1146,14 @@ public void updateOdometry()
10731146

10741147
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.POSE.ordinal())
10751148
{
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+
}
10771157
}
10781158

10791159
double sumVelocity = 0;

src/main/java/swervelib/SwerveModule.java

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -171,6 +171,11 @@ public SwerveModule(int moduleNumber, SwerveModuleConfiguration moduleConfigurat
171171
absoluteEncoder.configure(moduleConfiguration.absoluteEncoderInverted);
172172
}
173173

174+
if (SwerveDriveTelemetry.isSimulation)
175+
{
176+
simModule = new SwerveModuleSimulation();
177+
}
178+
174179
// Setup the cache for the absolute encoder position.
175180
absolutePositionCache = new Cache<>(this::getRawAbsolutePosition, 20);
176181

@@ -525,6 +530,13 @@ public double getAbsolutePosition()
525530
*/
526531
public double getRawAbsolutePosition()
527532
{
533+
/* During simulation, when no absolute encoders are available, we return the state from the simulation module instead. */
534+
if (SwerveDriveTelemetry.isSimulation)
535+
{
536+
Rotation2d absolutePosition = simModule.getState().angle;
537+
return absolutePosition.getDegrees();
538+
}
539+
528540
double angle;
529541
if (absoluteEncoder != null)
530542
{
@@ -709,4 +721,19 @@ public void invalidateCache()
709721
drivePositionCache.update();
710722
driveVelocityCache.update();
711723
}
724+
725+
/**
726+
* Obtains the {@link SwerveModuleSimulation} used in simulation.
727+
*
728+
* @return the module simulation, <b>null</b> if this method is called on a real robot
729+
* */
730+
public SwerveModuleSimulation getSimModule()
731+
{
732+
return simModule;
733+
}
734+
735+
public void configureModuleSimulation(org.ironmaple.simulation.drivesims.SwerveModuleSimulation swerveModuleSimulation)
736+
{
737+
this.simModule.configureSimModule(swerveModuleSimulation);
738+
}
712739
}

0 commit comments

Comments
 (0)