WPILibC++ 2023.4.3-108-ge5452e3
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
14#include "units/length.h"
15
16namespace frc {
17/**
18 * Class for differential drive odometry. Odometry allows you to track the
19 * robot's position on the field over the course of a match using readings from
20 * 2 encoders and a gyroscope.
21 *
22 * Teams can use odometry during the autonomous period for complex tasks like
23 * path following. Furthermore, odometry can be used for latency compensation
24 * when using computer-vision systems.
25 *
26 * It is important that you reset your encoders to zero before using this class.
27 * Any subsequent pose resets also require the encoders to be reset to zero.
28 */
30 : public Odometry<DifferentialDriveWheelSpeeds,
31 DifferentialDriveWheelPositions> {
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 units::meter_t leftDistance,
46 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, units::meter_t leftDistance,
64 units::meter_t rightDistance, const Pose2d& pose) {
66 DifferentialDriveWheelPositions>::ResetPosition(gyroAngle,
67 {leftDistance,
68 rightDistance},
69 pose);
70 }
71
72 /**
73 * Updates the robot position on the field using distance measurements from
74 * encoders. This method is more numerically accurate than using velocities to
75 * integrate the pose and is also advantageous for teams that are using lower
76 * CPR encoders.
77 *
78 * @param gyroAngle The angle reported by the gyroscope.
79 * @param leftDistance The distance traveled by the left encoder.
80 * @param rightDistance The distance traveled by the right encoder.
81 * @return The new pose of the robot.
82 */
83 const Pose2d& Update(const Rotation2d& gyroAngle, units::meter_t leftDistance,
84 units::meter_t rightDistance) {
86 DifferentialDriveWheelPositions>::Update(gyroAngle,
87 {leftDistance,
88 rightDistance});
89 }
90
91 private:
92 DifferentialDriveKinematics m_kinematicsImpl{units::meter_t{1}};
93};
94} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition: DifferentialDriveKinematics.h:29
Class for differential drive odometry.
Definition: DifferentialDriveOdometry.h:31
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.
Definition: DifferentialDriveOdometry.h:83
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:63
Class for odometry.
Definition: Odometry.h:25
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:25
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:26
Definition: AprilTagPoseEstimator.h:15
Represents the wheel positions for a differential drive drivetrain.
Definition: DifferentialDriveWheelPositions.h:16
Represents the wheel speeds for a differential drive drivetrain.
Definition: DifferentialDriveWheelSpeeds.h:15