2024-Robot
Robot code for 2024 FRC season by Argos, FRC team #1756
Loading...
Searching...
No Matches
swerve_drive_subsystem.h
Go to the documentation of this file.
1
4
5#pragma once
6
7#include <choreo/lib/Choreo.h>
8#include <frc/Timer.h>
9#include <frc/controller/HolonomicDriveController.h>
10#include <frc/controller/PIDController.h>
11#include <frc/controller/ProfiledPIDController.h>
12#include <frc/kinematics/ChassisSpeeds.h>
13#include <frc/kinematics/SwerveDriveKinematics.h>
14#include <frc/kinematics/SwerveDriveOdometry.h>
15#include <frc/kinematics/SwerveModulePosition.h>
16#include <frc/kinematics/SwerveModuleState.h>
17#include <frc2/command/SubsystemBase.h>
18#include <wpi/DataLog.h>
19
20#include <array>
21#include <memory>
22#include <mutex>
23#include <thread>
24
25#include <ctre/phoenix6/CANcoder.hpp>
26#include <ctre/phoenix6/Pigeon2.hpp>
27#include <ctre/phoenix6/TalonFX.hpp>
28
34#include "frc/StateSpaceUtil.h"
35#include "frc/estimator/SwerveDrivePoseEstimator.h"
36#include "frc/geometry/Transform3d.h"
39
41 public:
42 // MOTORS
43 ctre::phoenix6::hardware::TalonFX m_drive;
44 ctre::phoenix6::hardware::TalonFX m_turn;
45 // ENCODER
46 ctre::phoenix6::hardware::CANcoder m_encoder;
47
55 SwerveModule(const argos_lib::CANAddress& driveAddr,
56 const argos_lib::CANAddress& turnAddr,
57 const argos_lib::CANAddress& encoderAddr);
58
59 frc::SwerveModuleState GetState();
60 frc::SwerveModulePosition GetPosition();
61};
62
67class SwerveDriveSubsystem : public frc2::SubsystemBase {
68 public:
74
75 explicit SwerveDriveSubsystem(const argos_lib::RobotInstance instance);
76
77 virtual ~SwerveDriveSubsystem();
78
82 void Disable();
83
91 void SwerveDrive(const double fwVelocity, const double sideVelocity, const double rotVelocity);
92
97 void SwerveDrive(const units::degree_t& velAngle, const double& velocity, const double& rotVelocity);
98
102 void SwerveDrive(const units::degree_t& velAngle, const double& velocity);
103
106 void SwerveDrive(frc::ChassisSpeeds desiredChassisSpeed);
107
111 void StopDrive();
112
113 choreolib::ChoreoControllerFunction GetChoreoControllerFunction();
114
121 void Home(const units::degree_t& angle);
122
129 void FieldHome(units::degree_t homeAngle = 0_deg, bool updateOdometry = true);
130
136 void InitializeOdometry(const frc::Pose2d& currentPose);
137
138 frc::Rotation2d GetContinuousOdometryAngle();
139
140 frc::Rotation2d GetRawOdometryAngle();
141
142 frc::Rotation2d GetNearestSquareAngle();
143
144 frc::Pose2d GetContinuousOdometry();
145
146 frc::Pose2d GetRawOdometry();
147
151 void UpdateEstimatedPose();
152
159 units::degree_t GetFieldCentricAngle();
160
166 frc::Pose2d GetPoseEstimate(const frc::Pose2d& robotPose, const units::millisecond_t& latency);
167
168 void UpdateVisionMeasurement(const frc::Pose2d& poseEstimate,
169 units::second_t timestamp,
170 const wpi::array<double, 3>& visionMeasurementStdDevs);
171
173
178 void InitializeMotors();
179
188 void UpdateFollowerLinearPIDParams(double kP, double kI, double kD);
189
198 void UpdateFollowerRotationalPIDParams(double kP, double kI, double kD);
199
205 void UpdateFollowerRotationalPIDConstraints(frc::TrapezoidProfile<units::radians>::Constraints constraints);
206 void UpdateFollowerRotationalPIDConstraints(frc::TrapezoidProfile<units::degrees>::Constraints constraints);
207
214
221
226
232 bool ProfileIsComplete() const;
233
239 bool IsFollowingProfile() const;
240
247 frc::ChassisSpeeds GetChassisVelocity();
248
252 void LockWheels();
253
254 bool GetManualOverride();
255
261 units::degree_t GetRobotPitch() { return m_pigeonIMU.GetRoll().GetValue(); }
262
268 units::degrees_per_second_t GetRobotPitchRate();
269
270 units::degree_t GetIMUYaw();
271 units::degrees_per_second_t GetIMUYawRate();
272
273 private:
275
277
282
283 // GYROSCOPIC SENSORS
284 ctre::phoenix6::hardware::Pigeon2 m_pigeonIMU;
285
286 units::degree_t m_fieldHomeOffset;
287
292 struct Velocities {
293 const double fwVelocity;
294 const double sideVelocity;
295 const double rotVelocity;
296 };
297
298 frc::SwerveDriveKinematics<4> m_swerveDriveKinematics;
299
300 frc::SwerveDriveOdometry<4> m_odometry;
301 units::degree_t m_prevOdometryAngle;
303
304 frc::SwerveDrivePoseEstimator<4> m_poseEstimator;
306 std::thread m_odometryThread;
307 std::chrono::time_point<std::chrono::steady_clock>
310
311 // std::FILE SYSTEM HOMING STORAGE
313
317 std::unique_ptr<SwerveTrapezoidalProfileSegment> m_pActiveSwerveProfile;
318 std::unique_ptr<SwerveTrapezoidalSpline> m_pActiveSwerveSplineProfile;
319 std::chrono::time_point<std::chrono::steady_clock> m_swerveProfileStartTime;
320 frc::ProfiledPIDController<units::radians>::Constraints m_rotationalPIDConstraints;
321 frc::PIDController m_linearPID;
322 frc::HolonomicDriveController m_followerController;
323
324 std::unique_ptr<argos_lib::NTMotorPIDTuner> m_driveMotorPIDTuner;
325 std::unique_ptr<argos_lib::NTSubscriber> m_linearFollowerTuner_P;
326 std::unique_ptr<argos_lib::NTSubscriber> m_linearFollowerTuner_I;
327 std::unique_ptr<argos_lib::NTSubscriber> m_linearFollowerTuner_D;
328 std::unique_ptr<argos_lib::NTSubscriber> m_rotationalFollowerTuner_P;
329 std::unique_ptr<argos_lib::NTSubscriber> m_rotationalFollowerTuner_I;
330 std::unique_ptr<argos_lib::NTSubscriber> m_rotationalFollowerTuner_D;
331 std::unique_ptr<argos_lib::NTSubscriber> m_rotationalFollowerConstraintTuner_vel;
332 std::unique_ptr<argos_lib::NTSubscriber> m_rotationalFollowerConstraintTuner_accel;
333
334 wpi::array<frc::SwerveModuleState, 4> GetRawModuleStates(frc::ChassisSpeeds velocities);
341 wpi::array<frc::SwerveModuleState, 4> GetRawModuleStates(SwerveDriveSubsystem::Velocities velocities);
342
348 wpi::array<frc::SwerveModuleState, 4> GetCurrentModuleStates();
349
355 wpi::array<frc::SwerveModulePosition, 4> GetCurrentModulePositions();
356
363 void HomeToFS(const units::degree_t& angle);
364
370
371 void ResetIMUYaw();
372
373 wpi::array<frc::SwerveModuleState, 4> OptimizeAllModules(wpi::array<frc::SwerveModuleState, 4> rawStates);
374
375 void ClosedLoopDrive(wpi::array<frc::SwerveModuleState, 4> moduleStates);
376
377 wpi::log::StructLogEntry<frc::Pose2d> m_poseEstimateLogger;
378 wpi::log::StructArrayLogEntry<frc::SwerveModuleState> m_setpointLogger;
379 wpi::log::StructArrayLogEntry<frc::SwerveModuleState> m_stateLogger;
380};
Subsystem for controlling the swerve drivetrain of the robot.
Definition swerve_drive_subsystem.h:67
void Home(const units::degree_t &angle)
Save homes to persistent storage and updates module motors.
Definition swerve_drive_subsystem.cpp:576
frc::Pose2d GetContinuousOdometry()
Definition swerve_drive_subsystem.cpp:682
void Disable()
Handle the robot disabling.
Definition swerve_drive_subsystem.cpp:278
void UpdateVisionMeasurement(const frc::Pose2d &poseEstimate, units::second_t timestamp, const wpi::array< double, 3 > &visionMeasurementStdDevs)
Definition swerve_drive_subsystem.cpp:842
void HomeToFS(const units::degree_t &angle)
Save homes to a file.
Definition swerve_drive_subsystem.cpp:861
void FieldHome(units::degree_t homeAngle=0_deg, bool updateOdometry=true)
Tell the robot it's in it's correct field-oriented "Front".
Definition swerve_drive_subsystem.cpp:627
void UpdateFollowerRotationalPIDParams(double kP, double kI, double kD)
Change PID parameters for rotational follower. These adjust velocities based on angle error from path...
Definition swerve_drive_subsystem.cpp:926
SwerveModule m_backRight
Back right swerve module.
Definition swerve_drive_subsystem.h:280
std::unique_ptr< SwerveTrapezoidalSpline > m_pActiveSwerveSplineProfile
Profile to execute.
Definition swerve_drive_subsystem.h:318
frc::PIDController m_linearPID
Correction parameters for x/y error when following drive profile.
Definition swerve_drive_subsystem.h:321
frc::HolonomicDriveController m_followerController
Controller to follow drive profile.
Definition swerve_drive_subsystem.h:322
SwerveModule m_frontLeft
Front left swerve module.
Definition swerve_drive_subsystem.h:278
wpi::log::StructArrayLogEntry< frc::SwerveModuleState > m_setpointLogger
Definition swerve_drive_subsystem.h:378
wpi::array< frc::SwerveModuleState, 4 > OptimizeAllModules(wpi::array< frc::SwerveModuleState, 4 > rawStates)
Definition swerve_drive_subsystem.cpp:994
std::chrono::time_point< std::chrono::steady_clock > m_swerveProfileStartTime
Time when active profile began.
Definition swerve_drive_subsystem.h:319
units::degrees_per_second_t GetIMUYawRate()
Definition swerve_drive_subsystem.cpp:982
virtual ~SwerveDriveSubsystem()
Definition swerve_drive_subsystem.cpp:273
std::unique_ptr< argos_lib::NTSubscriber > m_linearFollowerTuner_D
Definition swerve_drive_subsystem.h:327
std::unique_ptr< argos_lib::NTSubscriber > m_rotationalFollowerTuner_D
Definition swerve_drive_subsystem.h:330
DriveControlMode
Enumerator for either field-centric or robot centric drive modes.
Definition swerve_drive_subsystem.h:73
@ robotCentricControl
Definition swerve_drive_subsystem.h:73
@ fieldCentricControl
Definition swerve_drive_subsystem.h:73
choreolib::ChoreoControllerFunction GetChoreoControllerFunction()
Definition swerve_drive_subsystem.cpp:563
bool m_profileComplete
True once a drive profile has been completed.
Definition swerve_drive_subsystem.h:315
void CancelDrivingProfile()
Cancel the current driving profile without marking it complete.
Definition swerve_drive_subsystem.cpp:965
bool m_followingProfile
True when an incomplete drive profile is being run.
Definition swerve_drive_subsystem.h:314
bool IsFollowingProfile() const
Check if drivetrain is following a profile.
Definition swerve_drive_subsystem.cpp:974
units::degree_t m_fieldHomeOffset
Offset from IMU angle to 0 field angle (intake away from driver station)
Definition swerve_drive_subsystem.h:286
void UpdateFollowerLinearPIDParams(double kP, double kI, double kD)
Change PID parameters for linear follower. These adjust velocities based on distance error from path ...
Definition swerve_drive_subsystem.cpp:919
std::unique_ptr< argos_lib::NTSubscriber > m_rotationalFollowerConstraintTuner_accel
Definition swerve_drive_subsystem.h:332
frc::Pose2d GetRawOdometry()
Definition swerve_drive_subsystem.cpp:698
void InitializeOdometry(const frc::Pose2d &currentPose)
Set current robot position. Useful for initializing initial position before autonomous.
Definition swerve_drive_subsystem.cpp:640
void InitializeMotorsFromFS()
Initialize motors from saved file.
Definition swerve_drive_subsystem.cpp:871
frc::Pose2d GetPoseEstimate(const frc::Pose2d &robotPose, const units::millisecond_t &latency)
Get the latest pose estimate.
Definition swerve_drive_subsystem.cpp:821
wpi::array< frc::SwerveModuleState, 4 > GetRawModuleStates(frc::ChassisSpeeds velocities)
Definition swerve_drive_subsystem.cpp:286
void StartDrivingProfile(SwerveTrapezoidalProfileSegment newProfile)
Start driving a new profile. This also resets the finished flag.
Definition swerve_drive_subsystem.cpp:944
units::degree_t GetIMUYaw()
Definition swerve_drive_subsystem.cpp:978
frc::SwerveDriveKinematics< 4 > m_swerveDriveKinematics
Kinematics model for swerve drive system.
Definition swerve_drive_subsystem.h:298
units::degree_t GetRobotPitch()
Get the robot pitch as determined by the pigeon IMU.
Definition swerve_drive_subsystem.h:261
std::thread m_odometryThread
Updates robot odometry at very high rate.
Definition swerve_drive_subsystem.h:306
std::unique_ptr< argos_lib::NTMotorPIDTuner > m_driveMotorPIDTuner
Utility to tune drive motors.
Definition swerve_drive_subsystem.h:324
std::unique_ptr< argos_lib::NTSubscriber > m_rotationalFollowerConstraintTuner_vel
Definition swerve_drive_subsystem.h:331
SwerveModule m_backLeft
Back left swerve module.
Definition swerve_drive_subsystem.h:281
DriveControlMode m_controlMode
Active control mode.
Definition swerve_drive_subsystem.h:276
wpi::array< frc::SwerveModulePosition, 4 > GetCurrentModulePositions()
Get the active positions of all swerve modules.
Definition swerve_drive_subsystem.cpp:336
units::degree_t GetFieldCentricAngle()
Get the field-centric angle of the robot based on gyro and saved reference orientation.
Definition swerve_drive_subsystem.cpp:817
void SetControlMode(SwerveDriveSubsystem::DriveControlMode controlMode)
Definition swerve_drive_subsystem.cpp:853
wpi::array< frc::SwerveModuleState, 4 > GetCurrentModuleStates()
Get the active states of all swerve modules.
Definition swerve_drive_subsystem.cpp:332
std::unique_ptr< argos_lib::NTSubscriber > m_linearFollowerTuner_P
Definition swerve_drive_subsystem.h:325
bool ProfileIsComplete() const
Check if a driving profile path has been completed.
Definition swerve_drive_subsystem.cpp:970
frc::Rotation2d GetRawOdometryAngle()
Definition swerve_drive_subsystem.cpp:672
void SwerveDrive(const double fwVelocity, const double sideVelocity, const double rotVelocity)
Main drive function for the robot.
Definition swerve_drive_subsystem.cpp:340
std::unique_ptr< argos_lib::NTSubscriber > m_rotationalFollowerTuner_I
Definition swerve_drive_subsystem.h:329
std::chrono::time_point< std::chrono::steady_clock > m_odometryResetTime
Time when odometry was last reset to known position.
Definition swerve_drive_subsystem.h:308
wpi::log::StructArrayLogEntry< frc::SwerveModuleState > m_stateLogger
Definition swerve_drive_subsystem.h:379
void InitializeMotors()
Initialize motors from persistent storage.
Definition swerve_drive_subsystem.cpp:857
void UpdateEstimatedPose()
Reads module states & gyro and updates pose estimator.
Definition swerve_drive_subsystem.cpp:713
wpi::log::StructLogEntry< frc::Pose2d > m_poseEstimateLogger
Definition swerve_drive_subsystem.h:377
units::degrees_per_second_t GetRobotPitchRate()
Get the rate of robot pitch.
Definition swerve_drive_subsystem.cpp:589
frc::ChassisSpeeds GetChassisVelocity()
Get the robot velocity in chassis frame (x toward intake, y toward left) based on GetCurrentModuleSta...
Definition swerve_drive_subsystem.cpp:990
std::unique_ptr< argos_lib::NTSubscriber > m_rotationalFollowerTuner_P
Definition swerve_drive_subsystem.h:328
ctre::phoenix6::hardware::Pigeon2 m_pigeonIMU
Definition swerve_drive_subsystem.h:284
frc::ProfiledPIDController< units::radians >::Constraints m_rotationalPIDConstraints
Definition swerve_drive_subsystem.h:320
void LockWheels()
Put the robot wheels in an x shape where it locks the movement of it.
Definition swerve_drive_subsystem.cpp:593
void UpdateFollowerRotationalPIDConstraints(frc::TrapezoidProfile< units::radians >::Constraints constraints)
Update constraints to rotate robot along profiled path.
Definition swerve_drive_subsystem.cpp:931
std::unique_ptr< SwerveTrapezoidalProfileSegment > m_pActiveSwerveProfile
Profile to execute.
Definition swerve_drive_subsystem.h:317
void StopDrive()
Stop all motors.
Definition swerve_drive_subsystem.cpp:552
SwerveModule m_frontRight
Front right swerve module.
Definition swerve_drive_subsystem.h:279
std::unique_ptr< argos_lib::NTSubscriber > m_linearFollowerTuner_I
Definition swerve_drive_subsystem.h:326
frc::Rotation2d GetNearestSquareAngle()
Definition swerve_drive_subsystem.cpp:677
std::mutex m_poseEstimatorLock
Definition swerve_drive_subsystem.h:305
frc::SwerveDriveOdometry< 4 > m_odometry
Odometry to track robot.
Definition swerve_drive_subsystem.h:300
bool m_manualOverride
Definition swerve_drive_subsystem.h:316
frc::Rotation2d GetContinuousOdometryAngle()
Definition swerve_drive_subsystem.cpp:652
units::degree_t m_continuousOdometryOffset
Offset to convert [-180,180] odometry angle to continuous angle.
Definition swerve_drive_subsystem.h:302
void ResetIMUYaw()
Definition swerve_drive_subsystem.cpp:986
argos_lib::SwerveFSHomingStorage m_fsStorage
Roborio filesystem access for homes.
Definition swerve_drive_subsystem.h:312
bool GetManualOverride()
Definition swerve_drive_subsystem.cpp:623
void ClosedLoopDrive(wpi::array< frc::SwerveModuleState, 4 > moduleStates)
Definition swerve_drive_subsystem.cpp:1023
frc::SwerveDrivePoseEstimator< 4 > m_poseEstimator
accounts vision-based measurements for odometry
Definition swerve_drive_subsystem.h:304
units::degree_t m_prevOdometryAngle
Last odometry angle used for continuous calculations.
Definition swerve_drive_subsystem.h:301
bool m_stillRunning
false indicates subsystem is being destroyed
Definition swerve_drive_subsystem.h:309
argos_lib::RobotInstance m_instance
Definition swerve_drive_subsystem.h:274
Definition swerve_drive_subsystem.h:40
frc::SwerveModuleState GetState()
Definition swerve_drive_subsystem.cpp:907
ctre::phoenix6::hardware::CANcoder m_encoder
Definition swerve_drive_subsystem.h:46
ctre::phoenix6::hardware::TalonFX m_turn
Definition swerve_drive_subsystem.h:44
ctre::phoenix6::hardware::TalonFX m_drive
Definition swerve_drive_subsystem.h:43
frc::SwerveModulePosition GetPosition()
Definition swerve_drive_subsystem.cpp:913
Definition swerve_trapezoidal_profile.h:18
Definition swerve_trapezoidal_spline.h:19
Definition fs_homing.h:17
RobotInstance
Differentiates between practice robot and competition robot.
Definition config_types.h:13
A struct for holding the 3 different input velocities, for organization.
Definition swerve_drive_subsystem.h:292
const double sideVelocity
Definition swerve_drive_subsystem.h:294
const double rotVelocity
Definition swerve_drive_subsystem.h:295
const double fwVelocity
Definition swerve_drive_subsystem.h:293
Definition config_types.h:25