68 _isRunning.store(
true, std::memory_order_relaxed);
80 _isRunning.store(
false, std::memory_order_relaxed);
172 std::vector<std::unique_ptr<SwerveModuleImpl>> _modules;
174 std::vector<Translation2d> _moduleLocations;
175 std::vector<SwerveModulePosition> _modulePositions;
176 std::vector<SwerveModuleState> _moduleStates;
181 Rotation2d _operatorForwardDirection{};
184 ControlParameters _requestParameters{};
186 mutable std::recursive_mutex _stateLock;
187 SwerveDriveState _cachedState{};
188 std::function<void(SwerveDriveState
const &)> _telemetryFunction{};
191 units::hertz_t _updateFrequency;
193 std::unique_ptr<OdometryThread> _odometryThread;
206 std::derived_from<configs::ParentConfiguration> DriveMotorConfigsT,
207 std::derived_from<configs::ParentConfiguration> SteerMotorConfigsT,
208 std::derived_from<configs::ParentConfiguration> EncoderConfigsT
230 std::derived_from<configs::ParentConfiguration> DriveMotorConfigsT,
231 std::derived_from<configs::ParentConfiguration> SteerMotorConfigsT,
232 std::derived_from<configs::ParentConfiguration> EncoderConfigsT
236 units::hertz_t odometryUpdateFrequency,
239 SwerveDrivetrainImpl{drivetrainConstants, odometryUpdateFrequency, std::array{0.1, 0.1, 0.1}, std::array{0.9, 0.9, 0.9}, modules}
261 std::derived_from<configs::ParentConfiguration> DriveMotorConfigsT,
262 std::derived_from<configs::ParentConfiguration> SteerMotorConfigsT,
263 std::derived_from<configs::ParentConfiguration> EncoderConfigsT
267 units::hertz_t odometryUpdateFrequency,
268 std::array<double, 3>
const &odometryStandardDeviation,
269 std::array<double, 3>
const &visionStandardDeviation,
301 return _odometryThread->IsOdometryValid();
318 std::lock_guard<std::recursive_mutex> lock{_stateLock};
320 _requestToApply = std::move(request);
337 std::lock_guard<std::recursive_mutex> lock{_stateLock};
338 return request(_requestParameters, _modules);
350 std::lock_guard<std::recursive_mutex> lock{_stateLock};
369 std::lock_guard<std::recursive_mutex> lock{_stateLock};
370 _telemetryFunction = std::move(telemetryFunction);
383 for (
auto &module : _modules) {
384 auto status =
module->ConfigNeutralMode(neutralMode, timeoutSeconds);
399 std::lock_guard<std::recursive_mutex> lock{_stateLock};
401 for (
size_t i = 0; i < _modules.size(); ++i) {
402 _modules[i]->ResetPosition();
403 _modulePositions[i] = _modules[i]->GetPosition(
true);
434 std::lock_guard<std::recursive_mutex> lock{_stateLock};
450 std::lock_guard<std::recursive_mutex> lock{_stateLock};
466 std::lock_guard<std::recursive_mutex> lock{_stateLock};
490 std::lock_guard<std::recursive_mutex> lock{_stateLock};
491 _operatorForwardDirection = fieldDirection;
507 std::lock_guard<std::recursive_mutex> lock{_stateLock};
508 return _operatorForwardDirection;
536 std::lock_guard<std::recursive_mutex> lock{_stateLock};
573 Pose2d visionRobotPose,
574 units::second_t timestamp,
575 std::array<double, 3>
const &visionMeasurementStdDevs)
577 std::lock_guard<std::recursive_mutex> lock{_stateLock};
594 std::lock_guard<std::recursive_mutex> lock{_stateLock};
608 std::lock_guard<std::recursive_mutex> lock{_stateLock};
628 std::lock_guard<std::recursive_mutex> lock{_stateLock};
629 return _odometry.
SampleAt(timestamp);
654 std::span<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:474
T GetValue() const
Gets the cached value from this status signal.
Definition StatusSignal.hpp:522
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition CorePigeon2.hpp:1063
Class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states ...
Definition SwerveDriveKinematics.hpp:41
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:290
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:368
void ResetTranslation(Translation2d const &translation)
Resets the robot's translation.
Definition SwerveDrivePoseEstimator.hpp:316
void ResetPose(Pose2d const &pose)
Resets the robot's pose.
Definition SwerveDrivePoseEstimator.hpp:303
std::optional< Pose2d > SampleAt(units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
void SetStateStdDevs(std::array< double, 3 > const &stateStdDevs)
Sets the pose estimator's trust in robot odometry.
Definition SwerveDrivePoseEstimator.hpp:254
void ResetRotation(Rotation2d const &rotation)
Resets the robot's rotation.
Definition SwerveDrivePoseEstimator.hpp:342
void SetVisionMeasurementStdDevs(std::array< double, 3 > const &visionMeasurementStdDevs)
Sets the pose estimator's trust in vision measurements.
Definition SwerveDrivePoseEstimator.hpp:272
Performs swerve module updates in a separate thread to minimize latency.
Definition SwerveDrivetrainImpl.hpp:32
std::thread _thread
Definition SwerveDrivetrainImpl.hpp:40
std::atomic< bool > _isRunning
Definition SwerveDrivetrainImpl.hpp:42
OdometryThread(SwerveDrivetrainImpl &drivetrain)
~OdometryThread()
Definition SwerveDrivetrainImpl.hpp:56
std::vector< BaseStatusSignal * > _allSignals
Definition SwerveDrivetrainImpl.hpp:44
bool IsOdometryValid() const
Check if the odometry is currently valid.
Definition SwerveDrivetrainImpl.hpp:90
void Stop()
Stops the odometry thread.
Definition SwerveDrivetrainImpl.hpp:76
std::atomic< int > _threadPriorityToSet
Definition SwerveDrivetrainImpl.hpp:51
static constexpr int START_THREAD_PRIORITY
Definition SwerveDrivetrainImpl.hpp:34
std::atomic< int32_t > _failedDaqs
Definition SwerveDrivetrainImpl.hpp:49
std::vector< BaseStatusSignal * > _encSignals
Definition SwerveDrivetrainImpl.hpp:45
void Start()
Starts the odometry thread.
Definition SwerveDrivetrainImpl.hpp:64
units::second_t _averageLoopTime
Definition SwerveDrivetrainImpl.hpp:47
SwerveDrivetrainImpl * _drivetrain
Definition SwerveDrivetrainImpl.hpp:38
void SetThreadPriority(int priority)
Sets the odometry thread priority to a real time priority under the specified priority level.
Definition SwerveDrivetrainImpl.hpp:101
std::atomic< int32_t > _successfulDaqs
Definition SwerveDrivetrainImpl.hpp:48
std::mutex _threadMtx
Definition SwerveDrivetrainImpl.hpp:41
int _lastThreadPriority
Definition SwerveDrivetrainImpl.hpp:52
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrainImpl.hpp:29
void TareEverything()
Zero's this swerve drive's odometry entirely.
Definition SwerveDrivetrainImpl.hpp:397
void SetControl(SwerveRequestFunc &&request)
Applies the specified control function to this swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:316
std::vector< Translation2d > const & GetModuleLocations() const
Gets the locations of the swerve modules.
Definition SwerveDrivetrainImpl.hpp:661
ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode, units::second_t timeoutSeconds=0.100_s)
Configures the neutral mode to use for all modules' drive motors.
Definition SwerveDrivetrainImpl.hpp:380
units::hertz_t GetOdometryFrequency() const
Gets the target odometry update frequency.
Definition SwerveDrivetrainImpl.hpp:285
SwerveDriveState GetState() const
Gets the current state of the swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:348
void AddVisionMeasurement(Pose2d visionRobotPose, units::second_t timestamp, std::array< double, 3 > const &visionMeasurementStdDevs)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrainImpl.hpp:572
SwerveModuleImpl const & GetModule(size_t index) const
Get a reference to the module at the specified index.
Definition SwerveDrivetrainImpl.hpp:647
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, std::span< SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > const > modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
Definition SwerveDrivetrainImpl.hpp:234
bool IsOdometryValid() const
Check if the odometry is currently valid.
Definition SwerveDrivetrainImpl.hpp:299
void ResetRotation(Rotation2d const &rotation)
Resets the rotation of the robot pose without affecting translation.
Definition SwerveDrivetrainImpl.hpp:464
hardware::core::CorePigeon2 & GetPigeon2()
Gets this drivetrain's Pigeon 2 reference.
Definition SwerveDrivetrainImpl.hpp:671
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:367
void SetVisionMeasurementStdDevs(std::array< double, 3 > const &visionMeasurementStdDevs)
Sets the pose estimator's trust of global measurements.
Definition SwerveDrivetrainImpl.hpp:592
void SetStateStdDevs(std::array< double, 3 > const &stateStdDevs)
Sets the pose estimator's trust in robot odometry.
Definition SwerveDrivetrainImpl.hpp:606
std::span< std::unique_ptr< SwerveModuleImpl > const > GetModules() const
Get a reference to the full array of modules.
Definition SwerveDrivetrainImpl.hpp:654
SwerveDriveKinematics const & GetKinematics() const
Gets a reference to the kinematics used for the drivetrain.
Definition SwerveDrivetrainImpl.hpp:309
SwerveModuleImpl & GetModule(size_t index)
Get a reference to the module at the specified index.
Definition SwerveDrivetrainImpl.hpp:639
std::function< ctre::phoenix::StatusCode(ControlParameters const &, std::span< std::unique_ptr< SwerveModuleImpl > const >)> SwerveRequestFunc
Definition SwerveDrivetrainImpl.hpp:161
void SetOperatorPerspectiveForward(Rotation2d fieldDirection)
Takes the requests::ForwardPerspectiveValue::BlueAlliance perpective direction and treats it as the f...
Definition SwerveDrivetrainImpl.hpp:488
Rotation2d GetOperatorForwardDirection() const
Returns the requests::ForwardPerspectiveValue::BlueAlliance perpective direction that is treated as t...
Definition SwerveDrivetrainImpl.hpp:505
OdometryThread & GetOdometryThread()
Gets a reference to the odometry thread.
Definition SwerveDrivetrainImpl.hpp:292
hardware::core::CorePigeon2 const & GetPigeon2() const
Gets this drivetrain's Pigeon 2 reference.
Definition SwerveDrivetrainImpl.hpp:680
bool IsOnCANFD() const
Gets whether the drivetrain is on a CAN FD bus.
Definition SwerveDrivetrainImpl.hpp:278
std::optional< Pose2d > SamplePoseAt(units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
Definition SwerveDrivetrainImpl.hpp:626
void SeedFieldCentric(Rotation2d const &rotation=Rotation2d{})
Resets the rotation of the robot pose to the given value from the requests::ForwardPerspectiveValue::...
Definition SwerveDrivetrainImpl.hpp:421
ctre::phoenix::StatusCode RunTempRequest(SwerveRequestFunc &&request) const
Immediately runs the provided temporary control function.
Definition SwerveDrivetrainImpl.hpp:335
void ResetPose(Pose2d const &pose)
Resets the pose of the robot.
Definition SwerveDrivetrainImpl.hpp:432
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, std::array< double, 3 > const &odometryStandardDeviation, std::array< double, 3 > const &visionStandardDeviation, std::span< SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > const > modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
void ResetTranslation(Translation2d const &translation)
Resets the translation of the robot pose without affecting rotation.
Definition SwerveDrivetrainImpl.hpp:448
SwerveDrivetrainImpl(SwerveDrivetrainConstants const &drivetrainConstants, std::span< SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > const > modules)
Constructs a CTRE SwerveDrivetrainImpl using the specified constants.
Definition SwerveDrivetrainImpl.hpp:210
void AddVisionMeasurement(Pose2d visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrainImpl.hpp:534
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveModuleImpl.hpp:61
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:28
static constexpr int OK
No Error.
Definition StatusCodes.h:35
constexpr bool IsOK() const
Definition StatusCodes.h:858
Definition motor_constants.h:14
The state of the motor controller bridge when output is neutral or disabled.
Definition SpnEnums.hpp:1603
Common constants for a swerve drivetrain.
Definition SwerveDrivetrainConstants.hpp:19
All constants for a swerve module.
Definition SwerveModuleConstants.hpp:148
Contains everything the control requests need to calculate the module state.
Definition SwerveDrivetrainImpl.hpp:141
units::second_t timestamp
The timestamp of the current control apply, in the timebase of utils::GetCurrentTime()
Definition SwerveDrivetrainImpl.hpp:156
units::meters_per_second_t kMaxSpeed
The max speed of the robot at 12 V output.
Definition SwerveDrivetrainImpl.hpp:147
units::second_t updatePeriod
The update period of control apply.
Definition SwerveDrivetrainImpl.hpp:158
ChassisSpeeds currentChassisSpeed
The current robot-centric chassis speeds.
Definition SwerveDrivetrainImpl.hpp:152
impl::SwerveDriveKinematics * kinematics
The kinematics object used for control.
Definition SwerveDrivetrainImpl.hpp:143
Pose2d currentPose
The current pose of the robot.
Definition SwerveDrivetrainImpl.hpp:154
Rotation2d operatorForwardDirection
The forward direction from the operator perspective.
Definition SwerveDrivetrainImpl.hpp:150
Translation2d const * moduleLocations
The locations of the swerve modules.
Definition SwerveDrivetrainImpl.hpp:145
Plain-Old-Data class holding the state of the swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:115
std::vector< SwerveModuleState > ModuleStates
The current module states.
Definition SwerveDrivetrainImpl.hpp:121
int32_t SuccessfulDaqs
Number of successful data acquisitions.
Definition SwerveDrivetrainImpl.hpp:133
ChassisSpeeds Speeds
The current robot-centric velocity.
Definition SwerveDrivetrainImpl.hpp:119
units::second_t Timestamp
The timestamp of the state capture, in the timebase of utils::GetCurrentTime()
Definition SwerveDrivetrainImpl.hpp:129
std::vector< SwerveModulePosition > ModulePositions
The current module positions.
Definition SwerveDrivetrainImpl.hpp:125
Pose2d Pose
The current pose of the robot.
Definition SwerveDrivetrainImpl.hpp:117
std::vector< SwerveModuleState > ModuleTargets
The target module states.
Definition SwerveDrivetrainImpl.hpp:123
int32_t FailedDaqs
Number of failed data acquisitions.
Definition SwerveDrivetrainImpl.hpp:135
Rotation2d RawHeading
The raw heading of the robot, unaffected by vision updates and odometry resets.
Definition SwerveDrivetrainImpl.hpp:127
units::second_t OdometryPeriod
The measured odometry update period.
Definition SwerveDrivetrainImpl.hpp:131