CTRE Phoenix 6 C++ 24.50.0-alpha-2
ctre::phoenix6::swerve::impl::SwerveDriveOdometry Class Reference

Class for swerve drive odometry. More...

#include <ctre/phoenix6/swerve/impl/SwerveDrivePoseEstimator.hpp>

Public Types

using WheelSpeeds = std::vector< SwerveModuleState >
 
using WheelPositions = std::vector< SwerveModulePosition >
 

Public Member Functions

 SwerveDriveOdometry (SwerveDriveKinematics const &kinematics, Rotation2d const &gyroAngle, WheelPositions modulePositions, Pose2d initialPose=Pose2d{})
 Constructs a SwerveDriveOdometry object. More...
 
void ResetPosition (Rotation2d const &gyroAngle, WheelPositions wheelPositions, Pose2d const &pose)
 Resets the robot's position on the field. More...
 
Pose2d const & Pose () const
 Returns the position of the robot on the field. More...
 
Pose2d const & Update (Rotation2d const &gyroAngle, WheelPositions wheelPositions)
 Updates the robot's position on the field using forward kinematics and integration of the pose over time. More...
 

Detailed Description

Class for swerve drive odometry.

Odometry allows you to track the robot's position on the field over a course of a match using readings from your swerve drive encoders and swerve azimuth encoders.

Teams can use odometry during the autonomous period for complex tasks like path following. Furthermore, odometry can be used for latency compensation when using computer-vision systems.

Member Typedef Documentation

◆ WheelPositions

◆ WheelSpeeds

Constructor & Destructor Documentation

◆ SwerveDriveOdometry()

ctre::phoenix6::swerve::impl::SwerveDriveOdometry::SwerveDriveOdometry ( SwerveDriveKinematics const &  kinematics,
Rotation2d const &  gyroAngle,
WheelPositions  modulePositions,
Pose2d  initialPose = Pose2d{} 
)
inline

Constructs a SwerveDriveOdometry object.

Parameters
kinematicsThe swerve drive kinematics for your drivetrain.
gyroAngleThe angle reported by the gyroscope.
modulePositionsThe wheel positions reported by each module.
initialPoseThe starting position of the robot on the field.

Member Function Documentation

◆ Pose()

Pose2d const & ctre::phoenix6::swerve::impl::SwerveDriveOdometry::Pose ( ) const
inline

Returns the position of the robot on the field.

Returns
The pose of the robot.

◆ ResetPosition()

void ctre::phoenix6::swerve::impl::SwerveDriveOdometry::ResetPosition ( Rotation2d const &  gyroAngle,
WheelPositions  wheelPositions,
Pose2d const &  pose 
)
inline

Resets the robot's position on the field.

The gyroscope angle does not need to be reset here on the user's robot code. The library automatically takes care of offsetting the gyro angle.

Parameters
gyroAngleThe angle reported by the gyroscope.
wheelPositionsThe current distances measured by each wheel.
poseThe position on the field that your robot is at.

◆ Update()

Pose2d const & ctre::phoenix6::swerve::impl::SwerveDriveOdometry::Update ( Rotation2d const &  gyroAngle,
WheelPositions  wheelPositions 
)

Updates the robot's position on the field using forward kinematics and integration of the pose over time.

This method takes in an angle parameter which is used instead of the angular rate that is calculated from forward kinematics, in addition to the current distance measurement at each wheel.

Parameters
gyroAngleThe angle reported by the gyroscope.
wheelPositionsThe current distances measured by each wheel.
Returns
The new pose of the robot.

The documentation for this class was generated from the following file: