Files
YAGSL/swervelib/SwerveDrive.java

508 lines
18 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.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.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Transform2d;
2023-02-13 14:37:05 -06:00
import edu.wpi.first.math.geometry.Translation2d;
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.trajectory.Trajectory;
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;
import frc.robot.Robot;
2023-02-13 14:37:05 -06:00
import java.util.ArrayList;
import java.util.List;
2023-02-13 17:21:24 -06:00
import swervelib.imu.SwerveIMU;
import swervelib.math.SwerveKinematics2;
import swervelib.math.SwerveModuleState2;
import swervelib.parser.SwerveControllerConfiguration;
import swervelib.parser.SwerveDriveConfiguration;
import swervelib.simulation.SwerveIMUSimulation;
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-13 14:37:05 -06:00
public SwerveController swerveController;
/**
2023-02-13 14:37:05 -06:00
* Swerve IMU device for sensing the heading of the robot.
*/
2023-02-13 14:37:05 -06:00
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;
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#setModuleStates} 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#setModuleStates} 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
*/
2023-02-13 14:37:05 -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.
2023-01-29 21:18:52 -06:00
if (!Robot.isReal())
{
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
2023-02-13 14:37:05 -06:00
// odometry = new SwerveDriveOdometry(kinematics, getYaw(), getModulePositions());
swerveDrivePoseEstimator = new SwerveDrivePoseEstimator(
kinematics,
getYaw(),
getModulePositions(),
new Pose2d(new Translation2d(0, 0), Rotation2d.fromDegrees(0)),
VecBuilder.fill(0.1, 0.1, 0.1), // x,y,heading in radians; state std dev, higher=less weight
VecBuilder.fill(0.9, 0.9, 0.9)); // 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();
SmartDashboard.putData("Field", field);
2023-01-29 21:18:52 -06:00
}
/**
2023-02-13 14:37:05 -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.
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
* 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)
2023-01-29 21:18:52 -06:00
{
2023-02-13 14:37:05 -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);
// Display commanded speed for testing
SmartDashboard.putString("RobotVelocity", velocity.toString());
// Calculate required module states via kinematics
SwerveModuleState2[] swerveModuleStates = kinematics.toSwerveModuleStates(velocity);
setModuleStates(swerveModuleStates, isOpenLoop);
2023-01-29 21:18:52 -06:00
}
/**
2023-02-13 14:37:05 -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-02-13 14:37:05 -06:00
public void setModuleStates(SwerveModuleState2[] desiredStates, boolean isOpenLoop)
2023-01-29 21:18:52 -06:00
{
2023-02-13 14:37:05 -06:00
// Desaturates wheel speeds
SwerveKinematics2.desaturateWheelSpeeds(desiredStates, swerveDriveConfiguration.maxSpeed);
2023-01-29 21:18:52 -06:00
2023-02-13 14:37:05 -06:00
// Sets states
for (SwerveModule module : swerveModules)
2023-01-29 21:18:52 -06:00
{
2023-02-13 23:03:31 -06:00
module.setDesiredState(desiredStates[module.moduleNumber], isOpenLoop);
2023-02-13 14:37:05 -06:00
SmartDashboard.putNumber("Module " + module.moduleNumber + " Speed Setpoint: ",
desiredStates[module.moduleNumber].speedMetersPerSecond);
SmartDashboard.putNumber("Module " + module.moduleNumber + " Angle Setpoint: ",
desiredStates[module.moduleNumber].angle.getDegrees());
2023-01-29 21:18:52 -06:00
}
}
/**
* Set chassis speeds with closed-loop velocity control.
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
{
setModuleStates(kinematics.toSwerveModuleStates(chassisSpeeds),
2023-02-13 14:37:05 -06:00
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
// 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
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
* 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)
{
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
}
/**
2023-02-13 14:37:05 -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
{
2023-02-13 14:37:05 -06:00
SwerveModulePosition[] positions = new SwerveModulePosition[swerveDriveConfiguration.moduleCount];
for (SwerveModule module : swerveModules)
{
positions[module.moduleNumber] = module.getPosition();
}
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()
{
2023-02-13 14:37:05 -06:00
// Resets the real gyro or the angle accumulator, depending on whether the robot is being simulated
if (Robot.isReal())
{
imu.setYaw(0);
} else
{
simIMU.setAngle(0);
2023-02-13 14:37:05 -06:00
}
swerveController.lastAngle = 0;
resetOdometry(new Pose2d(getPose().getTranslation(), new Rotation2d()));
2023-01-29 21:18:52 -06:00
}
/**
2023-02-13 14:37:05 -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 (Robot.isReal())
{
double[] ypr = new double[3];
imu.getYawPitchRoll(ypr);
return Rotation2d.fromDegrees(swerveDriveConfiguration.invertedIMU ? 360 - ypr[0] : ypr[0]);
} 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 (Robot.isReal())
{
double[] ypr = new double[3];
imu.getYawPitchRoll(ypr);
return Rotation2d.fromDegrees(swerveDriveConfiguration.invertedIMU ? 360 - ypr[1] : ypr[1]);
} 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 (Robot.isReal())
{
double[] ypr = new double[3];
imu.getYawPitchRoll(ypr);
2023-02-14 22:49:55 -06:00
return Rotation2d.fromDegrees(swerveDriveConfiguration.invertedIMU ? 360 - ypr[2] : ypr[2]);
} 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 (Robot.isReal())
{
double[] ypr = new double[3];
imu.getYawPitchRoll(ypr);
return new Rotation3d(
2023-02-14 22:49:55 -06:00
Math.toRadians(swerveDriveConfiguration.invertedIMU ? 360 - ypr[2] : ypr[2]),
Math.toRadians(swerveDriveConfiguration.invertedIMU ? 360 - ypr[1] : ypr[1]),
2023-02-14 22:49:55 -06:00
Math.toRadians(swerveDriveConfiguration.invertedIMU ? 360 - ypr[0] : ypr[0]));
} else
{
return simIMU.getGyroRotation3d();
2023-02-13 14:37:05 -06:00
}
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
}
/**
* 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
{
2023-02-13 14:37:05 -06:00
for (SwerveModule swerveModule : swerveModules)
{
swerveModule.setDesiredState(new SwerveModuleState2(0,
swerveModule.configuration.moduleLocation.getAngle(),
0), true);
}
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)));
}
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 (!Robot.isReal())
2023-01-29 21:18:52 -06:00
{
simIMU.updateOdometry(kinematics, getStates(),
getSwerveModulePoses(swerveDrivePoseEstimator.getEstimatedPosition()), field);
2023-01-29 21:18:52 -06:00
}
2023-02-13 14:37:05 -06:00
field.setRobotPose(swerveDrivePoseEstimator.getEstimatedPosition());
double[] moduleStates = new double[swerveModules.length * 2];
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();
moduleStates[module.moduleNumber] = moduleState.angle.getDegrees();
moduleStates[module.moduleNumber + 1] = moduleState.speedMetersPerSecond;
sumOmega += Math.abs(moduleState.omegaRadPerSecond);
SmartDashboard.putNumber("Module" + module.moduleNumber + "Relative Encoder", module.getRelativePosition());
SmartDashboard.putNumber("Module" + module.moduleNumber + "Absolute Encoder", module.getAbsolutePosition());
2023-01-29 21:18:52 -06:00
}
2023-02-13 14:37:05 -06:00
SmartDashboard.putNumberArray("moduleStates", moduleStates);
// 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;
}
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.synchronizeEncoders();
}
}
/**
* Add a vision measurement to the {@link SwerveDrivePoseEstimator} and update the {@link SwerveIMU} gyro reading with
* the given timestamp of the vision measurement. <b>THIS WILL BREAK IF UPDATED TOO OFTEN.</b>
*
* @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)}.
*/
public void addVisionMeasurement(Pose2d robotPose, double timestamp, boolean soft)
{
if (soft)
{
swerveDrivePoseEstimator.addVisionMeasurement(robotPose, timestamp);
} else
{
swerveDrivePoseEstimator.resetPosition(robotPose.getRotation(), getModulePositions(), robotPose);
}
if (Robot.isReal())
{
imu.setYaw(swerveDrivePoseEstimator.getEstimatedPosition().getRotation().getDegrees());
// Yaw reset recommended by Team 1622
} else
{
simIMU.setAngle(swerveDrivePoseEstimator.getEstimatedPosition().getRotation().getRadians());
}
}
2023-02-13 14:37:05 -06:00
}