Files
YAGSL/swervelib/SwerveDrive.java

860 lines
35 KiB
Java
Raw Normal View History

2023-02-13 17:21:24 -06:00
package swervelib;
2023-01-29 21:18:52 -06:00
import edu.wpi.first.math.Matrix;
2023-01-29 21:18:52 -06:00
import edu.wpi.first.math.VecBuilder;
2023-02-13 14:37:05 -06:00
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
2023-01-29 21:18:52 -06:00
import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator;
import edu.wpi.first.math.filter.SlewRateLimiter;
2023-04-08 12:31:07 -05:00
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Transform2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.geometry.Twist2d;
2023-01-29 21:18:52 -06:00
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3;
import edu.wpi.first.math.trajectory.Trajectory;
2023-02-23 21:12:29 -06:00
import edu.wpi.first.math.util.Units;
2023-01-29 21:18:52 -06:00
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
2023-04-08 12:31:07 -05:00
import java.util.ArrayList;
import java.util.List;
import java.util.Optional;
2023-02-13 17:21:24 -06:00
import swervelib.imu.SwerveIMU;
import swervelib.math.SwerveKinematics2;
import swervelib.math.SwerveMath;
2023-02-13 17:21:24 -06:00
import swervelib.math.SwerveModuleState2;
import swervelib.parser.SwerveControllerConfiguration;
import swervelib.parser.SwerveDriveConfiguration;
import swervelib.simulation.SwerveIMUSimulation;
import swervelib.telemetry.SwerveDriveTelemetry;
import swervelib.telemetry.SwerveDriveTelemetry.TelemetryVerbosity;
2023-01-29 21:18:52 -06:00
/**
2023-02-13 14:37:05 -06:00
* Swerve Drive class representing and controlling the swerve drive.
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
public class SwerveDrive
2023-01-29 21:18:52 -06:00
{
/**
2023-02-13 14:37:05 -06:00
* Swerve Kinematics object utilizing second order kinematics.
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
public final SwerveKinematics2 kinematics;
2023-01-29 21:18:52 -06:00
/**
2023-02-13 14:37:05 -06:00
* Swerve drive configuration.
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
public final SwerveDriveConfiguration swerveDriveConfiguration;
/**
2023-02-13 14:37:05 -06:00
* Swerve odometry.
*/
2023-02-13 14:37:05 -06:00
public final SwerveDrivePoseEstimator swerveDrivePoseEstimator;
2023-01-29 21:18:52 -06:00
/**
2023-02-13 14:37:05 -06:00
* Swerve modules.
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
private final SwerveModule[] swerveModules;
2023-01-29 21:18:52 -06:00
/**
2023-02-13 14:37:05 -06:00
* Field object.
2023-01-29 21:18:52 -06:00
*/
public Field2d field = new Field2d();
2023-01-29 21:18:52 -06:00
/**
2023-02-13 14:37:05 -06:00
* Swerve controller for controlling heading of the robot.
2023-01-29 21:18:52 -06:00
*/
2023-02-24 22:10:33 -06:00
public SwerveController swerveController;
/**
* Trustworthiness of the internal model of how motors should be moving Measured in expected standard deviation
* (meters of position and degrees of rotation)
*/
2023-02-24 22:10:33 -06:00
public Matrix<N3, N1> stateStdDevs = VecBuilder.fill(0.1, 0.1, 0.1);
/**
* Trustworthiness of the vision system Measured in expected standard deviation (meters of position and degrees of
* rotation)
*/
public Matrix<N3, N1> visionMeasurementStdDevs = VecBuilder.fill(0.9, 0.9, 0.9);
/**
* Invert odometry readings of drive motor positions, used as a patch for debugging currently.
*/
public boolean invertOdometry = false;
/**
2023-02-13 14:37:05 -06:00
* Swerve IMU device for sensing the heading of the robot.
*/
private SwerveIMU imu;
/**
* Simulation of the swerve drive.
*/
private SwerveIMUSimulation simIMU;
/**
* Counter to synchronize the modules relative encoder with absolute encoder when not moving.
*/
private int moduleSynchronizationCounter = 0;
/**
* The last heading set in radians.
*/
private double lastHeadingRadians = 0;
2023-01-29 21:18:52 -06:00
/**
* Creates a new swerve drivebase subsystem. Robot is controlled via the {@link SwerveDrive#drive} method, or via the
* {@link SwerveDrive#setRawModuleStates} method. The {@link SwerveDrive#drive} method incorporates kinematics-- it
* takes a translation and rotation, as well as parameters for field-centric and closed-loop velocity control.
* {@link SwerveDrive#setRawModuleStates} takes a list of SwerveModuleStates and directly passes them to the modules.
* This subsystem also handles odometry.
*
* @param config The {@link SwerveDriveConfiguration} configuration to base the swerve drive off of.
* @param controllerConfig The {@link SwerveControllerConfiguration} to use when creating the
* {@link SwerveController}.
2023-01-29 21:18:52 -06:00
*/
public SwerveDrive(
SwerveDriveConfiguration config, SwerveControllerConfiguration controllerConfig)
2023-01-29 21:18:52 -06:00
{
2023-02-13 14:37:05 -06:00
swerveDriveConfiguration = config;
swerveController = new SwerveController(controllerConfig);
// Create Kinematics from swerve module locations.
kinematics = new SwerveKinematics2(config.moduleLocationsMeters);
2023-02-13 14:37:05 -06:00
// Create an integrator for angle if the robot is being simulated to emulate an IMU
// If the robot is real, instantiate the IMU instead.
if (SwerveDriveTelemetry.isSimulation)
2023-01-29 21:18:52 -06:00
{
simIMU = new SwerveIMUSimulation();
2023-02-13 14:37:05 -06:00
} else
{
imu = config.imu;
imu.factoryDefault();
2023-01-29 21:18:52 -06:00
}
2023-02-13 14:37:05 -06:00
this.swerveModules = config.modules;
2023-01-29 21:18:52 -06:00
// odometry = new SwerveDriveOdometry(kinematics, getYaw(), getModulePositions());
swerveDrivePoseEstimator =
new SwerveDrivePoseEstimator(
kinematics,
getYaw(),
getModulePositions(),
new Pose2d(new Translation2d(0, 0), Rotation2d.fromDegrees(0)),
stateStdDevs,
visionMeasurementStdDevs); // x,y,heading in radians; Vision measurement std dev, higher=less weight
2023-01-29 21:18:52 -06:00
2023-02-13 14:37:05 -06:00
zeroGyro();
// Initialize Telemetry
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.LOW.ordinal())
2023-02-22 20:50:16 -06:00
{
SmartDashboard.putData("Field", field);
}
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.HIGH.ordinal())
{
SwerveDriveTelemetry.maxSpeed = swerveDriveConfiguration.maxSpeed;
SwerveDriveTelemetry.maxAngularVelocity = swerveController.config.maxAngularVelocity;
SwerveDriveTelemetry.moduleCount = swerveModules.length;
SwerveDriveTelemetry.sizeFrontBack = Units.metersToInches(SwerveMath.getSwerveModule(swerveModules, true,
false).moduleLocation.getX() +
SwerveMath.getSwerveModule(swerveModules,
false,
false).moduleLocation.getX());
SwerveDriveTelemetry.sizeLeftRight = Units.metersToInches(SwerveMath.getSwerveModule(swerveModules, false,
true).moduleLocation.getY() +
SwerveMath.getSwerveModule(swerveModules,
false,
false).moduleLocation.getY());
SwerveDriveTelemetry.wheelLocations = new double[SwerveDriveTelemetry.moduleCount * 2];
for (SwerveModule module : swerveModules)
{
SwerveDriveTelemetry.wheelLocations[module.moduleNumber * 2] = Units.metersToInches(
module.configuration.moduleLocation.getX());
SwerveDriveTelemetry.wheelLocations[(module.moduleNumber * 2) + 1] = Units.metersToInches(
module.configuration.moduleLocation.getY());
}
SwerveDriveTelemetry.measuredStates = new double[SwerveDriveTelemetry.moduleCount * 2];
SwerveDriveTelemetry.desiredStates = new double[SwerveDriveTelemetry.moduleCount * 2];
2023-02-22 20:50:16 -06:00
}
2023-01-29 21:18:52 -06:00
}
/**
* 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.
2023-01-29 21:18:52 -06:00
*
2023-02-13 14:37:05 -06:00
* @param translation {@link 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).
* @param rotation Robot angular rate, in radians per second. CCW positive. Unaffected by field/robot
2023-02-13 14:37:05 -06:00
* relativity.
* @param fieldRelative Drive mode. True for field-relative, false for robot-relative.
* @param isOpenLoop Whether to use closed-loop velocity control. Set to true to disable closed-loop.
2023-02-13 14:37:05 -06:00
*/
public void drive(
Translation2d translation, double rotation, boolean fieldRelative, boolean isOpenLoop)
{
drive(translation, rotation, fieldRelative, isOpenLoop, false);
}
/**
* 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.
*
* @param translation {@link 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).
* @param rotation Robot angular rate, in radians per second. CCW positive. Unaffected by field/robot
* relativity.
* @param fieldRelative Drive mode. True for field-relative, false for robot-relative.
* @param isOpenLoop Whether to use closed-loop velocity control. Set to true to disable closed-loop.
* @param headingCorrection Whether to correct heading when driving translationally. Set to true to enable.
*/
public void drive(
Translation2d translation, double rotation, boolean fieldRelative, boolean isOpenLoop, boolean headingCorrection)
2023-01-29 21:18:52 -06:00
{
// Creates a robot-relative ChassisSpeeds object, converting from field-relative speeds if
// necessary.
ChassisSpeeds velocity =
fieldRelative
? ChassisSpeeds.fromFieldRelativeSpeeds(
translation.getX(), translation.getY(), rotation, getYaw())
: new ChassisSpeeds(translation.getX(), translation.getY(), rotation);
2023-02-13 14:37:05 -06:00
2023-04-08 12:31:07 -05:00
// Thank you to Jared Russell FRC254 for Open Loop Compensation Code
// https://www.chiefdelphi.com/t/whitepaper-swerve-drive-skew-and-second-order-kinematics/416964/5
double dtConstant = 0.009;
Pose2d robotPoseVel = new Pose2d(velocity.vxMetersPerSecond * dtConstant,
velocity.vyMetersPerSecond * dtConstant,
Rotation2d.fromRadians(velocity.omegaRadiansPerSecond * dtConstant));
Twist2d twistVel = SwerveMath.PoseLog(robotPoseVel);
velocity = new ChassisSpeeds(twistVel.dx / dtConstant, twistVel.dy / dtConstant,
twistVel.dtheta / dtConstant);
// Heading Angular Velocity Deadband, might make a configuration option later.
// Originally made by Team 1466 Webb Robotics.
if (headingCorrection)
{
if (Math.abs(rotation) < 0.01)
{
velocity.omegaRadiansPerSecond =
swerveController.headingCalculate(lastHeadingRadians, getYaw().getRadians());
} else
{
lastHeadingRadians = getYaw().getRadians();
}
}
2023-02-13 14:37:05 -06:00
// Display commanded speed for testing
if (SwerveDriveTelemetry.verbosity == TelemetryVerbosity.HIGH)
{
SmartDashboard.putString("RobotVelocity", velocity.toString());
}
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.HIGH.ordinal())
{
SwerveDriveTelemetry.desiredChassisSpeeds[1] = velocity.vyMetersPerSecond;
SwerveDriveTelemetry.desiredChassisSpeeds[0] = velocity.vxMetersPerSecond;
SwerveDriveTelemetry.desiredChassisSpeeds[2] = Math.toDegrees(velocity.omegaRadiansPerSecond);
}
2023-02-13 14:37:05 -06:00
// Calculate required module states via kinematics
SwerveModuleState2[] swerveModuleStates = kinematics.toSwerveModuleStates(velocity);
setRawModuleStates(swerveModuleStates, isOpenLoop);
2023-01-29 21:18:52 -06:00
}
2023-04-05 09:03:10 -05:00
/**
* Set the maximum speeds for desaturation.
*
2023-04-08 12:31:07 -05:00
* @param attainableMaxModuleSpeedMetersPerSecond The absolute max speed that a module can reach in meters per
* second.
2023-04-05 09:03:10 -05:00
* @param attainableMaxTranslationalSpeedMetersPerSecond The absolute max speed that your robot can reach while
* translating in meters per second.
2023-04-08 12:31:07 -05:00
* @param attainableMaxRotationalVelocityRadiansPerSecond The absolute max speed the robot can reach while rotating in
* radians per second.
2023-04-05 09:03:10 -05:00
*/
public void setMaximumSpeeds(
2023-04-08 12:31:07 -05:00
double attainableMaxModuleSpeedMetersPerSecond,
double attainableMaxTranslationalSpeedMetersPerSecond,
double attainableMaxRotationalVelocityRadiansPerSecond)
{
2023-04-05 09:03:10 -05:00
setMaximumSpeed(attainableMaxModuleSpeedMetersPerSecond);
2023-04-08 12:31:07 -05:00
swerveDriveConfiguration.attainableMaxTranslationalSpeedMetersPerSecond =
attainableMaxTranslationalSpeedMetersPerSecond;
swerveDriveConfiguration.attainableMaxRotationalVelocityRadiansPerSecond =
attainableMaxRotationalVelocityRadiansPerSecond;
2023-04-05 09:03:10 -05:00
}
2023-01-29 21:18:52 -06:00
/**
* Set the module states (azimuth and velocity) directly. Used primarily for auto pathing.
2023-01-29 21:18:52 -06:00
*
2023-02-13 14:37:05 -06:00
* @param desiredStates A list of SwerveModuleStates to send to the modules.
* @param isOpenLoop Whether to use closed-loop velocity control. Set to true to disable closed-loop.
2023-01-29 21:18:52 -06:00
*/
2023-04-08 12:31:07 -05:00
private void setRawModuleStates(SwerveModuleState2[] desiredStates, boolean isOpenLoop)
{
2023-02-13 14:37:05 -06:00
// Desaturates wheel speeds
2023-04-05 09:03:10 -05:00
if (swerveDriveConfiguration.attainableMaxTranslationalSpeedMetersPerSecond != 0 ||
2023-04-08 12:31:07 -05:00
swerveDriveConfiguration.attainableMaxRotationalVelocityRadiansPerSecond != 0)
{
2023-04-05 09:03:10 -05:00
SwerveKinematics2.desaturateWheelSpeeds(desiredStates, getRobotVelocity(),
2023-04-08 12:31:07 -05:00
swerveDriveConfiguration.maxSpeed,
swerveDriveConfiguration.attainableMaxTranslationalSpeedMetersPerSecond,
swerveDriveConfiguration.attainableMaxRotationalVelocityRadiansPerSecond);
} else
{
2023-04-05 09:03:10 -05:00
SwerveKinematics2.desaturateWheelSpeeds(desiredStates, swerveDriveConfiguration.maxSpeed);
2023-04-08 12:31:07 -05:00
}
2023-01-29 21:18:52 -06:00
2023-02-13 14:37:05 -06:00
// Sets states
2023-04-08 12:31:07 -05:00
for (SwerveModule module : swerveModules)
{
module.setDesiredState(desiredStates[module.moduleNumber], isOpenLoop, false);
2023-04-08 12:31:07 -05:00
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.HIGH.ordinal())
{
SwerveDriveTelemetry.desiredStates[module.moduleNumber *
2023-04-08 12:31:07 -05:00
2] = module.lastState.angle.getDegrees();
SwerveDriveTelemetry.desiredStates[(module.moduleNumber * 2) +
2023-04-08 12:31:07 -05:00
1] = module.lastState.speedMetersPerSecond;
}
2023-04-08 12:31:07 -05:00
if (SwerveDriveTelemetry.verbosity == TelemetryVerbosity.HIGH)
{
SmartDashboard.putNumber(
2023-04-08 12:31:07 -05:00
"Module[" + module.configuration.name + "] Speed Setpoint: ",
module.lastState.speedMetersPerSecond);
SmartDashboard.putNumber(
2023-04-08 12:31:07 -05:00
"Module[" + module.configuration.name + "] Angle Setpoint: ",
module.lastState.angle.getDegrees());
}
2023-01-29 21:18:52 -06:00
}
}
/**
* Set the module states (azimuth and velocity) directly. Used primarily for auto paths.
*
* @param desiredStates A list of SwerveModuleStates to send to the modules.
* @param isOpenLoop Whether to use closed-loop velocity control. Set to true to disable closed-loop.
*/
public void setModuleStates(SwerveModuleState2[] desiredStates, boolean isOpenLoop)
{
2023-04-08 12:31:07 -05:00
setRawModuleStates(kinematics.toSwerveModuleStates(kinematics.toChassisSpeeds(desiredStates)),
isOpenLoop);
}
2023-01-29 21:18:52 -06:00
/**
2023-04-08 12:31:07 -05:00
* Set chassis speeds with closed-loop velocity control and second order kinematics.
2023-01-29 21:18:52 -06:00
*
* @param chassisSpeeds Chassis speeds to set.
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
public void setChassisSpeeds(ChassisSpeeds chassisSpeeds)
2023-01-29 21:18:52 -06:00
{
2023-02-23 21:12:29 -06:00
SwerveDriveTelemetry.desiredChassisSpeeds[1] = chassisSpeeds.vyMetersPerSecond;
SwerveDriveTelemetry.desiredChassisSpeeds[0] = chassisSpeeds.vxMetersPerSecond;
SwerveDriveTelemetry.desiredChassisSpeeds[2] = Math.toDegrees(chassisSpeeds.omegaRadiansPerSecond);
setRawModuleStates(kinematics.toSwerveModuleStates(chassisSpeeds), false);
2023-01-29 21:18:52 -06:00
}
/**
2023-02-13 14:37:05 -06:00
* Gets the current pose (position and rotation) of the robot, as reported by odometry.
2023-01-29 21:18:52 -06:00
*
2023-02-13 14:37:05 -06:00
* @return The robot's pose
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
public Pose2d getPose()
2023-01-29 21:18:52 -06:00
{
2023-02-13 14:37:05 -06:00
return swerveDrivePoseEstimator.getEstimatedPosition();
2023-01-29 21:18:52 -06:00
}
/**
2023-02-13 14:37:05 -06:00
* Gets the current field-relative velocity (x, y and omega) of the robot
2023-01-29 21:18:52 -06:00
*
2023-02-13 14:37:05 -06:00
* @return A ChassisSpeeds object of the current field-relative velocity
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
public ChassisSpeeds getFieldVelocity()
2023-01-29 21:18:52 -06:00
{
2023-02-13 14:37:05 -06:00
// ChassisSpeeds has a method to convert from field-relative to robot-relative speeds,
// but not the reverse. However, because this transform is a simple rotation, negating the
// angle
2023-02-13 14:37:05 -06:00
// given as the robot angle reverses the direction of rotation, and the conversion is reversed.
return ChassisSpeeds.fromFieldRelativeSpeeds(
kinematics.toChassisSpeeds(getStates()), getYaw().unaryMinus());
2023-01-29 21:18:52 -06:00
}
/**
2023-02-13 14:37:05 -06:00
* Gets the current robot-relative velocity (x, y and omega) of the robot
2023-01-29 21:18:52 -06:00
*
2023-02-13 14:37:05 -06:00
* @return A ChassisSpeeds object of the current robot-relative velocity
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
public ChassisSpeeds getRobotVelocity()
2023-01-29 21:18:52 -06:00
{
2023-02-13 14:37:05 -06:00
return kinematics.toChassisSpeeds(getStates());
2023-01-29 21:18:52 -06:00
}
/**
2023-02-13 14:37:05 -06:00
* 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
2023-02-13 14:37:05 -06:00
* keep working.
2023-01-29 21:18:52 -06:00
*
2023-02-13 14:37:05 -06:00
* @param pose The pose to set the odometry to
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
public void resetOdometry(Pose2d pose)
2023-01-29 21:18:52 -06:00
{
2023-02-13 14:37:05 -06:00
swerveDrivePoseEstimator.resetPosition(getYaw(), getModulePositions(), pose);
2023-01-29 21:18:52 -06:00
}
/**
* Post the trajectory to the field
*
* @param trajectory the trajectory to post.
*/
public void postTrajectory(Trajectory trajectory)
{
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.LOW.ordinal())
{
field.getObject("Trajectory").setTrajectory(trajectory);
}
}
2023-01-29 21:18:52 -06:00
/**
2023-02-13 14:37:05 -06:00
* Gets the current module states (azimuth and velocity)
2023-01-29 21:18:52 -06:00
*
2023-02-13 14:37:05 -06:00
* @return A list of SwerveModuleStates containing the current module states
2023-01-29 21:18:52 -06:00
*/
public SwerveModuleState2[] getStates()
{
2023-02-13 14:37:05 -06:00
SwerveModuleState2[] states = new SwerveModuleState2[swerveDriveConfiguration.moduleCount];
for (SwerveModule module : swerveModules)
{
states[module.moduleNumber] = module.getState();
}
return states;
2023-01-29 21:18:52 -06:00
}
/**
* Gets the current module positions (azimuth and wheel position (meters)). Inverts the distance from each module if
* {@link #invertOdometry} is true.
2023-01-29 21:18:52 -06:00
*
2023-02-13 14:37:05 -06:00
* @return A list of SwerveModulePositions containg the current module positions
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
public SwerveModulePosition[] getModulePositions()
2023-01-29 21:18:52 -06:00
{
SwerveModulePosition[] positions =
new SwerveModulePosition[swerveDriveConfiguration.moduleCount];
2023-02-13 14:37:05 -06:00
for (SwerveModule module : swerveModules)
{
positions[module.moduleNumber] = module.getPosition();
if (invertOdometry)
{
positions[module.moduleNumber].distanceMeters *= -1;
}
2023-02-13 14:37:05 -06:00
}
return positions;
2023-01-29 21:18:52 -06:00
}
/**
2023-02-13 14:37:05 -06:00
* Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0.
2023-01-29 21:18:52 -06:00
*/
public void zeroGyro()
{
// Resets the real gyro or the angle accumulator, depending on whether the robot is being
// simulated
if (!SwerveDriveTelemetry.isSimulation)
2023-02-13 14:37:05 -06:00
{
2023-03-08 23:34:33 -06:00
imu.setOffset(imu.getRawRotation3d());
2023-02-13 14:37:05 -06:00
} else
{
simIMU.setAngle(0);
2023-02-13 14:37:05 -06:00
}
2023-02-22 20:50:16 -06:00
swerveController.lastAngleScalar = 0;
lastHeadingRadians = 0;
2023-02-13 14:37:05 -06:00
resetOdometry(new Pose2d(getPose().getTranslation(), new Rotation2d()));
2023-01-29 21:18:52 -06:00
}
/**
* Gets the current yaw angle of the robot, as reported by the imu. CCW positive, not wrapped.
2023-01-29 21:18:52 -06:00
*
2023-02-13 14:37:05 -06:00
* @return The yaw as a {@link Rotation2d} angle
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
public Rotation2d getYaw()
2023-01-29 21:18:52 -06:00
{
2023-02-13 14:37:05 -06:00
// Read the imu if the robot is real or the accumulator if the robot is simulated.
if (!SwerveDriveTelemetry.isSimulation)
2023-02-13 14:37:05 -06:00
{
return swerveDriveConfiguration.invertedIMU
? Rotation2d.fromRadians(imu.getRotation3d().unaryMinus().getZ())
: Rotation2d.fromRadians(imu.getRotation3d().getZ());
2023-02-13 14:37:05 -06:00
} else
{
return simIMU.getYaw();
2023-02-13 14:37:05 -06:00
}
2023-01-29 21:18:52 -06:00
}
/**
* Gets the current pitch angle of the robot, as reported by the imu.
2023-01-29 21:18:52 -06:00
*
2023-02-13 14:37:05 -06:00
* @return The heading as a {@link Rotation2d} angle
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
public Rotation2d getPitch()
2023-01-29 21:18:52 -06:00
{
2023-02-13 14:37:05 -06:00
// Read the imu if the robot is real or the accumulator if the robot is simulated.
if (!SwerveDriveTelemetry.isSimulation)
2023-02-13 14:37:05 -06:00
{
return swerveDriveConfiguration.invertedIMU
? Rotation2d.fromRadians(imu.getRotation3d().unaryMinus().getY())
: Rotation2d.fromRadians(imu.getRotation3d().getY());
2023-02-13 14:37:05 -06:00
} else
{
return simIMU.getPitch();
}
}
/**
* Gets the current roll angle of the robot, as reported by the imu.
*
* @return The heading as a {@link Rotation2d} angle
*/
public Rotation2d getRoll()
{
// Read the imu if the robot is real or the accumulator if the robot is simulated.
if (!SwerveDriveTelemetry.isSimulation)
{
return swerveDriveConfiguration.invertedIMU
? Rotation2d.fromRadians(imu.getRotation3d().unaryMinus().getX())
: Rotation2d.fromRadians(imu.getRotation3d().getX());
} else
{
return simIMU.getRoll();
}
}
/**
* Gets the current gyro {@link Rotation3d} of the robot, as reported by the imu.
*
* @return The heading as a {@link Rotation3d} angle
*/
public Rotation3d getGyroRotation3d()
{
// Read the imu if the robot is real or the accumulator if the robot is simulated.
if (!SwerveDriveTelemetry.isSimulation)
{
return swerveDriveConfiguration.invertedIMU
? imu.getRotation3d().unaryMinus()
: imu.getRotation3d();
} else
{
return simIMU.getGyroRotation3d();
2023-02-13 14:37:05 -06:00
}
2023-01-29 21:18:52 -06:00
}
/**
* Gets current acceleration of the robot in m/s/s. If gyro unsupported returns empty.
*
* @return acceleration of the robot as a {@link Translation3d}
*/
public Optional<Translation3d> getAccel()
{
if (!SwerveDriveTelemetry.isSimulation)
{
return imu.getAccel();
} else
{
return simIMU.getAccel();
}
}
2023-01-29 21:18:52 -06:00
/**
2023-02-13 14:37:05 -06:00
* Sets the drive motors to brake/coast mode.
*
* @param brake True to set motors to brake mode, false for coast.
2023-01-29 21:18:52 -06:00
*/
public void setMotorIdleMode(boolean brake)
2023-01-29 21:18:52 -06:00
{
2023-02-13 14:37:05 -06:00
for (SwerveModule swerveModule : swerveModules)
{
swerveModule.setMotorBrake(brake);
}
2023-01-29 21:18:52 -06:00
}
/**
* Set the maximum speed of the drive motors, modified {@link SwerveControllerConfiguration#maxSpeed} and
* {@link SwerveDriveConfiguration#maxSpeed} which is used for the
* {@link SwerveDrive#setRawModuleStates(SwerveModuleState2[], boolean)} function and
* {@link 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.
*
* @param maximumSpeed Maximum speed for the drive motors in meters / second.
* @param 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
* {@link SwerveDrive#replaceSwerveModuleFeedforward(SimpleMotorFeedforward)}
*/
public void setMaximumSpeed(double maximumSpeed, boolean updateModuleFeedforward)
{
swerveDriveConfiguration.maxSpeed = maximumSpeed;
swerveController.config.maxSpeed = maximumSpeed;
for (SwerveModule module : swerveModules)
{
module.configuration.maxSpeed = maximumSpeed;
if (updateModuleFeedforward)
{
module.feedforward = module.configuration.createDriveFeedforward();
}
}
}
/**
* Set the maximum speed of the drive motors, modified {@link SwerveControllerConfiguration#maxSpeed} and
* {@link SwerveDriveConfiguration#maxSpeed} which is used for the
* {@link SwerveDrive#setRawModuleStates(SwerveModuleState2[], boolean)} function and
* {@link 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
* {@link SwerveModule#feedforward}.
*
* @param maximumSpeed Maximum speed for the drive motors in meters / second.
*/
public void setMaximumSpeed(double maximumSpeed)
{
setMaximumSpeed(maximumSpeed, true);
}
2023-01-29 21:18:52 -06:00
/**
* Point all modules toward the robot center, thus making the robot very difficult to move. Forcing the robot to keep
* the current pose.
2023-01-29 21:18:52 -06:00
*/
public void lockPose()
2023-01-29 21:18:52 -06:00
{
// Sets states
2023-02-13 14:37:05 -06:00
for (SwerveModule swerveModule : swerveModules)
{
SwerveModuleState2 desiredState =
new SwerveModuleState2(0, swerveModule.configuration.moduleLocation.getAngle(), 0);
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.HIGH.ordinal())
{
SwerveDriveTelemetry.desiredStates[swerveModule.moduleNumber * 2] =
desiredState.angle.getDegrees();
SwerveDriveTelemetry.desiredStates[(swerveModule.moduleNumber * 2) + 1] =
desiredState.speedMetersPerSecond;
}
swerveModule.setDesiredState(desiredState, false, true);
2023-02-13 14:37:05 -06:00
}
// Update kinematics because we are not using setModuleStates
kinematics.toSwerveModuleStates(new ChassisSpeeds());
2023-01-29 21:18:52 -06:00
}
/**
2023-02-13 14:37:05 -06:00
* Get the swerve module poses and on the field relative to the robot.
2023-01-29 21:18:52 -06:00
*
2023-02-13 14:37:05 -06:00
* @param robotPose Robot pose.
* @return Swerve module poses.
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
public Pose2d[] getSwerveModulePoses(Pose2d robotPose)
2023-01-29 21:18:52 -06:00
{
2023-02-13 14:37:05 -06:00
Pose2d[] poseArr = new Pose2d[swerveDriveConfiguration.moduleCount];
List<Pose2d> poses = new ArrayList<>();
for (SwerveModule module : swerveModules)
{
poses.add(
robotPose.plus(
new Transform2d(module.configuration.moduleLocation, module.getState().angle)));
2023-02-13 14:37:05 -06:00
}
return poses.toArray(poseArr);
2023-01-29 21:18:52 -06:00
}
/**
2023-02-13 14:37:05 -06:00
* Setup the swerve module feedforward.
2023-01-29 21:18:52 -06:00
*
2023-02-13 14:37:05 -06:00
* @param feedforward Feedforward for the drive motor on swerve modules.
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
public void replaceSwerveModuleFeedforward(SimpleMotorFeedforward feedforward)
2023-01-29 21:18:52 -06:00
{
2023-02-13 14:37:05 -06:00
for (SwerveModule swerveModule : swerveModules)
{
swerveModule.feedforward = feedforward;
}
2023-01-29 21:18:52 -06:00
}
/**
* 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.
2023-01-29 21:18:52 -06:00
*/
2023-02-13 14:37:05 -06:00
public void updateOdometry()
2023-01-29 21:18:52 -06:00
{
2023-02-13 14:37:05 -06:00
// Update odometry
swerveDrivePoseEstimator.update(getYaw(), getModulePositions());
2023-01-29 21:18:52 -06:00
2023-02-13 14:37:05 -06:00
// Update angle accumulator if the robot is simulated
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.HIGH.ordinal())
{
Pose2d[] modulePoses = getSwerveModulePoses(swerveDrivePoseEstimator.getEstimatedPosition());
if (SwerveDriveTelemetry.isSimulation)
{
simIMU.updateOdometry(
kinematics,
getStates(),
modulePoses,
field);
}
ChassisSpeeds measuredChassisSpeeds = getRobotVelocity();
SwerveDriveTelemetry.measuredChassisSpeeds[1] = measuredChassisSpeeds.vyMetersPerSecond;
SwerveDriveTelemetry.measuredChassisSpeeds[0] = measuredChassisSpeeds.vxMetersPerSecond;
SwerveDriveTelemetry.measuredChassisSpeeds[2] = Math.toDegrees(measuredChassisSpeeds.omegaRadiansPerSecond);
SwerveDriveTelemetry.robotRotation = getYaw().getDegrees();
2023-01-29 21:18:52 -06:00
}
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.LOW.ordinal())
{
field.setRobotPose(swerveDrivePoseEstimator.getEstimatedPosition());
}
2023-02-13 14:37:05 -06:00
double sumOmega = 0;
2023-02-13 14:37:05 -06:00
for (SwerveModule module : swerveModules)
2023-01-29 21:18:52 -06:00
{
SwerveModuleState2 moduleState = module.getState();
sumOmega += Math.abs(moduleState.omegaRadPerSecond);
if (SwerveDriveTelemetry.verbosity == TelemetryVerbosity.HIGH)
{
SmartDashboard.putNumber(
2023-04-08 12:31:07 -05:00
"Module[" + module.configuration.name + "] Relative Encoder", module.getRelativePosition());
SmartDashboard.putNumber(
2023-04-08 12:31:07 -05:00
"Module[" + module.configuration.name + "] Absolute Encoder", module.getAbsolutePosition());
}
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.HIGH.ordinal())
{
SwerveDriveTelemetry.measuredStates[module.moduleNumber * 2] = moduleState.angle.getDegrees();
SwerveDriveTelemetry.measuredStates[(module.moduleNumber * 2) + 1] = moduleState.speedMetersPerSecond;
}
2023-01-29 21:18:52 -06:00
}
// If the robot isn't moving synchronize the encoders every 100ms (Inspired by democrat's SDS
// lib)
// To ensure that everytime we initialize it works.
if (sumOmega <= .01 && ++moduleSynchronizationCounter > 5)
{
synchronizeModuleEncoders();
moduleSynchronizationCounter = 0;
}
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.HIGH.ordinal())
{
SwerveDriveTelemetry.updateData();
}
2023-01-29 21:18:52 -06:00
}
/**
* Synchronize angle motor integrated encoders with data from absolute encoders.
*/
public void synchronizeModuleEncoders()
{
for (SwerveModule module : swerveModules)
{
module.queueSynchronizeEncoders();
}
}
/**
* Add a vision measurement to the {@link SwerveDrivePoseEstimator} and update the {@link SwerveIMU} gyro reading with
* the given timestamp of the vision measurement.
*
* @param robotPose Robot {@link Pose2d} as measured by vision.
* @param timestamp Timestamp the measurement was taken as time since startup, should be taken from
* {@link Timer#getFPGATimestamp()} or similar sources.
* @param soft Add vision estimate using the
* {@link SwerveDrivePoseEstimator#addVisionMeasurement(Pose2d, double)} function, or hard
* reset odometry with the given position with
* {@link edu.wpi.first.math.kinematics.SwerveDriveOdometry#resetPosition(Rotation2d,
* SwerveModulePosition[], Pose2d)}.
* @param trustWorthiness Trust level of vision reading when using a soft measurement, used to multiply the standard
* deviation. Set to 1 for full trust.
*/
public void addVisionMeasurement(Pose2d robotPose, double timestamp, boolean soft, double trustWorthiness)
{
if (soft)
{
swerveDrivePoseEstimator.addVisionMeasurement(robotPose, timestamp,
visionMeasurementStdDevs.times(1.0 / trustWorthiness));
} else
{
swerveDrivePoseEstimator.resetPosition(
robotPose.getRotation(), getModulePositions(), robotPose);
}
}
/**
* Add a vision measurement to the {@link SwerveDrivePoseEstimator} and update the {@link SwerveIMU} gyro reading with
* the given timestamp of the vision measurement.
*
* @param robotPose Robot {@link Pose2d} as measured by vision.
* @param timestamp Timestamp the measurement was taken as time since startup, should be taken from
* {@link Timer#getFPGATimestamp()} or similar sources.
* @param soft Add vision estimate using the
* {@link SwerveDrivePoseEstimator#addVisionMeasurement(Pose2d, double)} function, or
* hard reset odometry with the given position with
* {@link edu.wpi.first.math.kinematics.SwerveDriveOdometry#resetPosition(Rotation2d,
* SwerveModulePosition[], Pose2d)}.
* @param visionMeasurementStdDevs Vision measurement standard deviation that will be sent to the
* {@link SwerveDrivePoseEstimator}.
*/
public void addVisionMeasurement(Pose2d robotPose, double timestamp, boolean soft,
Matrix<N3, N1> visionMeasurementStdDevs)
{
this.visionMeasurementStdDevs = visionMeasurementStdDevs;
addVisionMeasurement(robotPose, timestamp, soft, 1);
}
/**
* Set the expected gyroscope angle using a {@link Rotation3d} object. To reset gyro, set to a new
* {@link Rotation3d}.
*
* @param gyro expected gyroscope angle.
*/
public void setGyro(Rotation3d gyro)
{
imu.setOffset(imu.getRawRotation3d().minus(gyro));
}
/**
* Helper function to get the {@link SwerveDrive#swerveController} for the {@link SwerveDrive} which can be used to
* generate {@link ChassisSpeeds} for the robot to orient it correctly given axis or angles, and apply
* {@link edu.wpi.first.math.filter.SlewRateLimiter} to given inputs. Important functions to look at are
* {@link SwerveController#getTargetSpeeds(double, double, double, double)},
* {@link SwerveController#addSlewRateLimiters(SlewRateLimiter, SlewRateLimiter, SlewRateLimiter)},
* {@link SwerveController#getRawTargetSpeeds(double, double, double)}.
*
* @return {@link SwerveController} for the {@link SwerveDrive}.
*/
public SwerveController getSwerveController()
{
return swerveController;
}
/**
* Get the {@link SwerveModule}s associated with the {@link SwerveDrive}.
*
* @return {@link SwerveModule} array specified by configurations.
*/
public SwerveModule[] getModules()
{
return swerveDriveConfiguration.modules;
}
/**
* Reset the drive encoders on the robot, useful when manually resetting the robot without a reboot, like in
* autonomous.
*/
public void resetEncoders()
{
for (SwerveModule module : swerveModules)
{
module.configuration.driveMotor.setPosition(0);
}
}
2023-02-13 14:37:05 -06:00
}