WPILibC++ 2025.1.1
Loading...
Searching...
No Matches
frc::MecanumDriveOdometry3d Class Reference

Class for mecanum drive odometry. More...

#include <frc/kinematics/MecanumDriveOdometry3d.h>

Inheritance diagram for frc::MecanumDriveOdometry3d:
frc::Odometry3d< MecanumDriveWheelSpeeds, MecanumDriveWheelPositions >

Public Member Functions

 MecanumDriveOdometry3d (MecanumDriveKinematics kinematics, const Rotation3d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose3d &initialPose=Pose3d{})
 Constructs a MecanumDriveOdometry3d object.
 
- Public Member Functions inherited from frc::Odometry3d< MecanumDriveWheelSpeeds, MecanumDriveWheelPositions >
 Odometry3d (const Kinematics< MecanumDriveWheelSpeeds, MecanumDriveWheelPositions > &kinematics, const Rotation3d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose3d &initialPose=Pose3d{})
 Constructs an Odometry3d object.
 
void ResetPosition (const Rotation3d &gyroAngle, const MecanumDriveWheelPositions &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 MecanumDriveWheelPositions &wheelPositions)
 Updates the robot's position on the field using forward kinematics and integration of the pose over time.
 

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

◆ MecanumDriveOdometry3d()

frc::MecanumDriveOdometry3d::MecanumDriveOdometry3d ( MecanumDriveKinematics kinematics,
const Rotation3d & gyroAngle,
const MecanumDriveWheelPositions & wheelPositions,
const Pose3d & initialPose = Pose3d{} )
explicit

Constructs a MecanumDriveOdometry3d object.

Parameters
kinematicsThe mecanum drive 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.

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