Package swervelib

Class SwerveDrive

java.lang.Object
swervelib.SwerveDrive

public class SwerveDrive extends Object
Swerve Drive class representing and controlling the swerve drive.
  • Field Details

    • kinematics

      public final SwerveKinematics2 kinematics
      Swerve Kinematics object utilizing second order kinematics.
    • swerveDriveConfiguration

      public final SwerveDriveConfiguration swerveDriveConfiguration
      Swerve drive configuration.
    • swerveDrivePoseEstimator

      public final SwervePoseEstimator2 swerveDrivePoseEstimator
      Swerve odometry.
    • swerveModules

      private final SwerveModule[] swerveModules
      Swerve modules.
    • field

      public edu.wpi.first.wpilibj.smartdashboard.Field2d field
      Field object.
    • swerveController

      public SwerveController swerveController
      Swerve controller for controlling heading of the robot.
    • stateStdDevs

      public edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N3,edu.wpi.first.math.numbers.N1> stateStdDevs
      Trustworthiness of the internal model of how motors should be moving Measured in expected standard deviation (meters of position and degrees of rotation)
    • visionMeasurementStdDevs

      public edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N3,edu.wpi.first.math.numbers.N1> visionMeasurementStdDevs
      Trustworthiness of the vision system Measured in expected standard deviation (meters of position and degrees of rotation)
    • invertOdometry

      public boolean invertOdometry
      Invert odometry readings of drive motor positions, used as a patch for debugging currently.
    • chassisVelocityCorrection

      public boolean chassisVelocityCorrection
      Correct chassis velocity in drive(Translation2d, double, boolean, boolean) using 254's correction.
    • imu

      private SwerveIMU imu
      Swerve IMU device for sensing the heading of the robot.
    • simIMU

      private SwerveIMUSimulation simIMU
      Simulation of the swerve drive.
    • moduleSynchronizationCounter

      private int moduleSynchronizationCounter
      Counter to synchronize the modules relative encoder with absolute encoder when not moving.
    • lastHeadingRadians

      private double lastHeadingRadians
      The last heading set in radians.
  • Constructor Details

  • Method Details

    • drive

      public void drive(edu.wpi.first.math.geometry.Translation2d translation, double rotation, boolean fieldRelative, boolean isOpenLoop)
      The primary method for controlling the drivebase. Takes a Translation2d and a rotation rate, and calculates and commands module states accordingly. Can use either open-loop or closed-loop velocity control for the wheel velocities. Also has field- and robot-relative modes, which affect how the translation vector is used. This method defaults to no heading correction.
      Parameters:
      translation - Translation2d that is the commanded linear velocity of the robot, in meters per second. In robot-relative mode, positive x is torwards the bow (front) and positive y is torwards port (left). In field-relative mode, positive x is away from the alliance wall (field North) and positive y is torwards the left wall when looking through the driver station glass (field West).
      rotation - Robot angular rate, in radians per second. CCW positive. Unaffected by field/robot relativity.
      fieldRelative - Drive mode. True for field-relative, false for robot-relative.
      isOpenLoop - Whether to use closed-loop velocity control. Set to true to disable closed-loop.
    • drive

      public void drive(edu.wpi.first.math.geometry.Translation2d translation, double rotation, boolean fieldRelative, boolean isOpenLoop, boolean headingCorrection)
      The primary method for controlling the drivebase. Takes a Translation2d and a rotation rate, and calculates and commands module states accordingly. Can use either open-loop or closed-loop velocity control for the wheel velocities. Also has field- and robot-relative modes, which affect how the translation vector is used.
      Parameters:
      translation - Translation2d that is the commanded linear velocity of the robot, in meters per second. In robot-relative mode, positive x is torwards the bow (front) and positive y is torwards port (left). In field-relative mode, positive x is away from the alliance wall (field North) and positive y is torwards the left wall when looking through the driver station glass (field West).
      rotation - Robot angular rate, in radians per second. CCW positive. Unaffected by field/robot relativity.
      fieldRelative - Drive mode. True for field-relative, false for robot-relative.
      isOpenLoop - Whether to use closed-loop velocity control. Set to true to disable closed-loop.
      headingCorrection - Whether to correct heading when driving translationally. Set to true to enable.
    • setMaximumSpeeds

      public void setMaximumSpeeds(double attainableMaxModuleSpeedMetersPerSecond, double attainableMaxTranslationalSpeedMetersPerSecond, double attainableMaxRotationalVelocityRadiansPerSecond)
      Set the maximum speeds for desaturation.
      Parameters:
      attainableMaxModuleSpeedMetersPerSecond - The absolute max speed that a module can reach in meters per second.
      attainableMaxTranslationalSpeedMetersPerSecond - The absolute max speed that your robot can reach while translating in meters per second.
      attainableMaxRotationalVelocityRadiansPerSecond - The absolute max speed the robot can reach while rotating in radians per second.
    • setRawModuleStates

      private void setRawModuleStates(SwerveModuleState2[] desiredStates, boolean isOpenLoop)
      Set the module states (azimuth and velocity) directly. Used primarily for auto pathing.
      Parameters:
      desiredStates - A list of SwerveModuleStates to send to the modules.
      isOpenLoop - Whether to use closed-loop velocity control. Set to true to disable closed-loop.
    • setModuleStates

      public void setModuleStates(SwerveModuleState2[] desiredStates, boolean isOpenLoop)
      Set the module states (azimuth and velocity) directly. Used primarily for auto paths.
      Parameters:
      desiredStates - A list of SwerveModuleStates to send to the modules.
      isOpenLoop - Whether to use closed-loop velocity control. Set to true to disable closed-loop.
    • setChassisSpeeds

      public void setChassisSpeeds(edu.wpi.first.math.kinematics.ChassisSpeeds chassisSpeeds)
      Set chassis speeds with closed-loop velocity control and second order kinematics.
      Parameters:
      chassisSpeeds - Chassis speeds to set.
    • getPose

      public edu.wpi.first.math.geometry.Pose2d getPose()
      Gets the current pose (position and rotation) of the robot, as reported by odometry.
      Returns:
      The robot's pose
    • getFieldVelocity

      public edu.wpi.first.math.kinematics.ChassisSpeeds getFieldVelocity()
      Gets the current field-relative velocity (x, y and omega) of the robot
      Returns:
      A ChassisSpeeds object of the current field-relative velocity
    • getRobotVelocity

      public edu.wpi.first.math.kinematics.ChassisSpeeds getRobotVelocity()
      Gets the current robot-relative velocity (x, y and omega) of the robot
      Returns:
      A ChassisSpeeds object of the current robot-relative velocity
    • resetOdometry

      public void resetOdometry(edu.wpi.first.math.geometry.Pose2d pose)
      Resets odometry to the given pose. Gyro angle and module positions do not need to be reset when calling this method. However, if either gyro angle or module position is reset, this must be called in order for odometry to keep working.
      Parameters:
      pose - The pose to set the odometry to
    • postTrajectory

      public void postTrajectory(edu.wpi.first.math.trajectory.Trajectory trajectory)
      Post the trajectory to the field
      Parameters:
      trajectory - the trajectory to post.
    • getStates

      public SwerveModuleState2[] getStates()
      Gets the current module states (azimuth and velocity)
      Returns:
      A list of SwerveModuleStates containing the current module states
    • getModulePositions

      public edu.wpi.first.math.kinematics.SwerveModulePosition[] getModulePositions()
      Gets the current module positions (azimuth and wheel position (meters)). Inverts the distance from each module if invertOdometry is true.
      Returns:
      A list of SwerveModulePositions containg the current module positions
    • zeroGyro

      public void zeroGyro()
      Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.
    • getYaw

      public edu.wpi.first.math.geometry.Rotation2d getYaw()
      Gets the current yaw angle of the robot, as reported by the imu. CCW positive, not wrapped.
      Returns:
      The yaw as a Rotation2d angle
    • getPitch

      public edu.wpi.first.math.geometry.Rotation2d getPitch()
      Gets the current pitch angle of the robot, as reported by the imu.
      Returns:
      The heading as a Rotation2d angle
    • getRoll

      public edu.wpi.first.math.geometry.Rotation2d getRoll()
      Gets the current roll angle of the robot, as reported by the imu.
      Returns:
      The heading as a Rotation2d angle
    • getGyroRotation3d

      public edu.wpi.first.math.geometry.Rotation3d getGyroRotation3d()
      Gets the current gyro Rotation3d of the robot, as reported by the imu.
      Returns:
      The heading as a Rotation3d angle
    • getAccel

      public Optional<edu.wpi.first.math.geometry.Translation3d> getAccel()
      Gets current acceleration of the robot in m/s/s. If gyro unsupported returns empty.
      Returns:
      acceleration of the robot as a Translation3d
    • setMotorIdleMode

      public void setMotorIdleMode(boolean brake)
      Sets the drive motors to brake/coast mode.
      Parameters:
      brake - True to set motors to brake mode, false for coast.
    • setMaximumSpeed

      public void setMaximumSpeed(double maximumSpeed, boolean updateModuleFeedforward)
      Set the maximum speed of the drive motors, modified SwerveControllerConfiguration.maxSpeed and SwerveDriveConfiguration.maxSpeed which is used for the setRawModuleStates(SwerveModuleState2[], boolean) function and SwerveController.getTargetSpeeds(double, double, double, double, double) functions. This function overrides what was placed in the JSON and could damage your motor/robot if set too high or unachievable rates.
      Parameters:
      maximumSpeed - Maximum speed for the drive motors in meters / second.
      updateModuleFeedforward - Update the swerve module feedforward to account for the new maximum speed. This should be true unless you have replaced the drive motor feedforward with replaceSwerveModuleFeedforward(SimpleMotorFeedforward)
    • setMaximumSpeed

      public void setMaximumSpeed(double maximumSpeed)
      Set the maximum speed of the drive motors, modified SwerveControllerConfiguration.maxSpeed and SwerveDriveConfiguration.maxSpeed which is used for the setRawModuleStates(SwerveModuleState2[], boolean) function and SwerveController.getTargetSpeeds(double, double, double, double, double) functions. This function overrides what was placed in the JSON and could damage your motor/robot if set too high or unachievable rates. Overwrites the SwerveModule.feedforward.
      Parameters:
      maximumSpeed - Maximum speed for the drive motors in meters / second.
    • lockPose

      public void lockPose()
      Point all modules toward the robot center, thus making the robot very difficult to move. Forcing the robot to keep the current pose.
    • getSwerveModulePoses

      public edu.wpi.first.math.geometry.Pose2d[] getSwerveModulePoses(edu.wpi.first.math.geometry.Pose2d robotPose)
      Get the swerve module poses and on the field relative to the robot.
      Parameters:
      robotPose - Robot pose.
      Returns:
      Swerve module poses.
    • replaceSwerveModuleFeedforward

      public void replaceSwerveModuleFeedforward(edu.wpi.first.math.controller.SimpleMotorFeedforward feedforward)
      Setup the swerve module feedforward.
      Parameters:
      feedforward - Feedforward for the drive motor on swerve modules.
    • updateOdometry

      public void updateOdometry()
      Update odometry should be run every loop. Synchronizes module absolute encoders with relative encoders periodically. In simulation mode will also post the pose of each module. Updates SmartDashboard with module encoder readings and states.
    • synchronizeModuleEncoders

      public void synchronizeModuleEncoders()
      Synchronize angle motor integrated encoders with data from absolute encoders.
    • addVisionMeasurement

      public void addVisionMeasurement(edu.wpi.first.math.geometry.Pose2d robotPose, double timestamp, boolean soft, double trustWorthiness)
      Add a vision measurement to the SwerveDrivePoseEstimator and update the SwerveIMU gyro reading with the given timestamp of the vision measurement.
      Parameters:
      robotPose - Robot Pose2d as measured by vision.
      timestamp - Timestamp the measurement was taken as time since startup, should be taken from Timer.getFPGATimestamp() or similar sources.
      soft - Add vision estimate using the SwerveDrivePoseEstimator.addVisionMeasurement(Pose2d, double) function, or hard reset odometry with the given position with SwerveDriveOdometry.resetPosition(Rotation2d, SwerveModulePosition[], Pose2d).
      trustWorthiness - Trust level of vision reading when using a soft measurement, used to multiply the standard deviation. Set to 1 for full trust.
    • addVisionMeasurement

      public void addVisionMeasurement(edu.wpi.first.math.geometry.Pose2d robotPose, double timestamp, boolean soft, edu.wpi.first.math.Matrix<edu.wpi.first.math.numbers.N3,edu.wpi.first.math.numbers.N1> visionMeasurementStdDevs)
      Add a vision measurement to the SwerveDrivePoseEstimator and update the SwerveIMU gyro reading with the given timestamp of the vision measurement.
      Parameters:
      robotPose - Robot Pose2d as measured by vision.
      timestamp - Timestamp the measurement was taken as time since startup, should be taken from Timer.getFPGATimestamp() or similar sources.
      soft - Add vision estimate using the SwerveDrivePoseEstimator.addVisionMeasurement(Pose2d, double) function, or hard reset odometry with the given position with SwerveDriveOdometry.resetPosition(Rotation2d, SwerveModulePosition[], Pose2d).
      visionMeasurementStdDevs - Vision measurement standard deviation that will be sent to the SwerveDrivePoseEstimator.
    • setGyro

      public void setGyro(edu.wpi.first.math.geometry.Rotation3d gyro)
      Set the expected gyroscope angle using a Rotation3d object. To reset gyro, set to a new Rotation3d.
      Parameters:
      gyro - expected gyroscope angle.
    • getSwerveController

      public SwerveController getSwerveController()
      Helper function to get the swerveController for the SwerveDrive which can be used to generate ChassisSpeeds for the robot to orient it correctly given axis or angles, and apply SlewRateLimiter to given inputs. Important functions to look at are SwerveController.getTargetSpeeds(double, double, double, double), SwerveController.addSlewRateLimiters(SlewRateLimiter, SlewRateLimiter, SlewRateLimiter), SwerveController.getRawTargetSpeeds(double, double, double).
      Returns:
      SwerveController for the SwerveDrive.
    • getModules

      public SwerveModule[] getModules()
      Get the SwerveModules associated with the SwerveDrive.
      Returns:
      SwerveModule array specified by configurations.
    • resetEncoders

      public void resetEncoders()
      Reset the drive encoders on the robot, useful when manually resetting the robot without a reboot, like in autonomous.
    • enableSecondOrderKinematics

      public void enableSecondOrderKinematics(double moduleFeedforward)
      Enable second order kinematics for simulation and modifying the feedforward. Second order kinematics could increase accuracy in odometry.
      Parameters:
      moduleFeedforward - Module feedforward to apply should be between [-1, 1] excluding 0.
    • enableSecondOrderKinematics

      public void enableSecondOrderKinematics()
      Enable second order kinematics for tracking purposes but completely untuned.
    • disableSecondOrderKinematics

      public void disableSecondOrderKinematics()
      Disable second order kinematics.