Class SwerveDriveSimulation
- All Implemented Interfaces:
org.dyn4j.collision.CollisionBody<org.dyn4j.dynamics.BodyFixture>,org.dyn4j.DataContainer,org.dyn4j.dynamics.PhysicsBody,org.dyn4j.geometry.Rotatable,org.dyn4j.geometry.Shiftable,org.dyn4j.geometry.Transformable,org.dyn4j.geometry.Translatable,org.dyn4j.Ownable
Simulates a Swerve Drivetrain.
Check Online Documentation
1. Purpose
This class simulates a swerve drivetrain composed of more than two SwerveModuleSimulation modules.
It provides a realistic modeling of drivetrain physics, replicating wheel grip and motor propulsion for an actual swerve drive.
2. Simulation Dynamics
- 1. Propelling forces generated by the drive motors, computed by
SwerveModuleSimulation.updateSimulationSubTickGetModuleForce(Vector2, Rotation2d, double). - 2. Friction forces generated by the wheels that "pull" the robot from its current ground velocity to the module velocities, both translational and rotational.
- 3. Centripetal forces generated by the steering when the drivetrain makes a turn.
3. Odometry Simulation
To simulate odometry, follow these steps:
- Obtain the
SwerveModuleSimulationinstances throughgetModules(). - Create an IO
Implementation that wraps around
SwerveModuleSimulationto retrieve encoder readings. - Update a
SwerveDrivePoseEstimatorusing the encoder readings, similar to how you would on a real robot.
Refer to the ModuleIOSim.java example project for more details.
Vision Simulation
You can obtain the real robot pose from AbstractDriveTrainSimulation.getSimulatedDriveTrainPose() and feed it to the PhotonVision
simulation to simulate vision.
-
Field Summary
FieldsModifier and TypeFieldDescriptionprotected final GyroSimulationprotected final SwerveDriveKinematicsprotected final Translation2d[]Fields inherited from class org.ironmaple.simulation.drivesims.AbstractDriveTrainSimulation
BUMPER_COEFFICIENT_OF_FRICTION, BUMPER_COEFFICIENT_OF_RESTITUTION, configFields inherited from class org.dyn4j.dynamics.AbstractPhysicsBody
angularDamping, angularVelocity, atRest, atRestDetectionEnabled, atRestTime, bullet, force, forces, gravityScale, linearDamping, linearVelocity, mass, torque, torquesFields inherited from class org.dyn4j.collision.AbstractCollisionBody
enabled, fixtureModificationHandler, fixtures, fixturesUnmodifiable, owner, radius, transform, transform0, userDataFields inherited from interface org.dyn4j.collision.CollisionBody
TYPICAL_FIXTURE_COUNTFields inherited from interface org.dyn4j.dynamics.PhysicsBody
DEFAULT_ANGULAR_DAMPING, DEFAULT_LINEAR_DAMPING -
Constructor Summary
ConstructorsConstructorDescriptionSwerveDriveSimulation(DriveTrainSimulationConfig config, Pose2d initialPoseOnField) Creates a Swerve Drive Simulation. -
Method Summary
Modifier and TypeMethodDescriptionObtains the drive base radius of the swerve drive.maxAngularAcceleration(Current statorCurrentLimit) Obtains the maximum achievable angular acceleration of the chassis.Obtains the maximum achievable angular velocity of the chassis.maxLinearAcceleration(Current statorCurrentLimit) Obtains the maximum achievable linear acceleration of the chassis.Obtains the maximum achievable linear velocity of the chassis.voidUpdates the Swerve Drive Simulation.Methods inherited from class org.ironmaple.simulation.drivesims.AbstractDriveTrainSimulation
getDriveTrainSimulatedChassisSpeedsFieldRelative, getDriveTrainSimulatedChassisSpeedsRobotRelative, getSimulatedDriveTrainPose, setRobotSpeeds, setSimulationWorldPoseMethods inherited from class org.dyn4j.dynamics.AbstractPhysicsBody
accumulate, addFixture, addFixture, addFixture, applyForce, applyForce, applyForce, applyImpulse, applyImpulse, applyImpulse, applyTorque, applyTorque, clearAccumulatedForce, clearAccumulatedTorque, clearForce, clearTorque, computeSweptAABB, computeSweptAABB, createSweptAABB, createSweptAABB, getAccumulatedForce, getAccumulatedTorque, getAngularDamping, getAngularVelocity, getChangeInOrientation, getChangeInPosition, getForce, getGravityScale, getLinearDamping, getLinearVelocity, getLinearVelocity, getLocalCenter, getMass, getTorque, getWorldCenter, integratePosition, integrateVelocity, isAtRest, isAtRestDetectionEnabled, isBullet, isDynamic, isKinematic, isStatic, removeAllFixtures, removeFixture, removeFixture, removeFixture, removeFixtures, setAngularDamping, setAngularVelocity, setAtRest, setAtRestDetectionEnabled, setBullet, setEnabled, setGravityScale, setLinearDamping, setLinearVelocity, setLinearVelocity, setMass, setMass, setMassType, toString, updateAtRestTime, updateMassMethods inherited from class org.dyn4j.collision.AbstractCollisionBody
addFixture, computeAABB, computeAABB, contains, containsFixture, createAABB, createAABB, getFixture, getFixture, getFixtureCount, getFixtureIterator, getFixtureModificationHandler, getFixtures, getFixtures, getLocalPoint, getLocalVector, getOwner, getPreviousTransform, getRotationDiscRadius, getTransform, getUserData, getWorldPoint, getWorldVector, isEnabled, rotate, rotate, rotate, rotate, rotate, rotate, rotateAboutCenter, setFixtureModificationHandler, setOwner, setRotationDiscRadius, setTransform, setUserData, shift, translate, translate, translateToOriginMethods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, waitMethods inherited from interface org.dyn4j.collision.CollisionBody
addFixture, addFixture, computeAABB, computeAABB, contains, containsFixture, createAABB, createAABB, getFixture, getFixture, getFixtureCount, getFixtureIterator, getFixtureModificationHandler, getFixtures, getFixtures, getLocalCenter, getLocalPoint, getLocalVector, getPreviousTransform, getRotationDiscRadius, getTransform, getWorldCenter, getWorldPoint, getWorldVector, isEnabled, removeAllFixtures, removeFixture, removeFixture, removeFixture, removeFixtures, rotateAboutCenter, setEnabled, setFixtureModificationHandler, setTransform, translateToOriginMethods inherited from interface org.dyn4j.DataContainer
getUserData, setUserDataMethods inherited from interface org.dyn4j.Ownable
getOwner, setOwnerMethods inherited from interface org.dyn4j.dynamics.PhysicsBody
addFixture, addFixture, applyForce, applyForce, applyForce, applyImpulse, applyImpulse, applyImpulse, applyTorque, applyTorque, clearAccumulatedForce, clearAccumulatedTorque, clearForce, clearTorque, computeSweptAABB, computeSweptAABB, createSweptAABB, createSweptAABB, getAccumulatedForce, getAccumulatedTorque, getAngularDamping, getAngularVelocity, getChangeInOrientation, getChangeInPosition, getForce, getGravityScale, getLinearDamping, getLinearVelocity, getLinearVelocity, getMass, getTorque, integratePosition, integrateVelocity, isAtRest, isAtRestDetectionEnabled, isBullet, isDynamic, isKinematic, isStatic, setAngularDamping, setAngularVelocity, setAtRest, setAtRestDetectionEnabled, setBullet, setGravityScale, setLinearDamping, setLinearVelocity, setLinearVelocity, setMass, setMass, setMassType, updateAtRestTime, updateMassMethods inherited from interface org.dyn4j.geometry.Rotatable
rotate, rotate, rotate, rotate, rotate, rotateMethods inherited from interface org.dyn4j.geometry.Shiftable
shiftMethods inherited from interface org.dyn4j.geometry.Translatable
translate, translate
-
Field Details
-
gyroSimulation
-
moduleTranslations
-
kinematics
-
-
Constructor Details
-
SwerveDriveSimulation
Creates a Swerve Drive Simulation.
This constructor initializes a swerve drive simulation with the given robot mass, bumper dimensions, module simulations, module translations, gyro simulation, and initial pose on the field.
- Parameters:
config- aDriveTrainSimulationConfiginstance containing the configurations of * this drivetraininitialPoseOnField- the initial pose of the drivetrain in the simulation world, represented as aPose2d
-
-
Method Details
-
simulationSubTick
public void simulationSubTick()Updates the Swerve Drive Simulation.
This method performs the following actions during each sub-tick of the simulation:
- Applies the translational friction force to the physics engine.
- Applies the rotational friction torque to the physics engine.
- Updates the simulation of each swerve module.
- Applies the propelling forces of the modules to the physics engine.
- Updates the gyro simulation of the drivetrain.
- Specified by:
simulationSubTickin classAbstractDriveTrainSimulation
-
maxLinearVelocity
Obtains the maximum achievable linear velocity of the chassis.
- Returns:
- the maximum linear velocity
- See Also:
-
maxLinearAcceleration
Obtains the maximum achievable linear acceleration of the chassis.
- Returns:
- the maximum linear acceleration
- See Also:
-
driveBaseRadius
Obtains the drive base radius of the swerve drive.
- Returns:
- the drive base radius.
-
maxAngularVelocity
Obtains the maximum achievable angular velocity of the chassis.
- Returns:
- the maximum angular velocity
-
maxAngularAcceleration
Obtains the maximum achievable angular acceleration of the chassis.
- Returns:
- the maximum angular acceleration
-
getModules
-
getGyroSimulation
-