WPILibC++  2020.3.2-60-g3011ebe
frc::MecanumDriveOdometry Class Reference

Class for mecanum drive odometry. More...

#include <MecanumDriveOdometry.h>

Public Member Functions

 MecanumDriveOdometry (MecanumDriveKinematics kinematics, const Rotation2d &gyroAngle, const Pose2d &initialPose=Pose2d())
 Constructs a MecanumDriveOdometry object. More...
 
void ResetPosition (const Pose2d &pose, const Rotation2d &gyroAngle)
 Resets the robot's position on the field. More...
 
const Pose2dGetPose () const
 Returns the position of the robot on the field. More...
 
const Pose2dUpdateWithTime (units::second_t currentTime, const Rotation2d &gyroAngle, MecanumDriveWheelSpeeds wheelSpeeds)
 Updates the robot's position on the field using forward kinematics and integration of the pose over time. More...
 
const Pose2dUpdate (const Rotation2d &gyroAngle, MecanumDriveWheelSpeeds wheelSpeeds)
 Updates the robot's position on the field using forward kinematics and integration of the pose over time. More...
 

Detailed Description

Class for mecanum drive odometry.

Odometry allows you to track the robot's position on the field over a course of a match using readings from your mecanum 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.

Constructor & Destructor Documentation

◆ MecanumDriveOdometry()

frc::MecanumDriveOdometry::MecanumDriveOdometry ( MecanumDriveKinematics  kinematics,
const Rotation2d gyroAngle,
const Pose2d initialPose = Pose2d() 
)
explicit

Constructs a MecanumDriveOdometry object.

Parameters
kinematicsThe mecanum drive kinematics for your drivetrain.
gyroAngleThe angle reported by the gyroscope.
initialPoseThe starting position of the robot on the field.

Member Function Documentation

◆ GetPose()

const Pose2d& frc::MecanumDriveOdometry::GetPose ( ) const
inline

Returns the position of the robot on the field.

Returns
The pose of the robot.

◆ ResetPosition()

void frc::MecanumDriveOdometry::ResetPosition ( const Pose2d pose,
const Rotation2d gyroAngle 
)
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
poseThe position on the field that your robot is at.
gyroAngleThe angle reported by the gyroscope.

◆ Update()

const Pose2d& frc::MecanumDriveOdometry::Update ( const Rotation2d gyroAngle,
MecanumDriveWheelSpeeds  wheelSpeeds 
)
inline

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

This method automatically calculates the current time to calculate period (difference between two timestamps). The period is used to calculate the change in distance from a velocity. This also takes in an angle parameter which is used instead of the angular rate that is calculated from forward kinematics.

Parameters
gyroAngleThe angle reported by the gyroscope.
wheelSpeedsThe current wheel speeds.
Returns
The new pose of the robot.

◆ UpdateWithTime()

const Pose2d& frc::MecanumDriveOdometry::UpdateWithTime ( units::second_t  currentTime,
const Rotation2d gyroAngle,
MecanumDriveWheelSpeeds  wheelSpeeds 
)

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

This method takes in the current time as a parameter to calculate period (difference between two timestamps). The period is used to calculate the change in distance from a velocity. This also takes in an angle parameter which is used instead of the angular rate that is calculated from forward kinematics.

Parameters
currentTimeThe current time.
gyroAngleThe angle reported by the gyroscope.
wheelSpeedsThe current wheel speeds.
Returns
The new pose of the robot.

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