Files
YAGSL/swervelib/SwerveDrive.java

1615 lines
66 KiB
Java
Raw Permalink Normal View History

2023-02-13 17:21:24 -06:00
package swervelib;
2023-01-29 21:18:52 -06:00
2024-12-09 23:26:04 +00:00
import static edu.wpi.first.hal.FRCNetComm.tInstances.kRobotDriveSwerve_YAGSL;
import static edu.wpi.first.hal.FRCNetComm.tResourceType.kResourceType_RobotDrive;
import static edu.wpi.first.units.Units.Inches;
import static edu.wpi.first.units.Units.KilogramSquareMeters;
import static edu.wpi.first.units.Units.Kilograms;
import static edu.wpi.first.units.Units.Meters;
import static edu.wpi.first.units.Units.Newtons;
2024-12-17 18:49:55 +00:00
import static edu.wpi.first.units.Units.RadiansPerSecond;
2024-12-09 23:26:04 +00:00
import static edu.wpi.first.units.Units.Seconds;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.hal.HAL;
import edu.wpi.first.math.Matrix;
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;
2023-01-29 21:18:52 -06:00
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
2023-01-29 21:18:52 -06:00
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.numbers.N1;
import edu.wpi.first.math.numbers.N3;
2024-12-09 23:26:04 +00:00
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.trajectory.Trajectory;
2023-02-23 21:12:29 -06:00
import edu.wpi.first.math.util.Units;
2024-12-17 18:49:55 +00:00
import edu.wpi.first.networktables.DoublePublisher;
import edu.wpi.first.networktables.NetworkTableInstance;
2024-12-09 23:26:04 +00:00
import edu.wpi.first.units.measure.AngularVelocity;
import edu.wpi.first.units.measure.Force;
import edu.wpi.first.units.measure.LinearVelocity;
import edu.wpi.first.wpilibj.Alert;
import edu.wpi.first.wpilibj.Alert.AlertType;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Notifier;
2024-12-09 23:26:04 +00:00
import edu.wpi.first.wpilibj.TimedRobot;
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;
2024-02-02 18:55:29 -06:00
import java.util.HashMap;
2023-04-08 12:31:07 -05:00
import java.util.List;
2024-02-02 18:55:29 -06:00
import java.util.Map;
2023-04-08 12:31:07 -05:00
import java.util.Optional;
import java.util.concurrent.locks.Lock;
import java.util.concurrent.locks.ReentrantLock;
2024-12-09 23:26:04 +00:00
import org.ironmaple.simulation.SimulatedArena;
import org.ironmaple.simulation.drivesims.AbstractDriveTrainSimulation;
import org.ironmaple.simulation.drivesims.SwerveDriveSimulation;
import org.ironmaple.simulation.drivesims.configs.DriveTrainSimulationConfig;
2025-01-06 15:44:15 +00:00
import org.ironmaple.simulation.drivesims.configs.SwerveModuleSimulationConfig;
import swervelib.encoders.CANCoderSwerve;
import swervelib.imu.Pigeon2Swerve;
2023-02-13 17:21:24 -06:00
import swervelib.imu.SwerveIMU;
import swervelib.math.SwerveMath;
import swervelib.motors.TalonFXSwerve;
2024-02-02 18:55:29 -06:00
import swervelib.parser.Cache;
2023-02-13 17:21:24 -06:00
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
*/
2025-02-22 06:15:56 +00:00
public class SwerveDrive implements AutoCloseable
2023-01-29 21:18:52 -06:00
{
/**
2023-11-09 17:32:48 -06:00
* Swerve Kinematics object.
2023-01-29 21:18:52 -06:00
*/
public final SwerveDriveKinematics 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.
*/
public final SwerveDrivePoseEstimator swerveDrivePoseEstimator;
2024-02-02 18:55:29 -06:00
/**
* IMU reading cache for robot readings.
*/
public final Cache<Rotation3d> imuReadingCache;
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;
/**
* WPILib {@link Notifier} to keep odometry up to date.
*/
private final Notifier odometryThread;
/**
* Odometry lock to ensure thread safety.
*/
2024-12-17 18:49:55 +00:00
private final Lock odometryLock = new ReentrantLock();
2024-01-17 09:17:39 -06:00
/**
2024-01-22 15:11:18 -06:00
* Alert to recommend Tuner X if the configuration is compatible.
2024-01-17 09:17:39 -06:00
*/
2024-12-17 18:49:55 +00:00
private final Alert tunerXRecommendation = new Alert("Swerve Drive",
"Your Swerve Drive is compatible with Tuner X swerve generator, please consider using that instead of YAGSL. More information here!\n" +
"https://pro.docs.ctr-electronics.com/en/latest/docs/tuner/tuner-swerve/index.html",
AlertType.kWarning);
/**
* NT4 Publisher for the IMU reading.
*/
private final DoublePublisher rawIMUPublisher
= NetworkTableInstance.getDefault()
2025-02-22 06:15:56 +00:00
.getTable(
"SmartDashboard")
2024-12-17 18:49:55 +00:00
.getDoubleTopic(
2025-02-22 06:15:56 +00:00
"swerve/imu/raw")
2024-12-17 18:49:55 +00:00
.publish();
/**
* NT4 Publisher for the IMU reading adjusted by offset and inversion.
*/
private final DoublePublisher adjustedIMUPublisher
= NetworkTableInstance.getDefault()
2025-02-22 06:15:56 +00:00
.getTable(
"SmartDashboard")
2024-12-17 18:49:55 +00:00
.getDoubleTopic(
2025-02-22 06:15:56 +00:00
"swerve/imu/adjusted")
2024-12-17 18:49:55 +00:00
.publish();
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
*/
2024-12-17 18:49:55 +00: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;
/**
* Correct chassis velocity in {@link SwerveDrive#drive(Translation2d, double, boolean, boolean)} using 254's
* correction.
*/
2024-12-17 18:49:55 +00:00
public boolean chassisVelocityCorrection = true;
2024-10-14 13:22:11 -05:00
/**
* Correct chassis velocity in {@link SwerveDrive#setChassisSpeeds(ChassisSpeeds chassisSpeeds)} (auto) using 254's
* correction during auto.
*/
2024-12-17 18:49:55 +00:00
public boolean autonomousChassisVelocityCorrection = false;
2024-10-14 13:22:11 -05:00
/**
2024-11-06 00:10:07 +00:00
* Correct for skew that scales with angular velocity in
* {@link SwerveDrive#drive(Translation2d, double, boolean, boolean)}
2024-10-14 13:22:11 -05:00
*/
2024-12-17 18:49:55 +00:00
public boolean angularVelocityCorrection = false;
2024-11-06 00:10:07 +00:00
/**
* Correct for skew that scales with angular velocity in
* {@link SwerveDrive#setChassisSpeeds(ChassisSpeeds chassisSpeeds)} during auto.
2024-10-14 13:22:11 -05:00
*/
2024-12-17 18:49:55 +00:00
public boolean autonomousAngularVelocityCorrection = false;
2024-10-14 13:22:11 -05:00
/**
* Angular Velocity Correction Coefficent (expected values between -0.15 and 0.15).
*/
2024-12-17 18:49:55 +00:00
public double angularVelocityCoefficient = 0;
2023-11-09 17:32:48 -06:00
/**
* Whether to correct heading when driving translationally. Set to true to enable.
*/
2024-12-17 18:49:55 +00:00
public boolean headingCorrection = false;
2024-12-09 23:26:04 +00:00
/**
* MapleSim SwerveDrive.
*/
private SwerveDriveSimulation mapleSimDrive;
2024-06-12 15:10:29 -05:00
/**
* Amount of seconds the duration of the timestep the speeds should be applied for.
*/
2024-12-17 18:49:55 +00:00
private double discretizationdtSeconds = 0.02;
2024-01-22 15:11:18 -06:00
/**
* Deadband for speeds in heading correction.
*/
2024-12-17 18:49:55 +00:00
private double HEADING_CORRECTION_DEADBAND = 0.01;
/**
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.
*/
2024-12-17 18:49:55 +00:00
private SwerveIMUSimulation simIMU;
/**
* Counter to synchronize the modules relative encoder with absolute encoder when not moving.
*/
2024-12-17 18:49:55 +00:00
private int moduleSynchronizationCounter = 0;
/**
* The last heading set in radians.
*/
2024-12-17 18:49:55 +00:00
private double lastHeadingRadians = 0;
2023-11-09 17:32:48 -06:00
/**
* The absolute max speed that your robot can reach while translating in meters per second.
*/
2024-12-17 18:49:55 +00:00
private double attainableMaxTranslationalSpeedMetersPerSecond = 0;
2023-11-09 17:32:48 -06:00
/**
* The absolute max speed the robot can reach while rotating radians per second.
*/
2024-12-17 18:49:55 +00:00
private double attainableMaxRotationalVelocityRadiansPerSecond = 0;
2023-11-09 17:32:48 -06:00
/**
* Maximum speed of the robot in meters per second.
*/
2024-12-17 18:49:55 +00:00
private double maxChassisSpeedMPS;
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}.
2024-12-09 23:26:04 +00:00
* @param maxSpeedMPS Maximum speed of the robot in meters per second, remember to use
* {@link Units#feetToMeters(double)} if you have feet per second!
* @param startingPose Starting {@link Pose2d} on the field.
2023-01-29 21:18:52 -06:00
*/
public SwerveDrive(
2024-12-09 23:26:04 +00:00
SwerveDriveConfiguration config, SwerveControllerConfiguration controllerConfig, double maxSpeedMPS,
Pose2d startingPose)
2023-01-29 21:18:52 -06:00
{
2025-02-22 06:15:56 +00:00
this.attainableMaxTranslationalSpeedMetersPerSecond = this.maxChassisSpeedMPS = maxSpeedMPS;
this.attainableMaxRotationalVelocityRadiansPerSecond = Math.PI *
2; // Defaulting to something reasonable for most robots
2023-02-13 14:37:05 -06:00
swerveDriveConfiguration = config;
swerveController = new SwerveController(controllerConfig);
// Create Kinematics from swerve module locations.
kinematics = new SwerveDriveKinematics(config.moduleLocationsMeters);
odometryThread = new Notifier(this::updateOdometry);
2024-12-09 23:26:04 +00:00
this.swerveModules = config.modules;
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
{
2024-12-09 23:26:04 +00:00
DriveTrainSimulationConfig simulationConfig = DriveTrainSimulationConfig.Default()
.withBumperSize(
Meters.of(config.getTracklength())
.plus(Inches.of(5)),
Meters.of(config.getTrackwidth())
.plus(Inches.of(5)))
.withRobotMass(Kilograms.of(config.physicalCharacteristics.robotMassKg))
.withCustomModuleTranslations(config.moduleLocationsMeters)
.withGyro(config.getGyroSim())
2025-01-06 15:44:15 +00:00
.withSwerveModule(new SwerveModuleSimulationConfig(
2025-02-22 06:15:56 +00:00
config.getDriveMotorSim(),
config.getAngleMotorSim(),
config.physicalCharacteristics.conversionFactor.drive.gearRatio,
config.physicalCharacteristics.conversionFactor.angle.gearRatio,
Volts.of(config.physicalCharacteristics.driveFrictionVoltage),
Volts.of(config.physicalCharacteristics.angleFrictionVoltage),
Inches.of(
config.physicalCharacteristics.conversionFactor.drive.diameter /
2),
KilogramSquareMeters.of(0.02),
config.physicalCharacteristics.wheelGripCoefficientOfFriction)
2025-01-06 15:44:15 +00:00
);
2024-12-09 23:26:04 +00:00
mapleSimDrive = new SwerveDriveSimulation(simulationConfig, startingPose);
// feed module simulation instances to modules
for (int i = 0; i < swerveModules.length; i++)
{
this.swerveModules[i].configureModuleSimulation(mapleSimDrive.getModules()[i], config.physicalCharacteristics);
}
// register the drivetrain simulation
SimulatedArena.getInstance().addDriveTrainSimulation(mapleSimDrive);
simIMU = new SwerveIMUSimulation(mapleSimDrive.getGyroSimulation());
2024-02-02 18:55:29 -06:00
imuReadingCache = new Cache<>(simIMU::getGyroRotation3d, 5L);
2023-02-13 14:37:05 -06:00
} else
{
imu = config.imu;
imu.factoryDefault();
2024-02-02 18:55:29 -06:00
imuReadingCache = new Cache<>(imu::getRotation3d, 5L);
2023-01-29 21:18:52 -06:00
}
// odometry = new SwerveDriveOdometry(kinematics, getYaw(), getModulePositions());
swerveDrivePoseEstimator =
new SwerveDrivePoseEstimator(
kinematics,
getYaw(),
getModulePositions(),
2024-12-09 23:26:04 +00:00
startingPose); // x,y,heading in radians; Vision measurement std dev, higher=less weight
2025-03-19 03:45:47 +00:00
//
// Rotation3d currentGyro = imuReadingCache.getValue();
// double offset = currentGyro.getZ() +
// startingPose.getRotation().getRadians();
// setGyroOffset(new Rotation3d(currentGyro.getX(), currentGyro.getY(), offset));
// Initialize Telemetry
2024-06-12 15:10:29 -05:00
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.POSE.ordinal())
2023-02-22 20:50:16 -06:00
{
SmartDashboard.putData("Field", field);
}
2024-06-12 15:10:29 -05:00
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.INFO.ordinal())
{
2023-11-09 17:32:48 -06:00
SwerveDriveTelemetry.maxSpeed = maxSpeedMPS;
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];
2024-12-09 23:26:04 +00:00
SwerveDriveTelemetry.desiredStatesObj = new SwerveModuleState[SwerveDriveTelemetry.moduleCount];
SwerveDriveTelemetry.measuredStatesObj = new SwerveModuleState[SwerveDriveTelemetry.moduleCount];
2023-02-22 20:50:16 -06:00
}
2024-12-09 23:26:04 +00:00
setOdometryPeriod(SwerveDriveTelemetry.isSimulation ? 0.004 : 0.02);
2024-01-18 12:11:22 -06:00
checkIfTunerXCompatible();
2024-12-09 23:26:04 +00:00
HAL.report(kResourceType_RobotDrive, kRobotDriveSwerve_YAGSL);
2023-01-29 21:18:52 -06:00
}
2025-02-22 06:15:56 +00:00
@Override
2025-03-19 03:45:47 +00:00
public void close()
{
2025-02-22 06:15:56 +00:00
imu.close();
tunerXRecommendation.close();
2025-03-19 03:45:47 +00:00
for (var module : swerveModules)
{
2025-02-22 06:15:56 +00:00
module.close();
}
}
2024-02-02 18:55:29 -06:00
/**
* Update the cache validity period for the robot.
*
* @param imu IMU reading cache validity period in milliseconds.
* @param driveMotor Drive motor reading cache in milliseconds.
* @param absoluteEncoder Absolute encoder reading cache in milliseconds.
*/
public void updateCacheValidityPeriods(long imu, long driveMotor, long absoluteEncoder)
{
imuReadingCache.updateValidityPeriod(imu);
for (SwerveModule module : swerveModules)
{
module.drivePositionCache.updateValidityPeriod(driveMotor);
module.driveVelocityCache.updateValidityPeriod(driveMotor);
module.absolutePositionCache.updateValidityPeriod(absoluteEncoder);
}
}
/**
* Check all components to ensure that Tuner X Swerve Generator is recommended instead.
*/
private void checkIfTunerXCompatible()
{
boolean compatible = imu instanceof Pigeon2Swerve;
for (SwerveModule module : swerveModules)
{
compatible = compatible && module.getDriveMotor() instanceof TalonFXSwerve &&
module.getAngleMotor() instanceof TalonFXSwerve &&
module.getAbsoluteEncoder() instanceof CANCoderSwerve;
if (!compatible)
{
break;
}
}
if (compatible)
{
tunerXRecommendation.set(true);
}
}
2023-01-29 21:18:52 -06:00
/**
* Set the odometry update period in seconds.
*
* @param period period in seconds.
*/
public void setOdometryPeriod(double period)
{
odometryThread.stop();
2025-03-19 03:45:47 +00:00
if (SwerveDriveTelemetry.isSimulation)
{
SimulatedArena.overrideSimulationTimings(Seconds.of(period), 1);
}
odometryThread.startPeriodic(period);
}
/**
* Stop the odometry thread in favor of manually updating odometry.
*/
public void stopOdometryThread()
{
odometryThread.stop();
2025-03-19 03:45:47 +00:00
if (SwerveDriveTelemetry.isSimulation)
{
SimulatedArena.overrideSimulationTimings(Seconds.of(TimedRobot.kDefaultPeriod), 5);
}
}
/**
2023-11-09 17:32:48 -06:00
* Set the conversion factor for the angle/azimuth motor controller.
2023-01-29 21:18:52 -06:00
*
2023-11-09 17:32:48 -06:00
* @param conversionFactor Angle motor conversion factor for PID, should be generated from
* {@link SwerveMath#calculateDegreesPerSteeringRotation(double, double)} or calculated.
2023-02-13 14:37:05 -06:00
*/
2023-11-09 17:32:48 -06:00
public void setAngleMotorConversionFactor(double conversionFactor)
{
2023-11-09 17:32:48 -06:00
for (SwerveModule module : swerveModules)
{
module.setAngleMotorConversionFactor(conversionFactor);
}
}
/**
2023-11-09 17:32:48 -06:00
* Set the conversion factor for the drive motor controller.
*
2023-11-09 17:32:48 -06:00
* @param conversionFactor Drive motor conversion factor for PID, should be generated from
* {@link SwerveMath#calculateMetersPerRotation(double, double, double)} or calculated.
*/
2023-11-09 17:32:48 -06:00
public void setDriveMotorConversionFactor(double conversionFactor)
{
for (SwerveModule module : swerveModules)
{
module.setDriveMotorConversionFactor(conversionFactor);
}
}
2024-01-22 15:11:18 -06:00
/**
* Fetch the latest odometry heading, should be trusted over {@link SwerveDrive#getYaw()}.
*
* @return {@link Rotation2d} of the robot heading.
*/
public Rotation2d getOdometryHeading()
{
return swerveDrivePoseEstimator.getEstimatedPosition().getRotation();
}
2023-11-09 17:32:48 -06:00
/**
* Set the heading correction capabilities of YAGSL.
*
* @param state {@link SwerveDrive#headingCorrection} state.
*/
public void setHeadingCorrection(boolean state)
{
setHeadingCorrection(state, HEADING_CORRECTION_DEADBAND);
}
/**
* Set the heading correction capabilities of YAGSL.
*
* @param state {@link SwerveDrive#headingCorrection} state.
* @param deadband {@link SwerveDrive#HEADING_CORRECTION_DEADBAND} deadband.
*/
public void setHeadingCorrection(boolean state, double deadband)
2023-11-09 17:32:48 -06:00
{
headingCorrection = state;
HEADING_CORRECTION_DEADBAND = deadband;
2023-11-09 17:32:48 -06:00
}
2024-06-12 15:10:29 -05:00
/**
2024-06-12 15:58:37 -05:00
* Tertiary method of controlling the drive base given velocity in both field oriented and robot oriented at the same
2025-01-06 15:44:15 +00:00
* time. The inputs are added together so this is not intended to be used to give the driver both methods of control.
2024-06-12 15:58:37 -05:00
*
2024-06-12 15:10:29 -05:00
* @param fieldOrientedVelocity The field oriented velocties to use
* @param robotOrientedVelocity The robot oriented velocties to use
*/
2025-01-06 15:44:15 +00:00
public void driveFieldOrientedAndRobotOriented(ChassisSpeeds fieldOrientedVelocity,
2024-06-12 15:58:37 -05:00
ChassisSpeeds robotOrientedVelocity)
2024-06-12 15:10:29 -05:00
{
2025-01-06 15:44:15 +00:00
drive(ChassisSpeeds.fromFieldRelativeSpeeds(fieldOrientedVelocity, getOdometryHeading())
.plus(robotOrientedVelocity));
2024-06-12 15:10:29 -05:00
}
2023-11-09 17:32:48 -06:00
/**
* Secondary method of controlling the drive base given velocity and adjusting it for field oriented use.
*
2025-01-06 15:44:15 +00:00
* @param fieldRelativeSpeeds Velocity of the robot desired.
2023-11-09 17:32:48 -06:00
*/
2025-01-06 15:44:15 +00:00
public void driveFieldOriented(ChassisSpeeds fieldRelativeSpeeds)
2023-11-09 17:32:48 -06:00
{
2025-01-06 15:44:15 +00:00
drive(ChassisSpeeds.fromFieldRelativeSpeeds(fieldRelativeSpeeds, getOdometryHeading()));
2023-11-09 17:32:48 -06:00
}
/**
* Secondary method of controlling the drive base given velocity and adjusting it for field oriented use.
*
2025-01-06 15:44:15 +00:00
* @param fieldRelativeSpeeds Velocity of the robot desired.
* @param centerOfRotationMeters The center of rotation in meters, 0 is the center of the robot.
*/
2025-01-06 15:44:15 +00:00
public void driveFieldOriented(ChassisSpeeds fieldRelativeSpeeds, Translation2d centerOfRotationMeters)
{
2025-01-06 15:44:15 +00:00
drive(ChassisSpeeds.fromFieldRelativeSpeeds(fieldRelativeSpeeds, getOdometryHeading()), centerOfRotationMeters);
}
2023-11-09 17:32:48 -06:00
/**
* Secondary method for controlling the drivebase. Given a simple {@link ChassisSpeeds} set the swerve module states,
* to achieve the goal.
*
* @param velocity The desired robot-oriented {@link ChassisSpeeds} for the robot to achieve.
*/
public void drive(ChassisSpeeds velocity)
{
drive(velocity, false, new Translation2d());
}
/**
* Secondary method for controlling the drivebase. Given a simple {@link ChassisSpeeds} set the swerve module states,
* to achieve the goal.
*
* @param velocity The desired robot-oriented {@link ChassisSpeeds} for the robot to achieve.
* @param centerOfRotationMeters The center of rotation in meters, 0 is the center of the robot.
*/
public void drive(ChassisSpeeds velocity, Translation2d centerOfRotationMeters)
{
drive(velocity, false, centerOfRotationMeters);
}
/**
* The primary method for controlling the drivebase. Takes a {@link 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 centerOfRotationMeters The center of rotation in meters, 0 is the center of the robot.
*/
public void drive(
Translation2d translation, double rotation, boolean fieldRelative, boolean isOpenLoop,
Translation2d centerOfRotationMeters)
{
// Creates a robot-relative ChassisSpeeds object, converting from field-relative speeds if
// necessary.
2024-12-09 23:26:04 +00:00
ChassisSpeeds velocity = new ChassisSpeeds(translation.getX(), translation.getY(), rotation);
if (fieldRelative)
{
2025-01-06 15:44:15 +00:00
velocity = ChassisSpeeds.fromFieldRelativeSpeeds(velocity, getOdometryHeading());
2024-12-09 23:26:04 +00:00
}
drive(velocity, isOpenLoop, centerOfRotationMeters);
}
/**
* The primary method for controlling the drivebase. Takes a {@link 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.
*/
public void drive(
Translation2d translation, double rotation, boolean fieldRelative, boolean isOpenLoop)
{
// Creates a robot-relative ChassisSpeeds object, converting from field-relative speeds if
// necessary.
2024-12-09 23:26:04 +00:00
ChassisSpeeds velocity = new ChassisSpeeds(translation.getX(), translation.getY(), rotation);
2024-12-09 23:26:04 +00:00
if (fieldRelative)
{
2025-02-22 06:15:56 +00:00
velocity = ChassisSpeeds.fromFieldRelativeSpeeds(velocity, getOdometryHeading());
2024-12-09 23:26:04 +00:00
}
drive(velocity, isOpenLoop, new Translation2d());
2023-11-09 17:32:48 -06:00
}
/**
* The primary method for controlling the drivebase. Takes a {@link ChassisSpeeds}, and calculates and commands module
2024-02-19 20:48:54 -06:00
* states accordingly. Can use either open-loop or closed-loop velocity control for the wheel velocities. Applies
* heading correction if enabled and necessary.
2023-11-09 17:32:48 -06:00
*
2024-12-09 23:26:04 +00:00
* @param robotRelativeVelocity The chassis speeds to set the robot to achieve.
* @param isOpenLoop Whether to use closed-loop velocity control. Set to true to disable closed-loop.
* @param centerOfRotationMeters The center of rotation in meters, 0 is the center of the robot.
2023-11-09 17:32:48 -06:00
*/
2024-12-09 23:26:04 +00:00
public void drive(ChassisSpeeds robotRelativeVelocity, boolean isOpenLoop, Translation2d centerOfRotationMeters)
2023-01-29 21:18:52 -06:00
{
2024-12-17 18:49:55 +00:00
SwerveDriveTelemetry.startCtrlCycle();
2024-12-09 23:26:04 +00:00
robotRelativeVelocity = movementOptimizations(robotRelativeVelocity,
chassisVelocityCorrection,
angularVelocityCorrection);
2023-04-08 12:31:07 -05:00
// Heading Angular Velocity Deadband, might make a configuration option later.
// Originally made by Team 1466 Webb Robotics.
2024-01-15 14:37:13 -06:00
// Modified by Team 7525 Pioneers and BoiledBurntBagel of 6036
if (headingCorrection)
{
2024-12-09 23:26:04 +00:00
if (Math.abs(robotRelativeVelocity.omegaRadiansPerSecond) < HEADING_CORRECTION_DEADBAND
&& (Math.abs(robotRelativeVelocity.vxMetersPerSecond) > HEADING_CORRECTION_DEADBAND
|| Math.abs(robotRelativeVelocity.vyMetersPerSecond) > HEADING_CORRECTION_DEADBAND))
{
2024-12-09 23:26:04 +00:00
robotRelativeVelocity.omegaRadiansPerSecond =
2024-01-26 11:29:15 -06:00
swerveController.headingCalculate(getOdometryHeading().getRadians(), lastHeadingRadians);
} else
{
2024-01-26 11:29:15 -06:00
lastHeadingRadians = getOdometryHeading().getRadians();
}
}
2023-02-13 14:37:05 -06:00
// Display commanded speed for testing
2024-06-12 15:10:29 -05:00
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.LOW.ordinal())
{
2024-12-09 23:26:04 +00:00
SwerveDriveTelemetry.desiredChassisSpeedsObj = robotRelativeVelocity;
}
2023-02-13 14:37:05 -06:00
// Calculate required module states via kinematics
2024-12-09 23:26:04 +00:00
SwerveModuleState[] swerveModuleStates = kinematics.toSwerveModuleStates(robotRelativeVelocity,
centerOfRotationMeters);
2023-02-13 14:37:05 -06:00
2024-12-09 23:26:04 +00:00
setRawModuleStates(swerveModuleStates, robotRelativeVelocity, isOpenLoop);
2023-01-29 21:18:52 -06:00
}
2023-04-05 09:03:10 -05:00
/**
2025-02-22 06:15:56 +00:00
* Set the maximum attainable speeds for desaturation.
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
*/
2025-02-22 06:15:56 +00:00
public void setMaximumAttainableSpeeds(
2023-04-08 12:31:07 -05:00
double attainableMaxTranslationalSpeedMetersPerSecond,
double attainableMaxRotationalVelocityRadiansPerSecond)
{
2023-11-09 17:32:48 -06:00
this.attainableMaxTranslationalSpeedMetersPerSecond = attainableMaxTranslationalSpeedMetersPerSecond;
this.attainableMaxRotationalVelocityRadiansPerSecond = attainableMaxRotationalVelocityRadiansPerSecond;
2025-02-22 06:15:56 +00:00
}
/**
* Set the maximum allowable speeds for desaturation.
*
* @param maxTranslationalSpeedMetersPerSecond The allowable max speed that your robot should reach while translating
* in meters per second.
* @param maxRotationalVelocityRadiansPerSecond The allowable max speed the robot should reach while rotating in
* radians per second.
*/
public void setMaximumAllowableSpeeds(
double maxTranslationalSpeedMetersPerSecond,
double maxRotationalVelocityRadiansPerSecond)
{
this.maxChassisSpeedMPS = maxTranslationalSpeedMetersPerSecond;
this.swerveController.config.maxAngularVelocity = maxRotationalVelocityRadiansPerSecond;
}
/**
* Get the maximum velocity from {@link SwerveDrive#attainableMaxTranslationalSpeedMetersPerSecond} or
2025-02-22 06:15:56 +00:00
* {@link SwerveDrive#maxChassisSpeedMPS} whichever is the lower limit on the robot's speed.
*
2025-02-22 06:15:56 +00:00
* @return Minimum speed in meters/second of physically attainable and user allowable limits.
*/
2024-12-09 23:26:04 +00:00
public double getMaximumChassisVelocity()
{
2025-02-22 06:15:56 +00:00
return Math.min(this.attainableMaxTranslationalSpeedMetersPerSecond, maxChassisSpeedMPS);
2024-12-09 23:26:04 +00:00
}
/**
* Get the maximum drive velocity of a module as a {@link LinearVelocity}.
*
* @return {@link LinearVelocity} representing the maximum drive speed of a module.
*/
2025-02-22 06:15:56 +00:00
public double getMaximumModuleDriveVelocity()
{
2025-02-22 06:15:56 +00:00
return swerveModules[0].getMaxDriveVelocityMetersPerSecond();
2024-12-09 23:26:04 +00:00
}
/**
* Get the maximum angular velocity of an azimuth/angle motor in the swerve module.
*
* @return {@link AngularVelocity} of the maximum azimuth/angle motor.
*/
public AngularVelocity getMaximumModuleAngleVelocity()
{
return swerveModules[0].getMaxAngularVelocity();
}
/**
* Get the maximum angular velocity, either {@link SwerveDrive#attainableMaxRotationalVelocityRadiansPerSecond} or
2025-02-22 06:15:56 +00:00
* {@link SwerveControllerConfiguration#maxAngularVelocity}, whichever is the lower limit on the robot's speed.
*
2025-02-22 06:15:56 +00:00
* @return Minimum angular velocity in radians per second of physically attainable and user allowable limits.
*/
2024-12-09 23:26:04 +00:00
public double getMaximumChassisAngularVelocity()
{
2025-02-22 06:15:56 +00:00
return Math.min(this.attainableMaxRotationalVelocityRadiansPerSecond, swerveController.config.maxAngularVelocity);
2023-04-05 09:03:10 -05:00
}
2023-01-29 21:18:52 -06:00
/**
2024-02-19 20:48:54 -06:00
* Set the module states (azimuth and velocity) directly.
2023-01-29 21:18:52 -06:00
*
2024-11-06 00:10:07 +00:00
* @param desiredStates A list of SwerveModuleStates to send to the modules.
2024-10-14 13:22:11 -05:00
* @param desiredChassisSpeed The desired chassis speeds to set the robot to achieve.
2024-11-06 00:10:07 +00:00
* @param isOpenLoop Whether to use closed-loop velocity control. Set to true to disable closed-loop.
2023-01-29 21:18:52 -06:00
*/
2024-11-06 00:10:07 +00:00
private void setRawModuleStates(SwerveModuleState[] desiredStates, ChassisSpeeds desiredChassisSpeed,
boolean isOpenLoop)
2023-04-08 12:31:07 -05:00
{
2023-02-13 14:37:05 -06:00
// Desaturates wheel speeds
2025-02-22 06:15:56 +00:00
double maxModuleSpeedMPS = getMaximumModuleDriveVelocity();
if ((attainableMaxTranslationalSpeedMetersPerSecond != 0 || attainableMaxRotationalVelocityRadiansPerSecond != 0) &&
attainableMaxTranslationalSpeedMetersPerSecond != maxChassisSpeedMPS)
2023-04-08 12:31:07 -05:00
{
2024-10-14 13:22:11 -05:00
SwerveDriveKinematics.desaturateWheelSpeeds(desiredStates, desiredChassisSpeed,
2024-12-09 23:26:04 +00:00
maxModuleSpeedMPS,
2023-11-09 17:32:48 -06:00
attainableMaxTranslationalSpeedMetersPerSecond,
attainableMaxRotationalVelocityRadiansPerSecond);
2024-01-22 17:40:04 -06:00
} else
{
2024-12-09 23:26:04 +00:00
SwerveDriveKinematics.desaturateWheelSpeeds(desiredStates, maxModuleSpeedMPS);
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-01-29 21:18:52 -06:00
}
}
/**
2024-11-06 00:10:07 +00:00
* Set the module states (azimuth and velocity) directly. Used primarily for auto paths. Does not allow for usage of
2024-12-09 23:26:04 +00:00
* {@link SwerveDriveKinematics#desaturateWheelSpeeds(SwerveModuleState[] moduleStates, ChassisSpeeds
* desiredChassisSpeed, double attainableMaxModuleSpeedMetersPerSecond, double
* attainableMaxTranslationalSpeedMetersPerSecond, double attainableMaxRotationalVelocityRadiansPerSecond)}
*
* @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(SwerveModuleState[] desiredStates, boolean isOpenLoop)
{
2024-12-17 18:49:55 +00:00
SwerveDriveTelemetry.startCtrlCycle();
2025-02-22 06:15:56 +00:00
double maxModuleSpeedMPS = getMaximumModuleDriveVelocity();
2024-10-14 13:22:11 -05:00
desiredStates = kinematics.toSwerveModuleStates(kinematics.toChassisSpeeds(desiredStates));
2024-12-09 23:26:04 +00:00
SwerveDriveKinematics.desaturateWheelSpeeds(desiredStates, maxModuleSpeedMPS);
2024-10-14 13:22:11 -05:00
// Sets states
for (SwerveModule module : swerveModules)
{
module.setDesiredState(desiredStates[module.moduleNumber], isOpenLoop, false);
}
}
2024-12-09 23:26:04 +00:00
/**
* Drive the robot using the {@link SwerveModuleState}, it is recommended to have
* {@link SwerveDrive#setCosineCompensator(boolean)} set to false for this.<br/>
*
* @param robotRelativeVelocity Robot relative {@link ChassisSpeeds}
* @param states Corresponding {@link SwerveModuleState} to use (not checked against the
* {@param robotRelativeVelocity}).
* @param feedforwardForces Feedforward forces generated by set-point generator
*/
public void drive(ChassisSpeeds robotRelativeVelocity, SwerveModuleState[] states, Force[] feedforwardForces)
{
2024-12-17 18:49:55 +00:00
SwerveDriveTelemetry.startCtrlCycle();
2024-12-09 23:26:04 +00:00
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.LOW.ordinal())
{
SwerveDriveTelemetry.desiredChassisSpeedsObj = robotRelativeVelocity;
}
for (SwerveModule module : swerveModules)
{
2025-02-22 06:15:56 +00:00
module.applyStateOptimizations(states[module.moduleNumber]);
module.applyAntiJitter(states[module.moduleNumber], false);
2025-03-19 03:45:47 +00:00
2024-12-09 23:26:04 +00:00
// from the module configuration, obtain necessary information to calculate feed-forward
// Warning: Will not work well if motor is not what we are expecting.
// Warning: Should replace module.getDriveMotor().simMotor with expected motor type first.
DCMotor driveMotorModel = module.configuration.driveMotor.getSimMotor();
double driveGearRatio = module.configuration.conversionFactors.drive.gearRatio;
double wheelRadiusMeters = Units.inchesToMeters(module.configuration.conversionFactors.drive.diameter) / 2;
// calculation:
double desiredGroundSpeedMPS = states[module.moduleNumber].speedMetersPerSecond;
double feedforwardVoltage = driveMotorModel.getVoltage(
// Since: (1) torque = force * momentOfForce; (2) torque (on wheel) = torque (on motor) * gearRatio
// torque (on motor) = force * wheelRadius / gearRatio
feedforwardForces[module.moduleNumber].in(Newtons) * wheelRadiusMeters / driveGearRatio,
// Since: (1) linear velocity = angularVelocity * wheelRadius; (2) wheelVelocity = motorVelocity / gearRatio
// motorAngularVelocity = linearVelocity / wheelRadius * gearRatio
desiredGroundSpeedMPS / wheelRadiusMeters * driveGearRatio
);
module.setDesiredState(
states[module.moduleNumber],
false,
feedforwardVoltage
);
}
}
2023-01-29 21:18:52 -06:00
/**
2023-11-09 17:32:48 -06:00
* Set chassis speeds with closed-loop velocity control.
2023-01-29 21:18:52 -06:00
*
2024-12-09 23:26:04 +00:00
* @param robotRelativeSpeeds Chassis speeds to set.
2023-01-29 21:18:52 -06:00
*/
2024-12-09 23:26:04 +00:00
public void setChassisSpeeds(ChassisSpeeds robotRelativeSpeeds)
2023-01-29 21:18:52 -06:00
{
2024-12-17 18:49:55 +00:00
SwerveDriveTelemetry.startCtrlCycle();
2024-12-09 23:26:04 +00:00
robotRelativeSpeeds = movementOptimizations(robotRelativeSpeeds,
autonomousChassisVelocityCorrection,
autonomousAngularVelocityCorrection);
2024-10-14 13:22:11 -05:00
2024-12-09 23:26:04 +00:00
SwerveDriveTelemetry.desiredChassisSpeedsObj = robotRelativeSpeeds;
2023-02-23 21:12:29 -06:00
2024-12-09 23:26:04 +00:00
setRawModuleStates(kinematics.toSwerveModuleStates(robotRelativeSpeeds), robotRelativeSpeeds, false);
2023-01-29 21:18:52 -06:00
}
/**
2024-12-09 23:26:04 +00:00
* Gets the measured 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
{
odometryLock.lock();
Pose2d poseEstimation = swerveDrivePoseEstimator.getEstimatedPosition();
odometryLock.unlock();
return poseEstimation;
2023-01-29 21:18:52 -06:00
}
/**
2024-12-09 23:26:04 +00:00
* Gets the maple-sim drivetrain simulation instance This is used to add intake simulation / launch game pieces from
* the robot
*
* @return an optional maple-sim {@link SwerveDriveSimulation} object, or {@link Optional#empty()} when calling from a
* real robot
*/
public Optional<SwerveDriveSimulation> getMapleSimDrive()
{
if (SwerveDriveTelemetry.isSimulation)
{
return Optional.of(mapleSimDrive);
}
return Optional.empty();
}
/**
* Gets the actual pose of the drivetrain during simulation
*
* @return an {@link Optional} {@link Pose2d}, representing the drivetrain pose during simulation, or an empty
* optional when running on real robot
*/
public Optional<Pose2d> getSimulationDriveTrainPose()
{
odometryLock.lock();
Optional<Pose2d> simulationPose = getMapleSimDrive().map(AbstractDriveTrainSimulation::getSimulatedDriveTrainPose);
odometryLock.unlock();
return simulationPose;
}
/**
* Gets the measured field-relative robot velocity (x, y and omega)
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
2024-12-09 23:26:04 +00:00
// angle given as the robot angle reverses the direction of rotation, and the conversion is reversed.
ChassisSpeeds robotRelativeSpeeds = kinematics.toChassisSpeeds(getStates());
2025-01-06 15:44:15 +00:00
return ChassisSpeeds.fromRobotRelativeSpeeds(robotRelativeSpeeds, getOdometryHeading());
// Might need to be this instead
//return ChassisSpeeds.fromFieldRelativeSpeeds(
// kinematics.toChassisSpeeds(getStates()), getOdometryHeading().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
*
2025-03-19 03:45:47 +00:00
* @param pose The pose to set the odometry to. Field relative, blue-origin where 0deg is facing towards RED alliance.
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
{
odometryLock.lock();
2024-01-22 15:11:18 -06:00
swerveDrivePoseEstimator.resetPosition(getYaw(), getModulePositions(), pose);
2024-12-09 23:26:04 +00:00
if (SwerveDriveTelemetry.isSimulation)
{
mapleSimDrive.setSimulationWorldPose(pose);
}
odometryLock.unlock();
2025-01-06 15:44:15 +00:00
ChassisSpeeds robotRelativeSpeeds = ChassisSpeeds.fromRobotRelativeSpeeds(new ChassisSpeeds(0, 0, 0), getYaw());
2024-12-09 23:26:04 +00:00
kinematics.toSwerveModuleStates(robotRelativeSpeeds);
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)
{
2024-06-12 15:10:29 -05:00
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.POSE.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 SwerveModuleState[] getStates()
2023-01-29 21:18:52 -06:00
{
SwerveModuleState[] states = new SwerveModuleState[swerveDriveConfiguration.moduleCount];
2023-02-13 14:37:05 -06:00
for (SwerveModule module : swerveModules)
{
states[module.moduleNumber] = module.getState();
}
return states;
2023-01-29 21:18:52 -06:00
}
/**
2024-01-22 15:11:18 -06:00
* Gets the current module positions (azimuth and wheel position (meters)).
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();
}
return positions;
2023-01-29 21:18:52 -06:00
}
2024-01-26 11:29:15 -06:00
/**
* Getter for the {@link SwerveIMU}.
*
* @return generated {@link SwerveIMU}
*/
public SwerveIMU getGyro()
{
return swerveDriveConfiguration.imu;
}
/**
* Set the expected gyroscope angle using a {@link Rotation3d} object. To reset gyro, set to a new {@link Rotation3d}
* subtracted from the current gyroscopic readings {@link SwerveIMU#getRotation3d()}.
*
* @param gyro expected gyroscope angle as {@link Rotation3d}.
*/
public void setGyro(Rotation3d gyro)
{
if (SwerveDriveTelemetry.isSimulation)
{
setGyroOffset(simIMU.getGyroRotation3d().minus(gyro));
} else
{
setGyroOffset(imu.getRawRotation3d().minus(gyro));
}
2024-02-02 18:55:29 -06:00
imuReadingCache.update();
2024-01-26 11:29:15 -06:00
}
2023-01-29 21:18:52 -06:00
/**
2025-03-19 03:45:47 +00:00
* Resets the gyro angle to zero and resets odometry to the same position, but facing toward 0 (red alliance station).
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
2024-02-02 18:55:29 -06:00
if (SwerveDriveTelemetry.isSimulation)
2023-02-13 14:37:05 -06:00
{
2024-02-02 18:55:29 -06:00
simIMU.setAngle(0);
2023-02-13 14:37:05 -06:00
} else
{
2024-02-02 18:55:29 -06:00
setGyroOffset(imu.getRawRotation3d());
2023-02-13 14:37:05 -06:00
}
2024-02-02 18:55:29 -06:00
imuReadingCache.update();
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.
2024-02-02 18:55:29 -06:00
return Rotation2d.fromRadians(imuReadingCache.getValue().getZ());
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.
2024-02-02 18:55:29 -06:00
return Rotation2d.fromRadians(imuReadingCache.getValue().getY());
}
/**
* 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.
2024-02-02 18:55:29 -06:00
return Rotation2d.fromRadians(imuReadingCache.getValue().getX());
}
/**
* 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.
2024-02-02 18:55:29 -06:00
return imuReadingCache.getValue();
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
}
2024-10-14 13:22:11 -05:00
/**
2024-11-06 00:10:07 +00:00
* Enable auto synchronization for encoders during a match. This will only occur when the modules are not moving for a
* few seconds.
*
* @param enabled Enable state
2024-10-14 13:22:11 -05:00
* @param deadband Deadband in degrees, default is 3 degrees.
*/
public void setModuleEncoderAutoSynchronize(boolean enabled, double deadband)
{
2024-11-06 00:10:07 +00:00
for (SwerveModule swerveModule : swerveModules)
2024-10-14 13:22:11 -05:00
{
swerveModule.setEncoderAutoSynchronize(enabled, deadband);
}
}
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)
{
SwerveModuleState desiredState =
new SwerveModuleState(0, swerveModule.configuration.moduleLocation.getAngle());
2024-06-12 15:10:29 -05:00
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.INFO.ordinal())
{
2024-12-09 23:26:04 +00:00
SwerveDriveTelemetry.desiredStatesObj[swerveModule.moduleNumber] = desiredState;
}
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
*
2024-02-28 13:25:59 -06:00
* @param driveFeedforward Feedforward for the drive motor on swerve modules.
2023-01-29 21:18:52 -06:00
*/
2024-02-28 13:25:59 -06:00
public void replaceSwerveModuleFeedforward(SimpleMotorFeedforward driveFeedforward)
2023-01-29 21:18:52 -06:00
{
2023-02-13 14:37:05 -06:00
for (SwerveModule swerveModule : swerveModules)
{
2024-02-28 13:25:59 -06:00
swerveModule.setFeedforward(driveFeedforward);
2023-02-13 14:37:05 -06:00
}
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
{
2024-12-17 18:49:55 +00:00
SwerveDriveTelemetry.startOdomCycle();
odometryLock.lock();
2025-02-22 06:15:56 +00:00
// invalidateCache();
try
{
// Update odometry
swerveDrivePoseEstimator.update(getYaw(), getModulePositions());
2024-12-09 23:26:04 +00:00
if (SwerveDriveTelemetry.isSimulation)
{
2024-12-09 23:26:04 +00:00
try
{
SimulatedArena.getInstance().simulationPeriodic();
} catch (Exception e)
{
2024-12-09 23:26:04 +00:00
DriverStation.reportError("MapleSim error", false);
}
2024-12-09 23:26:04 +00:00
}
2024-12-09 23:26:04 +00:00
// Update angle accumulator if the robot is simulated
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.INFO.ordinal())
{
SwerveDriveTelemetry.measuredChassisSpeedsObj = getRobotVelocity();
SwerveDriveTelemetry.robotRotationObj = getOdometryHeading();
}
2024-06-12 15:10:29 -05:00
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.POSE.ordinal())
{
2024-12-09 23:26:04 +00:00
if (SwerveDriveTelemetry.isSimulation)
{
field.setRobotPose(mapleSimDrive.getSimulatedDriveTrainPose());
field.getObject("OdometryPose").setPose(swerveDrivePoseEstimator.getEstimatedPosition());
field.getObject("XModules").setPoses(getSwerveModulePoses(mapleSimDrive.getSimulatedDriveTrainPose()));
} else
{
field.setRobotPose(swerveDrivePoseEstimator.getEstimatedPosition());
}
}
2023-01-29 21:18:52 -06:00
double sumVelocity = 0;
for (SwerveModule module : swerveModules)
{
SwerveModuleState moduleState = module.getState();
sumVelocity += Math.abs(moduleState.speedMetersPerSecond);
if (SwerveDriveTelemetry.verbosity == TelemetryVerbosity.HIGH)
{
2024-01-15 14:37:13 -06:00
module.updateTelemetry();
2024-12-17 18:49:55 +00:00
rawIMUPublisher.set(getYaw().getDegrees());
adjustedIMUPublisher.set(getOdometryHeading().getDegrees());
}
2024-06-12 15:10:29 -05:00
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.INFO.ordinal())
{
2024-12-09 23:26:04 +00:00
SwerveDriveTelemetry.measuredStatesObj[module.moduleNumber] = moduleState;
}
}
2023-02-13 14:37:05 -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 (sumVelocity <= .01 && ++moduleSynchronizationCounter > 5)
{
synchronizeModuleEncoders();
moduleSynchronizationCounter = 0;
}
2024-06-12 15:10:29 -05:00
if (SwerveDriveTelemetry.verbosity.ordinal() >= TelemetryVerbosity.INFO.ordinal())
{
SwerveDriveTelemetry.updateData();
}
} catch (Exception e)
{
odometryLock.unlock();
throw e;
}
odometryLock.unlock();
2024-12-17 18:49:55 +00:00
SwerveDriveTelemetry.endOdomCycle();
2023-01-29 21:18:52 -06:00
}
2024-12-09 23:26:04 +00:00
/**
* Invalidate all {@link Cache} object used by the {@link SwerveDrive}
*/
public void invalidateCache()
{
imuReadingCache.update();
for (SwerveModule module : swerveModules)
{
module.invalidateCache();
}
}
/**
* Synchronize angle motor integrated encoders with data from absolute encoders.
*/
public void synchronizeModuleEncoders()
{
for (SwerveModule module : swerveModules)
{
module.queueSynchronizeEncoders();
}
}
/**
* Set the gyro scope offset to a desired known rotation. Unlike {@link SwerveDrive#setGyro(Rotation3d)} it DOES NOT
* take the current rotation into account.
*
* @param offset {@link Rotation3d} known offset of the robot for gyroscope to use.
*/
public void setGyroOffset(Rotation3d offset)
{
if (SwerveDriveTelemetry.isSimulation)
{
simIMU.setAngle(offset.getZ());
} else
{
imu.setOffset(offset);
}
2024-02-02 18:55:29 -06:00
imuReadingCache.update();
}
/**
* 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 visionMeasurementStdDevs Vision measurement standard deviation that will be sent to the
2023-11-09 17:32:48 -06:00
* {@link SwerveDrivePoseEstimator}.The standard deviation of the vision measurement,
2025-02-22 06:15:56 +00:00
* for best accuracy calculate the standard deviation at 2 or more points and fit a
2023-11-09 17:32:48 -06:00
* line to it with the calculated optimal standard deviation. (Units should be meters
* per pixel). By optimizing this you can get * vision accurate to inches instead of
* feet.
*/
2023-11-09 17:32:48 -06:00
public void addVisionMeasurement(Pose2d robotPose, double timestamp,
Matrix<N3, N1> visionMeasurementStdDevs)
{
2024-01-22 15:11:18 -06:00
odometryLock.lock();
swerveDrivePoseEstimator.addVisionMeasurement(robotPose, timestamp, visionMeasurementStdDevs);
odometryLock.unlock();
}
2024-08-24 17:27:03 -05:00
/**
* Sets the pose estimator's trust of global measurements. This might be used to change trust in vision measurements
* after the autonomous period, or to change trust as distance to a vision target increases.
*
* @param visionMeasurementStdDevs Standard deviations of the vision measurements. Increase these numbers to trust
* global measurements from vision less. This matrix is in the form [x, y, theta],
* with units in meters and radians.
*/
public void setVisionMeasurementStdDevs(Matrix<N3, N1> visionMeasurementStdDevs)
{
odometryLock.lock();
swerveDrivePoseEstimator.setVisionMeasurementStdDevs(visionMeasurementStdDevs);
odometryLock.unlock();
}
2024-01-22 15:11:18 -06:00
/**
* Add a vision measurement to the {@link SwerveDrivePoseEstimator} and update the {@link SwerveIMU} gyro reading with
2024-01-26 11:29:15 -06:00
* the given timestamp of the vision measurement.
2024-01-22 15:11:18 -06:00
*
* @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.
*/
public void addVisionMeasurement(Pose2d robotPose, double timestamp)
{
odometryLock.lock();
swerveDrivePoseEstimator.addVisionMeasurement(robotPose, timestamp);
// Pose2d newOdometry = new Pose2d(swerveDrivePoseEstimator.getEstimatedPosition().getTranslation(),
// robotPose.getRotation());
odometryLock.unlock();
// setGyroOffset(new Rotation3d(0, 0, robotPose.getRotation().getRadians()));
// resetOdometry(newOdometry);
}
/**
* 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
2023-11-09 17:32:48 -06:00
* {@link SwerveController#getTargetSpeeds(double, 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;
}
2024-02-02 18:55:29 -06:00
/**
* Get the {@link SwerveModule}'s as a {@link HashMap} where the key is the swerve module configuration name.
*
* @return {@link HashMap}(Module Name, SwerveModule)
*/
public Map<String, SwerveModule> getModuleMap()
{
Map<String, SwerveModule> map = new HashMap<String, SwerveModule>();
for (SwerveModule module : swerveModules)
{
map.put(module.configuration.name, module);
}
return map;
}
/**
* Reset the drive encoders on the robot, useful when manually resetting the robot without a reboot, like in
* autonomous.
*/
2024-01-15 14:37:13 -06:00
public void resetDriveEncoders()
{
for (SwerveModule module : swerveModules)
{
2024-02-28 13:25:59 -06:00
module.getDriveMotor().setPosition(0);
}
}
2025-02-22 06:15:56 +00:00
/**
* Set the motor controller closed loop feedback device to the defined external absolute encoder, with the given
* offset from the supplied configuration, overwriting any native offset.
*/
public void useExternalFeedbackSensor()
{
for (SwerveModule module : swerveModules)
{
module.useExternalFeedbackSensor();
}
}
/**
* Set the motor controller closed loop feedback device to the internal encoder instead of the absolute encoder.
*/
public void useInternalFeedbackSensor()
{
for (SwerveModule module : swerveModules)
{
module.useInternalFeedbackSensor();
}
}
/**
* Pushes the Absolute Encoder offsets to the Encoder or Motor Controller, depending on type. Also removes the
* internal offsets to prevent double offsetting.
*/
2025-02-22 06:15:56 +00:00
@Deprecated
2024-06-12 15:10:29 -05:00
public void pushOffsetsToEncoders()
{
for (SwerveModule module : swerveModules)
{
2024-06-12 15:10:29 -05:00
module.pushOffsetsToEncoders();
}
}
/**
* Restores Internal YAGSL Encoder offsets and sets the Encoder stored offset back to 0
*/
2025-02-22 06:15:56 +00:00
@Deprecated
public void restoreInternalOffset()
{
for (SwerveModule module : swerveModules)
{
module.restoreInternalOffset();
}
}
2025-02-22 06:15:56 +00:00
/**
* Set module optimization to be utilized or not. Sometimes it is desirable to be enabled for debugging purposes
* only.
*
* @param enabled Optimization enabled state.
*/
public void setModuleStateOptimization(boolean enabled)
{
for (SwerveModule module : swerveModules)
{
module.setModuleStateOptimization(enabled);
}
}
2024-07-29 15:14:25 -05:00
/**
* Enable auto-centering module wheels. This has a side effect of causing some jitter to the robot when a PID is not
* tuned perfectly. This function is a wrapper for {@link SwerveModule#setAntiJitter(boolean)} to perform
* auto-centering.
*
* @param enabled Enable auto-centering (disable antiJitter)
*/
public void setAutoCenteringModules(boolean enabled)
{
for (SwerveModule module : swerveModules)
{
module.setAntiJitter(!enabled);
}
}
2024-02-06 16:03:08 -06:00
/**
* Enable or disable the {@link swervelib.parser.SwerveModuleConfiguration#useCosineCompensator} for all
* {@link SwerveModule}'s in the swerve drive. The cosine compensator will slow down or speed up modules that are
* close to their desired state in theory.
*
* @param enabled Usage of the cosine compensator.
*/
public void setCosineCompensator(boolean enabled)
{
for (SwerveModule module : swerveModules)
{
module.configuration.useCosineCompensator = enabled;
}
}
2024-06-12 15:10:29 -05:00
/**
2024-10-14 13:22:11 -05:00
* Sets the Chassis discretization seconds as well as enableing/disabling the Chassis velocity correction in teleop
2024-06-12 15:58:37 -05:00
*
2025-01-06 15:44:15 +00:00
* @param enable Enable chassis velocity correction, which will use
* {@link ChassisSpeeds#discretize(ChassisSpeeds, double)}} with the following.
2024-06-12 15:58:37 -05:00
* @param dtSeconds The duration of the timestep the speeds should be applied for.
2024-06-12 15:10:29 -05:00
*/
2024-06-12 15:58:37 -05:00
public void setChassisDiscretization(boolean enable, double dtSeconds)
{
2024-11-06 00:10:07 +00:00
if (!SwerveDriveTelemetry.isSimulation)
2024-10-14 13:22:11 -05:00
{
chassisVelocityCorrection = enable;
discretizationdtSeconds = dtSeconds;
}
}
/**
2024-11-06 00:10:07 +00:00
* Sets the Chassis discretization seconds as well as enableing/disabling the Chassis velocity correction in teleop
* and/or auto
2024-10-14 13:22:11 -05:00
*
2025-01-06 15:44:15 +00:00
* @param useInTeleop Enable chassis velocity correction, which will use
* {@link ChassisSpeeds#discretize(ChassisSpeeds, double)} with the following in teleop.
* @param useInAuto Enable chassis velocity correction, which will use
* {@link ChassisSpeeds#discretize(ChassisSpeeds, double)} with the following in auto.
2024-11-06 00:10:07 +00:00
* @param dtSeconds The duration of the timestep the speeds should be applied for.
2024-10-14 13:22:11 -05:00
*/
public void setChassisDiscretization(boolean useInTeleop, boolean useInAuto, double dtSeconds)
{
2024-11-06 00:10:07 +00:00
if (!SwerveDriveTelemetry.isSimulation)
2024-10-14 13:22:11 -05:00
{
chassisVelocityCorrection = useInTeleop;
autonomousChassisVelocityCorrection = useInAuto;
discretizationdtSeconds = dtSeconds;
}
}
/**
2024-11-06 00:10:07 +00:00
* Enables angular velocity skew correction in teleop and/or autonomous and sets the angular velocity coefficient for
* both modes
2024-10-14 13:22:11 -05:00
*
* @param useInTeleop Enables angular velocity correction in teleop.
* @param useInAuto Enables angular velocity correction in autonomous.
2024-11-06 00:10:07 +00:00
* @param angularVelocityCoeff The angular velocity coefficient. Expected values between -0.15 to 0.15. Start with a
* value of 0.1, test in teleop. When enabling for the first time if the skew is
* significantly worse try inverting the value. Tune by moving in a straight line while
* rotating. Testing is best done with angular velocity controls on the right stick.
* Change the value until you are visually happy with the skew. Ensure your tune works
* with different translational and rotational magnitudes. If this reduces skew in teleop,
* it may improve auto.
2024-10-14 13:22:11 -05:00
*/
public void setAngularVelocityCompensation(boolean useInTeleop, boolean useInAuto, double angularVelocityCoeff)
{
2024-11-06 00:10:07 +00:00
if (!SwerveDriveTelemetry.isSimulation)
2024-10-14 13:22:11 -05:00
{
angularVelocityCorrection = useInTeleop;
autonomousAngularVelocityCorrection = useInAuto;
angularVelocityCoefficient = angularVelocityCoeff;
}
}
/**
* Correct for skew that worsens as angular velocity increases
*
2024-12-09 23:26:04 +00:00
* @param robotRelativeVelocity The chassis speeds to set the robot to achieve.
2024-10-14 13:22:11 -05:00
* @return {@link ChassisSpeeds} of the robot after angular velocity skew correction.
*/
2024-12-09 23:26:04 +00:00
public ChassisSpeeds angularVelocitySkewCorrection(ChassisSpeeds robotRelativeVelocity)
2024-10-14 13:22:11 -05:00
{
2024-12-17 18:49:55 +00:00
var angularVelocity = new Rotation2d(imu.getYawAngularVelocity().in(RadiansPerSecond) * angularVelocityCoefficient);
2024-11-06 00:10:07 +00:00
if (angularVelocity.getRadians() != 0.0)
{
2025-01-06 15:44:15 +00:00
ChassisSpeeds fieldRelativeVelocity = ChassisSpeeds.fromRobotRelativeSpeeds(robotRelativeVelocity,
getOdometryHeading());
robotRelativeVelocity = ChassisSpeeds.fromFieldRelativeSpeeds(fieldRelativeVelocity,
getOdometryHeading().plus(angularVelocity));
2024-11-06 00:10:07 +00:00
}
2024-12-09 23:26:04 +00:00
return robotRelativeVelocity;
2024-10-14 13:22:11 -05:00
}
/**
* Enable desired drive corrections
*
2024-12-09 23:26:04 +00:00
* @param robotRelativeVelocity The chassis speeds to set the robot to achieve.
2024-10-14 13:22:11 -05:00
* @param uesChassisDiscretize Correct chassis velocity using 254's correction.
* @param useAngularVelocitySkewCorrection Use the robot's angular velocity to correct for skew.
2024-11-06 00:10:07 +00:00
* @return The chassis speeds after optimizations.
2024-10-14 13:22:11 -05:00
*/
2024-12-09 23:26:04 +00:00
private ChassisSpeeds movementOptimizations(ChassisSpeeds robotRelativeVelocity, boolean uesChassisDiscretize,
2024-11-06 00:10:07 +00:00
boolean useAngularVelocitySkewCorrection)
2024-10-14 13:22:11 -05:00
{
2024-11-06 00:10:07 +00:00
if (useAngularVelocitySkewCorrection)
2024-10-14 13:22:11 -05:00
{
2024-12-09 23:26:04 +00:00
robotRelativeVelocity = angularVelocitySkewCorrection(robotRelativeVelocity);
2024-10-14 13:22:11 -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
if (uesChassisDiscretize)
{
2025-01-06 15:44:15 +00:00
robotRelativeVelocity = ChassisSpeeds.discretize(robotRelativeVelocity, discretizationdtSeconds);
2024-10-14 13:22:11 -05:00
}
2024-12-09 23:26:04 +00:00
return robotRelativeVelocity;
2024-06-12 15:10:29 -05:00
}
2024-12-09 23:26:04 +00:00
/**
* Convert a {@link ChassisSpeeds} to {@link SwerveModuleState[]} for use elsewhere.
*
* @param robotRelativeVelocity {@link ChassisSpeeds} velocity to use.
* @param optimize Perform chassis velocity correction or angular velocity correction.
* @return {@link SwerveModuleState[]} for use elsewhere.
*/
public SwerveModuleState[] toServeModuleStates(ChassisSpeeds robotRelativeVelocity, boolean optimize)
{
if (optimize)
{
robotRelativeVelocity = movementOptimizations(robotRelativeVelocity,
chassisVelocityCorrection,
angularVelocityCorrection);
}
return kinematics.toSwerveModuleStates(robotRelativeVelocity);
}
2023-02-13 14:37:05 -06:00
}