|
2024-Robot
Robot code for 2024 FRC season by Argos, FRC team #1756
|
Subsystem for controlling the swerve drivetrain of the robot. More...
#include <swerve_drive_subsystem.h>
Classes | |
| struct | Velocities |
| A struct for holding the 3 different input velocities, for organization. More... | |
Public Types | |
| enum | DriveControlMode { fieldCentricControl , robotCentricControl } |
| Enumerator for either field-centric or robot centric drive modes. More... | |
Public Member Functions | |
| SwerveDriveSubsystem (const argos_lib::RobotInstance instance) | |
| virtual | ~SwerveDriveSubsystem () |
| void | Disable () |
| Handle the robot disabling. | |
| void | SwerveDrive (const double fwVelocity, const double sideVelocity, const double rotVelocity) |
| Main drive function for the robot. | |
| void | SwerveDrive (const units::degree_t &velAngle, const double &velocity, const double &rotVelocity) |
| Same as polar swerve drive function, but also takes in a rotational velocity to apply ONLY USE IN FIELD-CENTRIC. | |
| void | SwerveDrive (const units::degree_t &velAngle, const double &velocity) |
| Takes in speeds as a polar vector, and calculates the forward and side velocity to apply ONLY USE IN FIELD-CENTRIC. | |
| void | SwerveDrive (frc::ChassisSpeeds desiredChassisSpeed) |
| Drive a set chassis speed. Used for choreo path tracking. | |
| void | StopDrive () |
| Stop all motors. | |
| choreolib::ChoreoControllerFunction | GetChoreoControllerFunction () |
| void | Home (const units::degree_t &angle) |
| Save homes to persistent storage and updates module motors. | |
| void | FieldHome (units::degree_t homeAngle=0_deg, bool updateOdometry=true) |
| Tell the robot it's in it's correct field-oriented "Front". | |
| void | InitializeOdometry (const frc::Pose2d ¤tPose) |
| Set current robot position. Useful for initializing initial position before autonomous. | |
| frc::Rotation2d | GetContinuousOdometryAngle () |
| frc::Rotation2d | GetRawOdometryAngle () |
| frc::Rotation2d | GetNearestSquareAngle () |
| frc::Pose2d | GetContinuousOdometry () |
| frc::Pose2d | GetRawOdometry () |
| void | UpdateEstimatedPose () |
| Reads module states & gyro and updates pose estimator. | |
| units::degree_t | GetFieldCentricAngle () |
| Get the field-centric angle of the robot based on gyro and saved reference orientation. | |
| frc::Pose2d | GetPoseEstimate (const frc::Pose2d &robotPose, const units::millisecond_t &latency) |
| Get the latest pose estimate. | |
| void | UpdateVisionMeasurement (const frc::Pose2d &poseEstimate, units::second_t timestamp, const wpi::array< double, 3 > &visionMeasurementStdDevs) |
| void | SetControlMode (SwerveDriveSubsystem::DriveControlMode controlMode) |
| void | InitializeMotors () |
| Initialize motors from persistent storage. | |
| void | UpdateFollowerLinearPIDParams (double kP, double kI, double kD) |
| Change PID parameters for linear follower. These adjust velocities based on distance error from path goal. | |
| void | UpdateFollowerRotationalPIDParams (double kP, double kI, double kD) |
| Change PID parameters for rotational follower. These adjust velocities based on angle error from path goal. | |
| void | UpdateFollowerRotationalPIDConstraints (frc::TrapezoidProfile< units::radians >::Constraints constraints) |
| Update constraints to rotate robot along profiled path. | |
| void | UpdateFollowerRotationalPIDConstraints (frc::TrapezoidProfile< units::degrees >::Constraints constraints) |
| void | StartDrivingProfile (SwerveTrapezoidalProfileSegment newProfile) |
| Start driving a new profile. This also resets the finished flag. | |
| void | StartDrivingProfile (SwerveTrapezoidalSpline newProfile) |
| Start driving a new profile. This also resets the finished flag. | |
| void | CancelDrivingProfile () |
| Cancel the current driving profile without marking it complete. | |
| bool | ProfileIsComplete () const |
| Check if a driving profile path has been completed. | |
| bool | IsFollowingProfile () const |
| Check if drivetrain is following a profile. | |
| frc::ChassisSpeeds | GetChassisVelocity () |
| Get the robot velocity in chassis frame (x toward intake, y toward left) based on GetCurrentModuleStates() output. | |
| void | LockWheels () |
| Put the robot wheels in an x shape where it locks the movement of it. | |
| bool | GetManualOverride () |
| units::degree_t | GetRobotPitch () |
| Get the robot pitch as determined by the pigeon IMU. | |
| units::degrees_per_second_t | GetRobotPitchRate () |
| Get the rate of robot pitch. | |
| units::degree_t | GetIMUYaw () |
| units::degrees_per_second_t | GetIMUYawRate () |
Private Member Functions | |
| wpi::array< frc::SwerveModuleState, 4 > | GetRawModuleStates (frc::ChassisSpeeds velocities) |
| wpi::array< frc::SwerveModuleState, 4 > | GetRawModuleStates (SwerveDriveSubsystem::Velocities velocities) |
| Get the Raw Module States object and switch between robot-centric and field-centric. | |
| wpi::array< frc::SwerveModuleState, 4 > | GetCurrentModuleStates () |
| Get the active states of all swerve modules. | |
| wpi::array< frc::SwerveModulePosition, 4 > | GetCurrentModulePositions () |
| Get the active positions of all swerve modules. | |
| void | HomeToFS (const units::degree_t &angle) |
| Save homes to a file. | |
| void | InitializeMotorsFromFS () |
| Initialize motors from saved file. | |
| void | ResetIMUYaw () |
| wpi::array< frc::SwerveModuleState, 4 > | OptimizeAllModules (wpi::array< frc::SwerveModuleState, 4 > rawStates) |
| void | ClosedLoopDrive (wpi::array< frc::SwerveModuleState, 4 > moduleStates) |
Private Attributes | |
| argos_lib::RobotInstance | m_instance |
| DriveControlMode | m_controlMode |
| Active control mode. | |
| SwerveModule | m_frontLeft |
| Front left swerve module. | |
| SwerveModule | m_frontRight |
| Front right swerve module. | |
| SwerveModule | m_backRight |
| Back right swerve module. | |
| SwerveModule | m_backLeft |
| Back left swerve module. | |
| ctre::phoenix6::hardware::Pigeon2 | m_pigeonIMU |
| units::degree_t | m_fieldHomeOffset |
| Offset from IMU angle to 0 field angle (intake away from driver station) | |
| frc::SwerveDriveKinematics< 4 > | m_swerveDriveKinematics |
| Kinematics model for swerve drive system. | |
| frc::SwerveDriveOdometry< 4 > | m_odometry |
| Odometry to track robot. | |
| units::degree_t | m_prevOdometryAngle |
| Last odometry angle used for continuous calculations. | |
| units::degree_t | m_continuousOdometryOffset |
| Offset to convert [-180,180] odometry angle to continuous angle. | |
| frc::SwerveDrivePoseEstimator< 4 > | m_poseEstimator |
| accounts vision-based measurements for odometry | |
| std::mutex | m_poseEstimatorLock |
| std::thread | m_odometryThread |
| Updates robot odometry at very high rate. | |
| std::chrono::time_point< std::chrono::steady_clock > | m_odometryResetTime |
| Time when odometry was last reset to known position. | |
| bool | m_stillRunning |
| false indicates subsystem is being destroyed | |
| argos_lib::SwerveFSHomingStorage | m_fsStorage |
| Roborio filesystem access for homes. | |
| bool | m_followingProfile |
| True when an incomplete drive profile is being run. | |
| bool | m_profileComplete |
| True once a drive profile has been completed. | |
| bool | m_manualOverride |
| std::unique_ptr< SwerveTrapezoidalProfileSegment > | m_pActiveSwerveProfile |
| Profile to execute. | |
| std::unique_ptr< SwerveTrapezoidalSpline > | m_pActiveSwerveSplineProfile |
| Profile to execute. | |
| std::chrono::time_point< std::chrono::steady_clock > | m_swerveProfileStartTime |
| Time when active profile began. | |
| frc::ProfiledPIDController< units::radians >::Constraints | m_rotationalPIDConstraints |
| frc::PIDController | m_linearPID |
| Correction parameters for x/y error when following drive profile. | |
| frc::HolonomicDriveController | m_followerController |
| Controller to follow drive profile. | |
| std::unique_ptr< argos_lib::NTMotorPIDTuner > | m_driveMotorPIDTuner |
| Utility to tune drive motors. | |
| std::unique_ptr< argos_lib::NTSubscriber > | m_linearFollowerTuner_P |
| std::unique_ptr< argos_lib::NTSubscriber > | m_linearFollowerTuner_I |
| std::unique_ptr< argos_lib::NTSubscriber > | m_linearFollowerTuner_D |
| std::unique_ptr< argos_lib::NTSubscriber > | m_rotationalFollowerTuner_P |
| std::unique_ptr< argos_lib::NTSubscriber > | m_rotationalFollowerTuner_I |
| std::unique_ptr< argos_lib::NTSubscriber > | m_rotationalFollowerTuner_D |
| std::unique_ptr< argos_lib::NTSubscriber > | m_rotationalFollowerConstraintTuner_vel |
| std::unique_ptr< argos_lib::NTSubscriber > | m_rotationalFollowerConstraintTuner_accel |
| wpi::log::StructLogEntry< frc::Pose2d > | m_poseEstimateLogger |
| wpi::log::StructArrayLogEntry< frc::SwerveModuleState > | m_setpointLogger |
| wpi::log::StructArrayLogEntry< frc::SwerveModuleState > | m_stateLogger |
Subsystem for controlling the swerve drivetrain of the robot.
|
explicit |
|
virtual |
| void SwerveDriveSubsystem::CancelDrivingProfile | ( | ) |
Cancel the current driving profile without marking it complete.
|
private |
| void SwerveDriveSubsystem::Disable | ( | ) |
Handle the robot disabling.
| void SwerveDriveSubsystem::FieldHome | ( | units::degree_t | homeAngle = 0_deg, |
| bool | updateOdometry = true |
||
| ) |
Tell the robot it's in it's correct field-oriented "Front".
| homeAngle | Current orientation of the robot |
| updateOdometry | Also update odometry field-centric angle |
| frc::ChassisSpeeds SwerveDriveSubsystem::GetChassisVelocity | ( | ) |
Get the robot velocity in chassis frame (x toward intake, y toward left) based on GetCurrentModuleStates() output.
| choreolib::ChoreoControllerFunction SwerveDriveSubsystem::GetChoreoControllerFunction | ( | ) |
| frc::Pose2d SwerveDriveSubsystem::GetContinuousOdometry | ( | ) |
| frc::Rotation2d SwerveDriveSubsystem::GetContinuousOdometryAngle | ( | ) |
|
private |
Get the active positions of all swerve modules.
|
private |
Get the active states of all swerve modules.
| units::degree_t SwerveDriveSubsystem::GetFieldCentricAngle | ( | ) |
Get the field-centric angle of the robot based on gyro and saved reference orientation.
| units::degree_t SwerveDriveSubsystem::GetIMUYaw | ( | ) |
| units::degrees_per_second_t SwerveDriveSubsystem::GetIMUYawRate | ( | ) |
| bool SwerveDriveSubsystem::GetManualOverride | ( | ) |
| frc::Rotation2d SwerveDriveSubsystem::GetNearestSquareAngle | ( | ) |
| frc::Pose2d SwerveDriveSubsystem::GetPoseEstimate | ( | const frc::Pose2d & | robotPose, |
| const units::millisecond_t & | latency | ||
| ) |
Get the latest pose estimate.
|
private |
|
private |
Get the Raw Module States object and switch between robot-centric and field-centric.
| velocities | Desired velocity |
| frc::Pose2d SwerveDriveSubsystem::GetRawOdometry | ( | ) |
| frc::Rotation2d SwerveDriveSubsystem::GetRawOdometryAngle | ( | ) |
|
inline |
Get the robot pitch as determined by the pigeon IMU.
| units::degrees_per_second_t SwerveDriveSubsystem::GetRobotPitchRate | ( | ) |
Get the rate of robot pitch.
| void SwerveDriveSubsystem::Home | ( | const units::degree_t & | angle | ) |
Save homes to persistent storage and updates module motors.
| angle | Current angle of all the swerve modules. They should all be oriented the same during homing. |
|
private |
Save homes to a file.
| angle | Current angle of all the swerve modules. They should all be oriented the same during homing. |
| void SwerveDriveSubsystem::InitializeMotors | ( | ) |
Initialize motors from persistent storage.
|
private |
Initialize motors from saved file.
| void SwerveDriveSubsystem::InitializeOdometry | ( | const frc::Pose2d & | currentPose | ) |
Set current robot position. Useful for initializing initial position before autonomous.
| currentPose | Field-centric pose of the robot |
| bool SwerveDriveSubsystem::IsFollowingProfile | ( | ) | const |
Check if drivetrain is following a profile.
| void SwerveDriveSubsystem::LockWheels | ( | ) |
Put the robot wheels in an x shape where it locks the movement of it.
|
private |
| bool SwerveDriveSubsystem::ProfileIsComplete | ( | ) | const |
Check if a driving profile path has been completed.
|
private |
| void SwerveDriveSubsystem::SetControlMode | ( | SwerveDriveSubsystem::DriveControlMode | controlMode | ) |
| void SwerveDriveSubsystem::StartDrivingProfile | ( | SwerveTrapezoidalProfileSegment | newProfile | ) |
Start driving a new profile. This also resets the finished flag.
| newProfile | Profile to follow with t=0 being the time this function is called |
| void SwerveDriveSubsystem::StartDrivingProfile | ( | SwerveTrapezoidalSpline | newProfile | ) |
Start driving a new profile. This also resets the finished flag.
| newProfile | Profile to follow with t=0 being the time this function is called |
| void SwerveDriveSubsystem::StopDrive | ( | ) |
Stop all motors.
| void SwerveDriveSubsystem::SwerveDrive | ( | const double | fwVelocity, |
| const double | sideVelocity, | ||
| const double | rotVelocity | ||
| ) |
Main drive function for the robot.
| fwVelocity | Percent speed forward. Range [-1.0, 1.0] where positive 1.0 is full speed forward |
| sideVelocity | Percent speed perpendicular to the robots front. Range [-1.0, 1.0] where positive 1.0 is full speed left |
| rotVelocity | Percent speed of rotation of the chassis. Range [-1.0, 1.0] where positive 1.0 is full speed counterclockwise |
| void SwerveDriveSubsystem::SwerveDrive | ( | const units::degree_t & | velAngle, |
| const double & | velocity | ||
| ) |
Takes in speeds as a polar vector, and calculates the forward and side velocity to apply ONLY USE IN FIELD-CENTRIC.
| velAngle | Angle of velocity vector, [0, 360] with 0 degrees being field-centric home |
| velocity | Magnitude of velocity on [0, 1] to apply |
| void SwerveDriveSubsystem::SwerveDrive | ( | const units::degree_t & | velAngle, |
| const double & | velocity, | ||
| const double & | rotVelocity | ||
| ) |
Same as polar swerve drive function, but also takes in a rotational velocity to apply ONLY USE IN FIELD-CENTRIC.
| velAngle | Angle of velocity vector, [0, 360] with 0 degrees being field-centric home |
| velocity | Magnitude of velocity on [0, 1] to apply |
| rotVelocity | Percent speed of rotation of the chassis. Range [-1.0, 1.0] where positive 1.0 is full speed counterclockwise |
| void SwerveDriveSubsystem::SwerveDrive | ( | frc::ChassisSpeeds | desiredChassisSpeed | ) |
Drive a set chassis speed. Used for choreo path tracking.
| desiredChassisSpeed | Motion parameters |
| void SwerveDriveSubsystem::UpdateEstimatedPose | ( | ) |
Reads module states & gyro and updates pose estimator.
| void SwerveDriveSubsystem::UpdateFollowerLinearPIDParams | ( | double | kP, |
| double | kI, | ||
| double | kD | ||
| ) |
Change PID parameters for linear follower. These adjust velocities based on distance error from path goal.
| kP | Proportional gain |
| kI | Integral gain |
| kD | Derivative gain |
| void SwerveDriveSubsystem::UpdateFollowerRotationalPIDConstraints | ( | frc::TrapezoidProfile< units::degrees >::Constraints | constraints | ) |
| void SwerveDriveSubsystem::UpdateFollowerRotationalPIDConstraints | ( | frc::TrapezoidProfile< units::radians >::Constraints | constraints | ) |
Update constraints to rotate robot along profiled path.
| constraints | Rotational velocity and acceleration constraints |
| void SwerveDriveSubsystem::UpdateFollowerRotationalPIDParams | ( | double | kP, |
| double | kI, | ||
| double | kD | ||
| ) |
Change PID parameters for rotational follower. These adjust velocities based on angle error from path goal.
| kP | Proportional gain |
| kI | Integral gain |
| kD | Derivative gain |
| void SwerveDriveSubsystem::UpdateVisionMeasurement | ( | const frc::Pose2d & | poseEstimate, |
| units::second_t | timestamp, | ||
| const wpi::array< double, 3 > & | visionMeasurementStdDevs | ||
| ) |
|
private |
Back left swerve module.
|
private |
Back right swerve module.
|
private |
Offset to convert [-180,180] odometry angle to continuous angle.
|
private |
Active control mode.
|
private |
Utility to tune drive motors.
|
private |
Offset from IMU angle to 0 field angle (intake away from driver station)
|
private |
Controller to follow drive profile.
|
private |
True when an incomplete drive profile is being run.
|
private |
Front left swerve module.
|
private |
Front right swerve module.
|
private |
Roborio filesystem access for homes.
|
private |
|
private |
|
private |
|
private |
|
private |
Correction parameters for x/y error when following drive profile.
|
private |
|
private |
Odometry to track robot.
|
private |
Time when odometry was last reset to known position.
|
private |
Updates robot odometry at very high rate.
|
private |
Profile to execute.
|
private |
Profile to execute.
|
private |
|
private |
|
private |
accounts vision-based measurements for odometry
|
private |
|
private |
Last odometry angle used for continuous calculations.
|
private |
True once a drive profile has been completed.
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
false indicates subsystem is being destroyed
|
private |
Kinematics model for swerve drive system.
|
private |
Time when active profile began.