CTRE Phoenix 6 C++ 25.2.1
|
Plain-Old-Data class holding the state of the swerve drivetrain. More...
#include <ctre/phoenix6/swerve/impl/SwerveDrivetrainImpl.hpp>
Public Attributes | |
Pose2d | Pose |
The current pose of the robot. | |
ChassisSpeeds | Speeds |
The current velocity of the robot. | |
std::vector< SwerveModuleState > | ModuleStates |
The current module states. | |
std::vector< SwerveModuleState > | ModuleTargets |
The target module states. | |
std::vector< SwerveModulePosition > | ModulePositions |
The current module positions. | |
Rotation2d | RawHeading |
The raw heading of the robot, unaffected by vision updates and odometry resets. | |
units::second_t | Timestamp |
The timestamp of the state capture, in the timebase of utils::GetCurrentTime() | |
units::second_t | OdometryPeriod |
The measured odometry update period. | |
int32_t | SuccessfulDaqs |
Number of successful data acquisitions. | |
int32_t | FailedDaqs |
Number of failed data acquisitions. | |
Plain-Old-Data class holding the state of the swerve drivetrain.
This encapsulates most data that is relevant for telemetry or decision-making from the Swerve Drive.
int32_t ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDriveState::FailedDaqs |
Number of failed data acquisitions.
std::vector<SwerveModulePosition> ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDriveState::ModulePositions |
The current module positions.
std::vector<SwerveModuleState> ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDriveState::ModuleStates |
The current module states.
std::vector<SwerveModuleState> ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDriveState::ModuleTargets |
The target module states.
units::second_t ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDriveState::OdometryPeriod |
The measured odometry update period.
Pose2d ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDriveState::Pose |
The current pose of the robot.
Rotation2d ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDriveState::RawHeading |
The raw heading of the robot, unaffected by vision updates and odometry resets.
ChassisSpeeds ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDriveState::Speeds |
The current velocity of the robot.
int32_t ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDriveState::SuccessfulDaqs |
Number of successful data acquisitions.
units::second_t ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDriveState::Timestamp |
The timestamp of the state capture, in the timebase of utils::GetCurrentTime()