WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
DifferentialDriveOdometry.hpp
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
12#include "wpi/units/length.hpp"
14
15namespace wpi::math {
16/**
17 * Class for differential drive odometry. Odometry allows you to track the
18 * robot's position on the field over the course of a match using readings from
19 * 2 encoders and a gyroscope.
20 *
21 * Teams can use odometry during the autonomous period for complex tasks like
22 * path following. Furthermore, odometry can be used for latency compensation
23 * when using computer-vision systems.
24 *
25 * It is important that you reset your encoders to zero before using this class.
26 * Any subsequent pose resets also require the encoders to be reset to zero.
27 */
29 : public Odometry<DifferentialDriveWheelPositions,
30 DifferentialDriveWheelVelocities,
31 DifferentialDriveWheelAccelerations> {
32 public:
33 /**
34 * Constructs a DifferentialDriveOdometry object.
35 *
36 * IF leftDistance and rightDistance are unspecified,
37 * You NEED to reset your encoders (to zero).
38 *
39 * @param gyroAngle The angle reported by the gyroscope.
40 * @param leftDistance The distance traveled by the left encoder.
41 * @param rightDistance The distance traveled by the right encoder.
42 * @param initialPose The starting position of the robot on the field.
43 */
44 explicit DifferentialDriveOdometry(const Rotation2d& gyroAngle,
45 wpi::units::meter_t leftDistance,
46 wpi::units::meter_t rightDistance,
47 const Pose2d& initialPose = Pose2d{});
48
49 /**
50 * Resets the robot's position on the field.
51 *
52 * IF leftDistance and rightDistance are unspecified,
53 * You NEED to reset your encoders (to zero).
54 *
55 * The gyroscope angle does not need to be reset here on the user's robot
56 * code. The library automatically takes care of offsetting the gyro angle.
57 *
58 * @param pose The position on the field that your robot is at.
59 * @param gyroAngle The angle reported by the gyroscope.
60 * @param leftDistance The distance traveled by the left encoder.
61 * @param rightDistance The distance traveled by the right encoder.
62 */
63 void ResetPosition(const Rotation2d& gyroAngle,
64 wpi::units::meter_t leftDistance,
65 wpi::units::meter_t rightDistance, const Pose2d& pose) {
66 Odometry::ResetPosition(gyroAngle, {leftDistance, rightDistance}, pose);
67 }
68
69 /**
70 * Updates the robot position on the field using distance measurements from
71 * encoders. This method is more numerically accurate than using velocities to
72 * integrate the pose and is also advantageous for teams that are using lower
73 * CPR encoders.
74 *
75 * @param gyroAngle The angle reported by the gyroscope.
76 * @param leftDistance The distance traveled by the left encoder.
77 * @param rightDistance The distance traveled by the right encoder.
78 * @return The new pose of the robot.
79 */
80 const Pose2d& Update(const Rotation2d& gyroAngle,
81 wpi::units::meter_t leftDistance,
82 wpi::units::meter_t rightDistance) {
83 return Odometry::Update(gyroAngle, {leftDistance, rightDistance});
84 }
85
86 private:
87 DifferentialDriveKinematics m_kinematicsImpl{wpi::units::meter_t{1}};
88};
89} // namespace wpi::math
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition DifferentialDriveKinematics.hpp:33
DifferentialDriveOdometry(const Rotation2d &gyroAngle, wpi::units::meter_t leftDistance, wpi::units::meter_t rightDistance, const Pose2d &initialPose=Pose2d{})
Constructs a DifferentialDriveOdometry object.
const Pose2d & Update(const Rotation2d &gyroAngle, wpi::units::meter_t leftDistance, wpi::units::meter_t rightDistance)
Updates the robot position on the field using distance measurements from encoders.
Definition DifferentialDriveOdometry.hpp:80
void ResetPosition(const Rotation2d &gyroAngle, wpi::units::meter_t leftDistance, wpi::units::meter_t rightDistance, const Pose2d &pose)
Resets the robot's position on the field.
Definition DifferentialDriveOdometry.hpp:63
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 t...
Definition Odometry.hpp:120
void ResetPosition(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions, const Pose2d &pose)
Resets the robot's position on the field.
Definition Odometry.hpp:63
Odometry(const Kinematics< DifferentialDriveWheelPositions, DifferentialDriveWheelVelocities, DifferentialDriveWheelAccelerations > &kinematics, const Rotation2d &gyroAngle, const DifferentialDriveWheelPositions &wheelPositions, const Pose2d &initialPose=Pose2d{})
Definition Odometry.hpp:41
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
Definition LinearSystem.hpp:20