|
template<typename... ModuleConstants, typename = std::enable_if_t<std::conjunction_v< std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >... >>> |
| SwerveDrivetrain (SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules) |
| Constructs a CTRE SwerveDrivetrain using the specified constants.
|
|
template<typename... ModuleConstants, typename = std::enable_if_t<std::conjunction_v< std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >... >>> |
| SwerveDrivetrain (SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, ModuleConstants const &... modules) |
| Constructs a CTRE SwerveDrivetrain using the specified constants.
|
|
template<typename... ModuleConstants, typename = std::enable_if_t<std::conjunction_v< std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >... >>> |
| SwerveDrivetrain (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 SwerveDrivetrain using the specified constants.
|
|
virtual | ~SwerveDrivetrain ()=default |
|
virtual void | UpdateSimState (units::second_t dt, units::volt_t supplyVoltage) |
| Updates all the simulation state variables for this drivetrain class.
|
|
bool | IsOnCANFD () const |
| Gets whether the drivetrain is on a CAN FD bus.
|
|
units::hertz_t | GetOdometryFrequency () const |
| Gets the target odometry update frequency.
|
|
OdometryThread & | GetOdometryThread () |
| Gets a reference to the odometry thread.
|
|
virtual bool | IsOdometryValid () const |
| Check if the odometry is currently valid.
|
|
impl::SwerveDriveKinematics const & | GetKinematics () const |
| Gets a reference to the kinematics used for the drivetrain.
|
|
template<typename Request , typename = std::enable_if_t<std::is_base_of_v<requests::SwerveRequest, Request>>, typename = std::enable_if_t<!std::is_const_v<Request>>> |
void | SetControl (Request &request) |
| Applies the specified control request to this swerve drivetrain.
|
|
template<typename Request , typename = std::enable_if_t<std::is_base_of_v<requests::SwerveRequest, Request>>, typename = std::enable_if_t<!std::is_const_v<Request>>> |
void | SetControl (Request &&request) |
| Applies the specified control request to this swerve drivetrain.
|
|
SwerveDriveState | GetState () const |
| Gets the current state of the swerve drivetrain.
|
|
virtual void | RegisterTelemetry (std::function< void(SwerveDriveState const &)> telemetryFunction) |
| Register the specified lambda to be executed whenever the SwerveDriveState is updated in the odometry thread.
|
|
virtual ctre::phoenix::StatusCode | ConfigNeutralMode (signals::NeutralModeValue neutralMode) |
| Configures the neutral mode to use for all modules' drive motors.
|
|
virtual void | TareEverything () |
| Zero's this swerve drive's odometry entirely.
|
|
virtual void | SeedFieldCentric () |
| Resets the rotation of the robot pose to 0 from the requests::ForwardPerspectiveValue::OperatorPerspective perspective.
|
|
virtual void | ResetPose (Pose2d const &pose) |
| Resets the pose of the robot.
|
|
virtual void | ResetTranslation (Translation2d const &translation) |
| Resets the translation of the robot pose without affecting rotation.
|
|
virtual void | ResetRotation (Rotation2d const &rotation) |
| Resets the rotation of the robot pose without affecting translation.
|
|
virtual void | SetOperatorPerspectiveForward (Rotation2d fieldDirection) |
| Takes the requests::ForwardPerspectiveValue::BlueAlliance perpective direction and treats it as the forward direction for requests::ForwardPerspectiveValue::OperatorPerspective.
|
|
Rotation2d | GetOperatorForwardDirection () const |
| Returns the requests::ForwardPerspectiveValue::BlueAlliance perpective direction that is treated as the forward direction for requests::ForwardPerspectiveValue::OperatorPerspective.
|
|
virtual void | AddVisionMeasurement (Pose2d visionRobotPose, units::second_t timestamp) |
| Adds a vision measurement to the Kalman Filter.
|
|
virtual void | AddVisionMeasurement (Pose2d visionRobotPose, units::second_t timestamp, std::array< double, 3 > visionMeasurementStdDevs) |
| Adds a vision measurement to the Kalman Filter.
|
|
virtual void | SetVisionMeasurementStdDevs (std::array< double, 3 > visionMeasurementStdDevs) |
| Sets the pose estimator's trust of global measurements.
|
|
virtual std::optional< Pose2d > | SamplePoseAt (units::second_t timestamp) |
| Return the pose at a given timestamp, if the buffer is not empty.
|
|
SwerveModule< DriveMotorT, SteerMotorT, EncoderT > & | GetModule (size_t index) |
| Get a reference to the module at the specified index.
|
|
SwerveModule< DriveMotorT, SteerMotorT, EncoderT > const & | GetModule (size_t index) const |
| Get a reference to the module at the specified index.
|
|
std::vector< std::unique_ptr< SwerveModule< DriveMotorT, SteerMotorT, EncoderT > > > const & | GetModules () const |
| Get a reference to the full array of modules.
|
|
std::vector< Translation2d > const & | GetModuleLocations () const |
| Gets the locations of the swerve modules.
|
|
frc::Rotation3d | GetRotation3d () const |
| Gets the current orientation of the robot as a frc#Rotation3d from the Pigeon 2 quaternion values.
|
|
hardware::Pigeon2 & | GetPigeon2 () |
| Gets this drivetrain's Pigeon 2 reference.
|
|
template<typename DriveMotorT, typename SteerMotorT, typename EncoderT, typename = std::enable_if_t<std::is_base_of_v<hardware::traits::CommonTalon, DriveMotorT>>, typename = std::enable_if_t<std::is_base_of_v<hardware::traits::CommonTalon, SteerMotorT>>, typename = std::enable_if_t<std::is_base_of_v<hardware::ParentDevice, EncoderT>>>
class ctre::phoenix6::swerve::SwerveDrivetrain< DriveMotorT, SteerMotorT, EncoderT, typename, typename, typename >
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
This class handles the kinematics, configuration, and odometry of a swerve drive utilizing CTR Electronics devices. We recommend using the Swerve Project Generator in Tuner X to create a template project that demonstrates how to use this class.
This class performs pose estimation internally using a separate odometry thread. Vision measurements can be added using AddVisionMeasurement. Other odometry APIs such as ResetPose are also available. The resulting pose estimate can be retrieved along with module states and other information using GetState. Additionally, the odometry thread synchronously provides all new state updates to a telemetry function registered with RegisterTelemetry.
This class will construct the hardware devices internally, so the user only specifies the constants (IDs, PID gains, gear ratios, etc). Getters for these hardware devices are available.
If using the generator, the order in which modules are constructed is Front Left, Front Right, Back Left, Back Right. This means if you need the Back Left module, call GetModule(2)
; to get the third (0-indexed) module.
template<typename DriveMotorT , typename SteerMotorT , typename EncoderT , typename = std::enable_if_t<std::is_base_of_v<hardware::traits::CommonTalon, DriveMotorT>>, typename = std::enable_if_t<std::is_base_of_v<hardware::traits::CommonTalon, SteerMotorT>>, typename = std::enable_if_t<std::is_base_of_v<hardware::ParentDevice, EncoderT>>>
template<typename... ModuleConstants, typename = std::enable_if_t<std::conjunction_v< std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >... >>>
Constructs a CTRE SwerveDrivetrain using the specified constants.
This constructs the underlying hardware devices, so users should not construct the devices themselves. If they need the devices, they can access them through getters in the classes.
- Parameters
-
drivetrainConstants | Drivetrain-wide constants for the swerve drive |
modules | Constants for each specific module |
template<typename DriveMotorT , typename SteerMotorT , typename EncoderT , typename = std::enable_if_t<std::is_base_of_v<hardware::traits::CommonTalon, DriveMotorT>>, typename = std::enable_if_t<std::is_base_of_v<hardware::traits::CommonTalon, SteerMotorT>>, typename = std::enable_if_t<std::is_base_of_v<hardware::ParentDevice, EncoderT>>>
template<typename... ModuleConstants, typename = std::enable_if_t<std::conjunction_v< std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >... >>>
Constructs a CTRE SwerveDrivetrain using the specified constants.
This constructs the underlying hardware devices, so users should not construct the devices themselves. If they need the devices, they can access them through getters in the classes.
- Parameters
-
drivetrainConstants | Drivetrain-wide constants for the swerve drive |
odometryUpdateFrequency | The frequency to run the odometry loop. If unspecified or set to 0 Hz, this is 250 Hz on CAN FD, and 100 Hz on CAN 2.0. |
modules | Constants for each specific module |
template<typename DriveMotorT , typename SteerMotorT , typename EncoderT , typename = std::enable_if_t<std::is_base_of_v<hardware::traits::CommonTalon, DriveMotorT>>, typename = std::enable_if_t<std::is_base_of_v<hardware::traits::CommonTalon, SteerMotorT>>, typename = std::enable_if_t<std::is_base_of_v<hardware::ParentDevice, EncoderT>>>
template<typename... ModuleConstants, typename = std::enable_if_t<std::conjunction_v< std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >... >>>
ctre::phoenix6::swerve::SwerveDrivetrain< DriveMotorT, SteerMotorT, EncoderT, typename, typename, typename >::SwerveDrivetrain |
( |
SwerveDrivetrainConstants const & | drivetrainConstants, |
|
|
units::hertz_t | odometryUpdateFrequency, |
|
|
std::array< double, 3 > const & | odometryStandardDeviation, |
|
|
std::array< double, 3 > const & | visionStandardDeviation, |
|
|
ModuleConstants const &... | modules ) |
|
inline |
Constructs a CTRE SwerveDrivetrain using the specified constants.
This constructs the underlying hardware devices, so users should not construct the devices themselves. If they need the devices, they can access them through getters in the classes.
- Parameters
-
drivetrainConstants | Drivetrain-wide constants for the swerve drive |
odometryUpdateFrequency | The frequency to run the odometry loop. If unspecified or set to 0 Hz, this is 250 Hz on CAN FD, and 100 Hz on CAN 2.0. |
odometryStandardDeviation | The standard deviation for odometry calculation in the form [x, y, theta]ᵀ, with units in meters and radians |
visionStandardDeviation | The standard deviation for vision calculation in the form [x, y, theta]ᵀ, with units in meters and radians |
modules | Constants for each specific module |
template<typename DriveMotorT , typename SteerMotorT , typename EncoderT , typename = std::enable_if_t<std::is_base_of_v<hardware::traits::CommonTalon, DriveMotorT>>, typename = std::enable_if_t<std::is_base_of_v<hardware::traits::CommonTalon, SteerMotorT>>, typename = std::enable_if_t<std::is_base_of_v<hardware::ParentDevice, EncoderT>>>
virtual void ctre::phoenix6::swerve::SwerveDrivetrain< DriveMotorT, SteerMotorT, EncoderT, typename, typename, typename >::AddVisionMeasurement |
( |
Pose2d | visionRobotPose, |
|
|
units::second_t | timestamp, |
|
|
std::array< double, 3 > | visionMeasurementStdDevs ) |
|
inlinevirtual |
Adds a vision measurement to the Kalman Filter.
This will correct the odometry pose estimate while still accounting for measurement noise.
This method can be called as infrequently as you want, as long as you are calling impl::SwerveDrivePoseEstimator::Update every loop.
To promote stability of the pose estimate and make it robust to bad vision data, we recommend only adding vision measurements that are already within one meter or so of the current pose estimate.
Note that the vision measurement standard deviations passed into this method will continue to apply to future measurements until a subsequent call to SetVisionMeasurementStdDevs or this method.
- Parameters
-
visionRobotPose | The pose of the robot as measured by the vision camera. |
timestamp | The timestamp of the vision measurement in seconds. Note that you must use a timestamp with an epoch since system startup (i.e., the epoch of this timestamp is the same epoch as utils::GetCurrentTime). This means that you should use utils::GetCurrentTime as your time source in this case. An FPGA timestamp can be converted to the correct timebase using utils::FPGAToCurrentTime. |
visionMeasurementStdDevs | Standard deviations of the vision pose measurement (x position in meters, y position in meters, and heading in radians). Increase these numbers to trust the vision pose measurement less. |
template<typename DriveMotorT , typename SteerMotorT , typename EncoderT , typename = std::enable_if_t<std::is_base_of_v<hardware::traits::CommonTalon, DriveMotorT>>, typename = std::enable_if_t<std::is_base_of_v<hardware::traits::CommonTalon, SteerMotorT>>, typename = std::enable_if_t<std::is_base_of_v<hardware::ParentDevice, EncoderT>>>
template<typename Request , typename = std::enable_if_t<std::is_base_of_v<requests::SwerveRequest, Request>>, typename = std::enable_if_t<!std::is_const_v<Request>>>
Applies the specified control request to this swerve drivetrain.
This captures the swerve request by reference, so it must live for at least as long as the drivetrain. This can be done by storing the request as a member variable of your drivetrain subsystem or robot.
- Parameters
-