WPILibC++ 2025.1.1
Loading...
Searching...
No Matches
frc::Odometry3d< WheelSpeeds, WheelPositions > Class Template Reference

Class for odometry. More...

#include <frc/kinematics/Odometry3d.h>

Public Member Functions

 Odometry3d (const Kinematics< WheelSpeeds, WheelPositions > &kinematics, const Rotation3d &gyroAngle, const WheelPositions &wheelPositions, const Pose3d &initialPose=Pose3d{})
 Constructs an Odometry3d object.
 
void ResetPosition (const Rotation3d &gyroAngle, const WheelPositions &wheelPositions, const Pose3d &pose)
 Resets the robot's position on the field.
 
void ResetPose (const Pose3d &pose)
 Resets the pose.
 
void ResetTranslation (const Translation3d &translation)
 Resets the translation of the pose.
 
void ResetRotation (const Rotation3d &rotation)
 Resets the rotation of the pose.
 
const Pose3dGetPose () const
 Returns the position of the robot on the field.
 
const Pose3dUpdate (const Rotation3d &gyroAngle, const WheelPositions &wheelPositions)
 Updates the robot's position on the field using forward kinematics and integration of the pose over time.
 

Detailed Description

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

Class for odometry.

Robot code should not use this directly- Instead, use the particular type for your drivetrain (e.g., DifferentialDriveOdometry3d). 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

◆ Odometry3d()

template<typename WheelSpeeds , typename WheelPositions >
frc::Odometry3d< WheelSpeeds, WheelPositions >::Odometry3d ( const Kinematics< WheelSpeeds, WheelPositions > & kinematics,
const Rotation3d & gyroAngle,
const WheelPositions & wheelPositions,
const Pose3d & initialPose = Pose3d{} )
inlineexplicit

Constructs an Odometry3d 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 , typename WheelPositions >
const Pose3d & frc::Odometry3d< WheelSpeeds, WheelPositions >::GetPose ( ) const
inline

Returns the position of the robot on the field.

Returns
The pose of the robot.

◆ ResetPose()

template<typename WheelSpeeds , typename WheelPositions >
void frc::Odometry3d< WheelSpeeds, WheelPositions >::ResetPose ( const Pose3d & pose)
inline

Resets the pose.

Parameters
poseThe pose to reset to.

◆ ResetPosition()

template<typename WheelSpeeds , typename WheelPositions >
void frc::Odometry3d< WheelSpeeds, WheelPositions >::ResetPosition ( const Rotation3d & gyroAngle,
const WheelPositions & wheelPositions,
const Pose3d & 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.

◆ ResetRotation()

template<typename WheelSpeeds , typename WheelPositions >
void frc::Odometry3d< WheelSpeeds, WheelPositions >::ResetRotation ( const Rotation3d & rotation)
inline

Resets the rotation of the pose.

Parameters
rotationThe rotation to reset to.

◆ ResetTranslation()

template<typename WheelSpeeds , typename WheelPositions >
void frc::Odometry3d< WheelSpeeds, WheelPositions >::ResetTranslation ( const Translation3d & translation)
inline

Resets the translation of the pose.

Parameters
translationThe translation to reset to.

◆ Update()

template<typename WheelSpeeds , typename WheelPositions >
const Pose3d & frc::Odometry3d< WheelSpeeds, WheelPositions >::Update ( const Rotation3d & gyroAngle,
const WheelPositions & wheelPositions )
inline

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: