WPILibC++ 2023.4.3
DifferentialDriveOdometry.h
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
7#include <wpi/SymbolExports.h>
8
10#include "units/length.h"
11
12namespace frc {
13/**
14 * Class for differential drive odometry. Odometry allows you to track the
15 * robot's position on the field over the course of a match using readings from
16 * 2 encoders and a gyroscope.
17 *
18 * Teams can use odometry during the autonomous period for complex tasks like
19 * path following. Furthermore, odometry can be used for latency compensation
20 * when using computer-vision systems.
21 *
22 * It is important that you reset your encoders to zero before using this class.
23 * Any subsequent pose resets also require the encoders to be reset to zero.
24 */
26 public:
27 /**
28 * Constructs a DifferentialDriveOdometry object.
29 *
30 * IF leftDistance and rightDistance are unspecified,
31 * You NEED to reset your encoders (to zero).
32 *
33 * @param gyroAngle The angle reported by the gyroscope.
34 * @param leftDistance The distance traveled by the left encoder.
35 * @param rightDistance The distance traveled by the right encoder.
36 * @param initialPose The starting position of the robot on the field.
37 */
38 explicit DifferentialDriveOdometry(const Rotation2d& gyroAngle,
39 units::meter_t leftDistance,
40 units::meter_t rightDistance,
41 const Pose2d& initialPose = Pose2d{});
42
43 /**
44 * Resets the robot's position on the field.
45 *
46 * IF leftDistance and rightDistance are unspecified,
47 * You NEED to reset your encoders (to zero).
48 *
49 * The gyroscope angle does not need to be reset here on the user's robot
50 * code. The library automatically takes care of offsetting the gyro angle.
51 *
52 * @param pose The position on the field that your robot is at.
53 * @param gyroAngle The angle reported by the gyroscope.
54 * @param leftDistance The distance traveled by the left encoder.
55 * @param rightDistance The distance traveled by the right encoder.
56 */
57 void ResetPosition(const Rotation2d& gyroAngle, units::meter_t leftDistance,
58 units::meter_t rightDistance, const Pose2d& pose) {
59 m_pose = pose;
60 m_previousAngle = pose.Rotation();
61 m_gyroOffset = m_pose.Rotation() - gyroAngle;
62
63 m_prevLeftDistance = leftDistance;
64 m_prevRightDistance = rightDistance;
65 }
66
67 /**
68 * Returns the position of the robot on the field.
69 * @return The pose of the robot.
70 */
71 const Pose2d& GetPose() const { return m_pose; }
72
73 /**
74 * Updates the robot position on the field using distance measurements from
75 * encoders. This method is more numerically accurate than using velocities to
76 * integrate the pose and is also advantageous for teams that are using lower
77 * CPR encoders.
78 *
79 * @param gyroAngle The angle reported by the gyroscope.
80 * @param leftDistance The distance traveled by the left encoder.
81 * @param rightDistance The distance traveled by the right encoder.
82 * @return The new pose of the robot.
83 */
84 const Pose2d& Update(const Rotation2d& gyroAngle, units::meter_t leftDistance,
85 units::meter_t rightDistance);
86
87 private:
88 Pose2d m_pose;
89
90 Rotation2d m_gyroOffset;
91 Rotation2d m_previousAngle;
92
93 units::meter_t m_prevLeftDistance = 0_m;
94 units::meter_t m_prevRightDistance = 0_m;
95};
96} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Class for differential drive odometry.
Definition: DifferentialDriveOdometry.h:25
const Pose2d & Update(const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance)
Updates the robot position on the field using distance measurements from encoders.
const Pose2d & GetPose() const
Returns the position of the robot on the field.
Definition: DifferentialDriveOdometry.h:71
DifferentialDriveOdometry(const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose2d &initialPose=Pose2d{})
Constructs a DifferentialDriveOdometry object.
void ResetPosition(const Rotation2d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose2d &pose)
Resets the robot's position on the field.
Definition: DifferentialDriveOdometry.h:57
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:25
constexpr const Rotation2d & Rotation() const
Returns the underlying rotation.
Definition: Pose2d.h:105
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:26
Definition: AprilTagFieldLayout.h:22