Class AbstractDriveTrainSimulation

java.lang.Object
org.dyn4j.collision.AbstractCollisionBody<org.dyn4j.dynamics.BodyFixture>
org.dyn4j.dynamics.AbstractPhysicsBody
org.dyn4j.dynamics.Body
org.ironmaple.simulation.drivesims.AbstractDriveTrainSimulation
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
Direct Known Subclasses:
SwerveDriveSimulation

public abstract class AbstractDriveTrainSimulation extends org.dyn4j.dynamics.Body

Represents an Abstract Drivetrain Simulation.

Simulates the Mass, Collision Space, and Friction of the Drivetrain.

This class models the physical properties of a drivetrain, including mass and collision space.

It also provides APIs to obtain the status (position, velocity etc.) in WPILib geometry classes.

The propelling forces generated by motors are simulated in its subclass, or SwerveDriveSimulation.

  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    static final double
     
    static final double
     
     

    Fields inherited from class org.dyn4j.dynamics.AbstractPhysicsBody

    angularDamping, angularVelocity, atRest, atRestDetectionEnabled, atRestTime, bullet, force, forces, gravityScale, linearDamping, linearVelocity, mass, torque, torques

    Fields inherited from class org.dyn4j.collision.AbstractCollisionBody

    enabled, fixtureModificationHandler, fixtures, fixturesUnmodifiable, owner, radius, transform, transform0, userData

    Fields inherited from interface org.dyn4j.collision.CollisionBody

    TYPICAL_FIXTURE_COUNT

    Fields inherited from interface org.dyn4j.dynamics.PhysicsBody

    DEFAULT_ANGULAR_DAMPING, DEFAULT_LINEAR_DAMPING
  • Constructor Summary

    Constructors
    Modifier
    Constructor
    Description
    protected
    Creates a Simulation of a Drivetrain.
  • Method Summary

    Modifier and Type
    Method
    Description
    Gets the Actual Field-Relative Chassis Speeds from the Simulation.
    Gets the Actual Robot-Relative Chassis Speeds from the Simulation.
    Gets the Actual Pose of the Drivetrain in the Simulation World.
    void
    Sets the Robot's Speeds to the Given Chassis Speeds.
    void
    Sets the Robot's Current Pose in the Simulation World.
    abstract void
    Abstract Simulation Sub-Tick Method.

    Methods 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, updateMass

    Methods 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, translateToOrigin

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, wait, wait, wait

    Methods 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, translateToOrigin

    Methods inherited from interface org.dyn4j.DataContainer

    getUserData, setUserData

    Methods inherited from interface org.dyn4j.Ownable

    getOwner, setOwner

    Methods 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, updateMass

    Methods inherited from interface org.dyn4j.geometry.Rotatable

    rotate, rotate, rotate, rotate, rotate, rotate

    Methods inherited from interface org.dyn4j.geometry.Shiftable

    shift

    Methods inherited from interface org.dyn4j.geometry.Translatable

    translate, translate
  • Field Details

  • Constructor Details

    • AbstractDriveTrainSimulation

      protected AbstractDriveTrainSimulation(DriveTrainSimulationConfig config, Pose2d initialPoseOnField)

      Creates a Simulation of a Drivetrain.

      Sets Up the Collision Space and Mass of the Chassis.

      Since this is an abstract class, the constructor must be called from a subclass.

      Note that the chassis does not appear on the simulation field upon creation. Refer to SimulatedArena for instructions on how to add it to the simulation world.

      Parameters:
      config - a DriveTrainSimulationConfig instance containing the configurations of this drivetrain
      initialPoseOnField - the initial pose of the drivetrain in the simulation world
  • Method Details

    • setSimulationWorldPose

      public void setSimulationWorldPose(Pose2d robotPose)

      Sets the Robot's Current Pose in the Simulation World.

      This method instantly teleports the robot to the specified pose in the simulation world. The robot does not drive to the new pose; it is moved directly.

      Parameters:
      robotPose - the desired robot pose, represented as a Pose2d
    • setRobotSpeeds

      public void setRobotSpeeds(ChassisSpeeds givenSpeeds)

      Sets the Robot's Speeds to the Given Chassis Speeds.

      This method sets the robot's current velocity to the specified chassis speeds.

      The robot does not accelerate smoothly to these speeds; instead, it jumps to the velocity Instantaneously.

      Parameters:
      givenSpeeds - the desired chassis speeds, represented as a ChassisSpeeds object
    • simulationSubTick

      public abstract void simulationSubTick()

      Abstract Simulation Sub-Tick Method.

      This method is called every time the simulation world is updated.

      It is implemented in the sub-classes of AbstractDriveTrainSimulation.

      It is responsible for applying the propelling forces to the robot during each sub-tick of the simulation.

    • getSimulatedDriveTrainPose

      public Pose2d getSimulatedDriveTrainPose()

      Gets the Actual Pose of the Drivetrain in the Simulation World.

      This method is used to display the robot on AdvantageScope Field3d or to update vision simulations.

      Note: Do not use this method to simulate odometry! For a more realistic odometry simulation, use a SwerveDriveSimulation together with a SwerveDrivePoseEstimator.

      Returns:
      a Pose2d object yielding the current world pose of the robot in the simulation
    • getDriveTrainSimulatedChassisSpeedsRobotRelative

      public ChassisSpeeds getDriveTrainSimulatedChassisSpeedsRobotRelative()

      Gets the Actual Robot-Relative Chassis Speeds from the Simulation.

      This method returns the actual chassis speeds of the drivetrain in the simulation, relative to the robot.

      To simulate the chassis speeds calculated by encoders, use a SwerveDriveSimulation together with SwerveDriveKinematics.toChassisSpeeds(SwerveModuleState...) for a more realistic simulation.

      Returns:
      the actual chassis speeds in the simulation world, Robot-Relative
    • getDriveTrainSimulatedChassisSpeedsFieldRelative

      public ChassisSpeeds getDriveTrainSimulatedChassisSpeedsFieldRelative()

      Gets the Actual Field-Relative Chassis Speeds from the Simulation.

      This method returns the actual chassis speeds of the drivetrain in the simulation, relative to the robot.

      To simulate the chassis speeds calculated by encoders, use a SwerveDriveSimulation together with SwerveDriveKinematics.toChassisSpeeds(SwerveModuleState...) for a more realistic simulation.

      Returns:
      the actual chassis speeds in the simulation world, Field-Relative