WPILibC++ 2024.3.2
|
Class for swerve drive odometry. More...
#include <frc/kinematics/SwerveDriveOdometry.h>
Public Member Functions | |
SwerveDriveOdometry (SwerveDriveKinematics< NumModules > kinematics, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose=Pose2d{}) | |
Constructs a SwerveDriveOdometry object. More... | |
void | ResetPosition (const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &pose) |
Resets the robot's position on the field. More... | |
const Pose2d & | Update (const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions) |
Updates the robot's position on the field using forward kinematics and integration of the pose over time. More... | |
Public Member Functions inherited from frc::Odometry< SwerveDriveWheelSpeeds< NumModules >, SwerveDriveWheelPositions< NumModules > > | |
Odometry (const Kinematics< SwerveDriveWheelSpeeds< NumModules >, 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 swerve drive odometry.
Odometry allows you to track the robot's position on the field over a course of a match using readings from your swerve drive encoders and swerve azimuth 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.
frc::SwerveDriveOdometry< NumModules >::SwerveDriveOdometry | ( | SwerveDriveKinematics< NumModules > | kinematics, |
const Rotation2d & | gyroAngle, | ||
const wpi::array< SwerveModulePosition, NumModules > & | modulePositions, | ||
const Pose2d & | initialPose = Pose2d{} |
||
) |
Constructs a SwerveDriveOdometry object.
kinematics | The swerve drive kinematics for your drivetrain. |
gyroAngle | The angle reported by the gyroscope. |
modulePositions | The wheel positions reported by each module. |
initialPose | The starting 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. |
modulePositions | The wheel positions reported by each module. |
pose | The position on the field that your robot is at. |
|
inline |
Updates the robot's position on the field using forward kinematics and integration of the pose over time.
This also takes in an angle parameter which is used instead of the angular rate that is calculated from forward kinematics.
gyroAngle | The angle reported by the gyroscope. |
modulePositions | The current position of all swerve modules. Please provide the positions in the same order in which you instantiated your SwerveDriveKinematics. |