WPILibC++ 2023.4.3-108-ge5452e3
frc::DifferentialDriveOdometry Class Reference

Class for differential drive odometry. More...

#include <frc/kinematics/DifferentialDriveOdometry.h>

Inheritance diagram for frc::DifferentialDriveOdometry:
frc::Odometry< DifferentialDriveWheelSpeeds, DifferentialDriveWheelPositions >

Public Member Functions

 DifferentialDriveOdometry (const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose2d &initialPose=Pose2d{})
 Constructs a DifferentialDriveOdometry object. More...
 
void ResetPosition (const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose2d &pose)
 Resets the robot's position on the field. More...
 
const Pose2dUpdate (const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance)
 Updates the robot position on the field using distance measurements from encoders. More...
 
- Public Member Functions inherited from frc::Odometry< DifferentialDriveWheelSpeeds, DifferentialDriveWheelPositions >
 Odometry (const Kinematics< DifferentialDriveWheelSpeeds, 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

Class for differential drive odometry.

Odometry allows you to track the robot's position on the field over the course of a match using readings from 2 encoders and a gyroscope.

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.

It is important that you reset your encoders to zero before using this class. Any subsequent pose resets also require the encoders to be reset to zero.

Constructor & Destructor Documentation

◆ DifferentialDriveOdometry()

frc::DifferentialDriveOdometry::DifferentialDriveOdometry ( const Rotation2d gyroAngle,
units::meter_t  leftDistance,
units::meter_t  rightDistance,
const Pose2d initialPose = Pose2d{} 
)
explicit

Constructs a DifferentialDriveOdometry object.

IF leftDistance and rightDistance are unspecified, You NEED to reset your encoders (to zero).

Parameters
gyroAngleThe angle reported by the gyroscope.
leftDistanceThe distance traveled by the left encoder.
rightDistanceThe distance traveled by the right encoder.
initialPoseThe starting position of the robot on the field.

Member Function Documentation

◆ ResetPosition()

void frc::DifferentialDriveOdometry::ResetPosition ( const Rotation2d gyroAngle,
units::meter_t  leftDistance,
units::meter_t  rightDistance,
const Pose2d pose 
)
inline

Resets the robot's position on the field.

IF leftDistance and rightDistance are unspecified, You NEED to reset your encoders (to zero).

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
poseThe position on the field that your robot is at.
gyroAngleThe angle reported by the gyroscope.
leftDistanceThe distance traveled by the left encoder.
rightDistanceThe distance traveled by the right encoder.

◆ Update()

const Pose2d & frc::DifferentialDriveOdometry::Update ( const Rotation2d gyroAngle,
units::meter_t  leftDistance,
units::meter_t  rightDistance 
)
inline

Updates the robot position on the field using distance measurements from encoders.

This method is more numerically accurate than using velocities to integrate the pose and is also advantageous for teams that are using lower CPR encoders.

Parameters
gyroAngleThe angle reported by the gyroscope.
leftDistanceThe distance traveled by the left encoder.
rightDistanceThe distance traveled by the right encoder.
Returns
The new pose of the robot.

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