WPILibC++ 2024.3.2
frc::Odometry< WheelSpeeds, WheelPositions > Class Template Reference

Class for odometry. More...

#include <frc/kinematics/Odometry.h>

Public Member Functions

 Odometry (const Kinematics< WheelSpeeds, WheelPositions > &kinematics, const Rotation2d &gyroAngle, const WheelPositions &wheelPositions, const Pose2d &initialPose=Pose2d{})
 Constructs an Odometry object. More...
 
void ResetPosition (const Rotation2d &gyroAngle, const WheelPositions &wheelPositions, const Pose2d &pose)
 Resets the robot's position on the field. More...
 
const Pose2dGetPose () const
 Returns the position of the robot on the field. More...
 
const Pose2dUpdate (const Rotation2d &gyroAngle, const WheelPositions &wheelPositions)
 Updates the robot's position on the field using forward kinematics and integration of the pose over time. More...
 

Detailed Description

template<typename WheelSpeeds, WheelPositions WheelPositions>
class frc::Odometry< WheelSpeeds, WheelPositions >

Class for odometry.

Robot code should not use this directly- Instead, use the particular type for your drivetrain (e.g., DifferentialDriveOdometry). Odometry allows you to track the robot's position on the field over a course of a match using readings from your wheel 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.

Template Parameters
WheelSpeedsWheel speeds type.
WheelPositionsWheel positions type.

Constructor & Destructor Documentation

◆ Odometry()

template<typename WheelSpeeds , WheelPositions WheelPositions>
frc::Odometry< WheelSpeeds, WheelPositions >::Odometry ( const Kinematics< WheelSpeeds, WheelPositions > &  kinematics,
const Rotation2d gyroAngle,
const WheelPositions &  wheelPositions,
const Pose2d initialPose = Pose2d{} 
)
explicit

Constructs an Odometry object.

Parameters
kinematicsThe kinematics for your drivetrain.
gyroAngleThe angle reported by the gyroscope.
wheelPositionsThe current distances measured by each wheel.
initialPoseThe starting position of the robot on the field.

Member Function Documentation

◆ GetPose()

template<typename WheelSpeeds , WheelPositions WheelPositions>
const Pose2d & frc::Odometry< WheelSpeeds, WheelPositions >::GetPose ( ) const
inline

Returns the position of the robot on the field.

Returns
The pose of the robot.

◆ ResetPosition()

template<typename WheelSpeeds , WheelPositions WheelPositions>
void frc::Odometry< WheelSpeeds, WheelPositions >::ResetPosition ( const Rotation2d gyroAngle,
const WheelPositions &  wheelPositions,
const Pose2d 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()

template<typename WheelSpeeds , WheelPositions WheelPositions>
const Pose2d & frc::Odometry< WheelSpeeds, WheelPositions >::Update ( const Rotation2d gyroAngle,
const 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 files: