WPILibC++ 2023.4.3-108-ge5452e3
|
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 Pose2d & | GetPose () const |
Returns the position of the robot on the field. More... | |
const Pose2d & | 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. More... | |
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.
|
explicit |
Constructs an Odometry object.
kinematics | The kinematics for your drivetrain. |
gyroAngle | The angle reported by the gyroscope. |
wheelPositions | The current distances measured by each wheel. |
initialPose | The starting position of the robot on the field. |
|
inline |
Returns the position of the robot on the field.
|
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.
gyroAngle | The angle reported by the gyroscope. |
wheelPositions | The current distances measured by each wheel. |
pose | The position on the field that your robot is at. |
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.
gyroAngle | The angle reported by the gyroscope. |
wheelPositions | The current distances measured by each wheel. |