74 _isRunning.store(
true, std::memory_order_relaxed);
86 _isRunning.store(
false, std::memory_order_relaxed);
178 std::vector<std::unique_ptr<SwerveModuleImpl>> _modules;
180 std::vector<Translation2d> _moduleLocations;
181 std::vector<SwerveModulePosition> _modulePositions;
182 std::vector<SwerveModuleState> _moduleStates;
187 Rotation2d _operatorForwardDirection{};
190 ControlParameters _requestParameters{};
192 mutable std::recursive_mutex _stateLock;
193 SwerveDriveState _cachedState{};
194 std::function<void(SwerveDriveState
const &)> _telemetryFunction{};
197 units::hertz_t _updateFrequency;
199 std::unique_ptr<OdometryThread> _odometryThread;
212 typename... ModuleConstants,
213 typename = std::enable_if_t<std::conjunction_v<
214 std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >...
249 typename... ModuleConstants,
250 typename = std::enable_if_t<std::conjunction_v<
251 std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >...
256 units::hertz_t odometryUpdateFrequency,
257 ModuleConstants
const &... modules
275 units::hertz_t odometryUpdateFrequency,
278 SwerveDrivetrainImpl{drivetrainConstants, odometryUpdateFrequency,
std::array{0.1, 0.1, 0.1},
std::array{0.9, 0.9, 0.9}, modules}
300 typename... ModuleConstants,
301 typename = std::enable_if_t<std::conjunction_v<
302 std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >...
307 units::hertz_t odometryUpdateFrequency,
308 std::array<double, 3>
const &odometryStandardDeviation,
309 std::array<double, 3>
const &visionStandardDeviation,
310 ModuleConstants
const &... modules
313 visionStandardDeviation,
std::array{modules...}}
335 units::hertz_t odometryUpdateFrequency,
336 std::array<double, 3>
const &odometryStandardDeviation,
337 std::array<double, 3>
const &visionStandardDeviation,
369 return _odometryThread->IsOdometryValid();
386 std::lock_guard<std::recursive_mutex> lock{_stateLock};
388 _requestToApply = std::move(request);
405 std::lock_guard<std::recursive_mutex> lock{_stateLock};
406 return request(_requestParameters, _modules);
418 std::lock_guard<std::recursive_mutex> lock{_stateLock};
437 std::lock_guard<std::recursive_mutex> lock{_stateLock};
438 _telemetryFunction = std::move(telemetryFunction);
450 for (
auto &module : _modules) {
451 auto status =
module->ConfigNeutralMode(neutralMode);
466 std::lock_guard<std::recursive_mutex> lock{_stateLock};
468 for (
size_t i = 0; i < _modules.size(); ++i) {
469 _modules[i]->ResetPosition();
470 _modulePositions[i] = _modules[i]->GetPosition(
true);
499 std::lock_guard<std::recursive_mutex> lock{_stateLock};
515 std::lock_guard<std::recursive_mutex> lock{_stateLock};
531 std::lock_guard<std::recursive_mutex> lock{_stateLock};
555 std::lock_guard<std::recursive_mutex> lock{_stateLock};
556 _operatorForwardDirection = fieldDirection;
572 std::lock_guard<std::recursive_mutex> lock{_stateLock};
573 return _operatorForwardDirection;
601 std::lock_guard<std::recursive_mutex> lock{_stateLock};
638 Pose2d visionRobotPose,
639 units::second_t timestamp,
640 std::array<double, 3> visionMeasurementStdDevs)
642 std::lock_guard<std::recursive_mutex> lock{_stateLock};
659 std::lock_guard<std::recursive_mutex> lock{_stateLock};
679 std::lock_guard<std::recursive_mutex> lock{_stateLock};
680 return _odometry.
SampleAt(timestamp);
705 std::vector<std::unique_ptr<SwerveModuleImpl>>
const &
GetModules()
const {
return _modules; }
Class for getting information about an available CAN bus.
Definition CANBus.hpp:19
Represents a status signal with data of type T, and operations available to retrieve information abou...
Definition StatusSignal.hpp:656
T GetValue() const
Gets the cached value from this status signal.
Definition StatusSignal.hpp:758
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition CorePigeon2.hpp:1116
The state of the motor controller bridge when output is neutral or disabled.
Definition SpnEnums.hpp:2202
This class implements a linear, digital filter.
Definition LinearFilter.hpp:78
static LinearFilter< T > MovingAverage(int taps)
Creates a K-tap FIR moving average filter of the form: y[n] = 1/k (x[k] + x[k-1] + … + x[0])
Definition LinearFilter.hpp:160
Class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states ...
Definition SwerveDriveKinematics.hpp:42
This class wraps Swerve Drive Odometry to fuse latency-compensated vision measurements with swerve dr...
Definition SwerveDrivePoseEstimator.hpp:142
void ResetPosition(Rotation2d const &gyroAngle, WheelPositions wheelPositions, Pose2d const &pose)
Resets the robot's position on the field.
Definition SwerveDrivePoseEstimator.hpp:262
void AddVisionMeasurement(Pose2d const &visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Pose2d GetEstimatedPosition() const
Gets the estimated robot pose.
Definition SwerveDrivePoseEstimator.hpp:314
void ResetTranslation(Translation2d const &translation)
Resets the robot's translation.
Definition SwerveDrivePoseEstimator.hpp:288
void ResetPose(Pose2d const &pose)
Resets the robot's pose.
Definition SwerveDrivePoseEstimator.hpp:275
std::optional< Pose2d > SampleAt(units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
void ResetRotation(Rotation2d const &rotation)
Resets the robot's rotation.
Definition SwerveDrivePoseEstimator.hpp:301
void SetVisionMeasurementStdDevs(std::array< double, 3 > const &visionMeasurementStdDevs)
Sets the pose estimator's trust in vision measurements.
Performs swerve module updates in a separate thread to minimize latency.
Definition SwerveDrivetrainImpl.hpp:33
std::thread _thread
Definition SwerveDrivetrainImpl.hpp:42
std::atomic< bool > _isRunning
Definition SwerveDrivetrainImpl.hpp:44
OdometryThread(SwerveDrivetrainImpl &drivetrain)
~OdometryThread()
Definition SwerveDrivetrainImpl.hpp:62
std::vector< BaseStatusSignal * > _allSignals
Definition SwerveDrivetrainImpl.hpp:46
bool IsOdometryValid() const
Check if the odometry is currently valid.
Definition SwerveDrivetrainImpl.hpp:96
units::second_t _lastTime
Definition SwerveDrivetrainImpl.hpp:51
void Stop()
Stops the odometry thread.
Definition SwerveDrivetrainImpl.hpp:82
std::atomic< int > _threadPriorityToSet
Definition SwerveDrivetrainImpl.hpp:57
static constexpr int START_THREAD_PRIORITY
Definition SwerveDrivetrainImpl.hpp:35
LinearFilter< units::second_t > _lowPass
Definition SwerveDrivetrainImpl.hpp:49
std::atomic< int32_t > _failedDaqs
Definition SwerveDrivetrainImpl.hpp:55
void Start()
Starts the odometry thread.
Definition SwerveDrivetrainImpl.hpp:70
bool _lastTimeValid
Definition SwerveDrivetrainImpl.hpp:50
units::second_t _averageLoopTime
Definition SwerveDrivetrainImpl.hpp:52
SwerveDrivetrainImpl * _drivetrain
Definition SwerveDrivetrainImpl.hpp:40
void SetThreadPriority(int priority)
Sets the odometry thread priority to a real time priority under the specified priority level.
Definition SwerveDrivetrainImpl.hpp:107
std::atomic< int32_t > _successfulDaqs
Definition SwerveDrivetrainImpl.hpp:54
std::mutex _threadMtx
Definition SwerveDrivetrainImpl.hpp:43
static constexpr int kLowPassTaps
Definition SwerveDrivetrainImpl.hpp:48
int _lastThreadPriority
Definition SwerveDrivetrainImpl.hpp:58
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrainImpl.hpp:30
void TareEverything()
Zero's this swerve drive's odometry entirely.
Definition SwerveDrivetrainImpl.hpp:464
std::function< ctre::phoenix::StatusCode(ControlParameters const &, std::vector< std::unique_ptr< SwerveModuleImpl > > const &)> SwerveRequestFunc
Definition SwerveDrivetrainImpl.hpp:167
void SetControl(SwerveRequestFunc &&request)
Applies the specified control function to this swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:384
std::vector< Translation2d > const & GetModuleLocations() const
Gets the locations of the swerve modules.
Definition SwerveDrivetrainImpl.hpp:712
units::hertz_t GetOdometryFrequency() const
Gets the target odometry update frequency.
Definition SwerveDrivetrainImpl.hpp:353
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, std::array< double, 3 > const &odometryStandardDeviation, std::array< double, 3 > const &visionStandardDeviation, span< SwerveModuleConstants< configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration > const > modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
SwerveDriveState GetState() const
Gets the current state of the swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:416
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
Definition SwerveDrivetrainImpl.hpp:217
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, span< SwerveModuleConstants< configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration > const > modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
Definition SwerveDrivetrainImpl.hpp:273
void SeedFieldCentric()
Resets the rotation of the robot pose to 0 from the requests::ForwardPerspectiveValue::OperatorPerspe...
Definition SwerveDrivetrainImpl.hpp:486
SwerveModuleImpl const & GetModule(size_t index) const
Get a reference to the module at the specified index.
Definition SwerveDrivetrainImpl.hpp:698
bool IsOdometryValid() const
Check if the odometry is currently valid.
Definition SwerveDrivetrainImpl.hpp:367
void ResetRotation(Rotation2d const &rotation)
Resets the rotation of the robot pose without affecting translation.
Definition SwerveDrivetrainImpl.hpp:529
hardware::core::CorePigeon2 & GetPigeon2()
Gets this drivetrain's Pigeon 2 reference.
Definition SwerveDrivetrainImpl.hpp:722
void RegisterTelemetry(std::function< void(SwerveDriveState const &)> telemetryFunction)
Register the specified lambda to be executed whenever the SwerveDriveState is updated in the odometry...
Definition SwerveDrivetrainImpl.hpp:435
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, span< SwerveModuleConstants< configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration > const > modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
Definition SwerveDrivetrainImpl.hpp:229
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, std::array< double, 3 > const &odometryStandardDeviation, std::array< double, 3 > const &visionStandardDeviation, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
Definition SwerveDrivetrainImpl.hpp:305
void AddVisionMeasurement(Pose2d visionRobotPose, units::second_t timestamp, std::array< double, 3 > visionMeasurementStdDevs)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrainImpl.hpp:637
std::vector< std::unique_ptr< SwerveModuleImpl > > const & GetModules() const
Get a reference to the full array of modules.
Definition SwerveDrivetrainImpl.hpp:705
ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode)
Configures the neutral mode to use for all modules' drive motors.
Definition SwerveDrivetrainImpl.hpp:447
SwerveDriveKinematics const & GetKinematics() const
Gets a reference to the kinematics used for the drivetrain.
Definition SwerveDrivetrainImpl.hpp:377
SwerveModuleImpl & GetModule(size_t index)
Get a reference to the module at the specified index.
Definition SwerveDrivetrainImpl.hpp:690
void SetOperatorPerspectiveForward(Rotation2d fieldDirection)
Takes the requests::ForwardPerspectiveValue::BlueAlliance perpective direction and treats it as the f...
Definition SwerveDrivetrainImpl.hpp:553
Rotation2d GetOperatorForwardDirection() const
Returns the requests::ForwardPerspectiveValue::BlueAlliance perpective direction that is treated as t...
Definition SwerveDrivetrainImpl.hpp:570
OdometryThread & GetOdometryThread()
Gets a reference to the odometry thread.
Definition SwerveDrivetrainImpl.hpp:360
std::optional< Pose2d > SamplePoseAt(units::second_t timestamp)
Return the pose at a given timestamp, if the buffer is not empty.
Definition SwerveDrivetrainImpl.hpp:677
bool IsOnCANFD() const
Gets whether the drivetrain is on a CAN FD bus.
Definition SwerveDrivetrainImpl.hpp:346
void SetVisionMeasurementStdDevs(std::array< double, 3 > visionMeasurementStdDevs)
Sets the pose estimator's trust of global measurements.
Definition SwerveDrivetrainImpl.hpp:657
ctre::phoenix::StatusCode RunTempRequest(SwerveRequestFunc &&request) const
Immediately runs the provided temporary control function.
Definition SwerveDrivetrainImpl.hpp:403
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
Definition SwerveDrivetrainImpl.hpp:254
void ResetPose(Pose2d const &pose)
Resets the pose of the robot.
Definition SwerveDrivetrainImpl.hpp:497
void ResetTranslation(Translation2d const &translation)
Resets the translation of the robot pose without affecting rotation.
Definition SwerveDrivetrainImpl.hpp:513
void AddVisionMeasurement(Pose2d visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrainImpl.hpp:599
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveModuleImpl.hpp:60
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:27
static constexpr int OK
No Error.
Definition StatusCodes.h:34
constexpr bool IsOK() const
Definition StatusCodes.h:859
Definition MotionMagicExpoTorqueCurrentFOC.hpp:18
Common constants for a swerve drivetrain.
Definition SwerveDrivetrainConstants.hpp:19
All constants for a swerve module.
Definition SwerveModuleConstants.hpp:117
Contains everything the control requests need to calculate the module state.
Definition SwerveDrivetrainImpl.hpp:147
units::second_t timestamp
The timestamp of the current control apply, in the timebase of utils::GetCurrentTime()
Definition SwerveDrivetrainImpl.hpp:162
units::meters_per_second_t kMaxSpeed
The max speed of the robot at 12 V output.
Definition SwerveDrivetrainImpl.hpp:153
units::second_t updatePeriod
The update period of control apply.
Definition SwerveDrivetrainImpl.hpp:164
ChassisSpeeds currentChassisSpeed
The current chassis speeds of the robot.
Definition SwerveDrivetrainImpl.hpp:158
impl::SwerveDriveKinematics * kinematics
The kinematics object used for control.
Definition SwerveDrivetrainImpl.hpp:149
Pose2d currentPose
The current pose of the robot.
Definition SwerveDrivetrainImpl.hpp:160
Rotation2d operatorForwardDirection
The forward direction from the operator perspective.
Definition SwerveDrivetrainImpl.hpp:156
Translation2d const * moduleLocations
The locations of the swerve modules.
Definition SwerveDrivetrainImpl.hpp:151
Plain-Old-Data class holding the state of the swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:121
std::vector< SwerveModuleState > ModuleStates
The current module states.
Definition SwerveDrivetrainImpl.hpp:127
int32_t SuccessfulDaqs
Number of successful data acquisitions.
Definition SwerveDrivetrainImpl.hpp:139
ChassisSpeeds Speeds
The current velocity of the robot.
Definition SwerveDrivetrainImpl.hpp:125
units::second_t Timestamp
The timestamp of the state capture, in the timebase of utils::GetCurrentTime()
Definition SwerveDrivetrainImpl.hpp:135
std::vector< SwerveModulePosition > ModulePositions
The current module positions.
Definition SwerveDrivetrainImpl.hpp:131
Pose2d Pose
The current pose of the robot.
Definition SwerveDrivetrainImpl.hpp:123
std::vector< SwerveModuleState > ModuleTargets
The target module states.
Definition SwerveDrivetrainImpl.hpp:129
int32_t FailedDaqs
Number of failed data acquisitions.
Definition SwerveDrivetrainImpl.hpp:141
Rotation2d RawHeading
The raw heading of the robot, unaffected by vision updates and odometry resets.
Definition SwerveDrivetrainImpl.hpp:133
units::second_t OdometryPeriod
The measured odometry update period.
Definition SwerveDrivetrainImpl.hpp:137