WPILibC++ 2023.4.3-108-ge5452e3
Odometry.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
12
13namespace frc {
14/**
15 * Class for odometry. Robot code should not use this directly- Instead, use the
16 * particular type for your drivetrain (e.g., DifferentialDriveOdometry).
17 * Odometry allows you to track the robot's position on the field over a course
18 * of a match using readings from your wheel encoders.
19 *
20 * Teams can use odometry during the autonomous period for complex tasks like
21 * path following. Furthermore, odometry can be used for latency compensation
22 * when using computer-vision systems.
23 */
24template <typename WheelSpeeds, WheelPositions WheelPositions>
26 public:
27 /**
28 * Constructs an Odometry object.
29 *
30 * @param kinematics The kinematics for your drivetrain.
31 * @param gyroAngle The angle reported by the gyroscope.
32 * @param wheelPositions The current distances measured by each wheel.
33 * @param initialPose The starting position of the robot on the field.
34 */
35 explicit Odometry(const Kinematics<WheelSpeeds, WheelPositions>& kinematics,
36 const Rotation2d& gyroAngle,
37 const WheelPositions& wheelPositions,
38 const Pose2d& initialPose = Pose2d{});
39
40 /**
41 * Resets the robot's position on the field.
42 *
43 * The gyroscope angle does not need to be reset here on the user's robot
44 * code. The library automatically takes care of offsetting the gyro angle.
45 *
46 * @param gyroAngle The angle reported by the gyroscope.
47 * @param wheelPositions The current distances measured by each wheel.
48 * @param pose The position on the field that your robot is at.
49 */
50 void ResetPosition(const Rotation2d& gyroAngle,
51 const WheelPositions& wheelPositions, const Pose2d& pose) {
52 m_pose = pose;
53 m_previousAngle = pose.Rotation();
54 m_gyroOffset = m_pose.Rotation() - gyroAngle;
55 m_previousWheelPositions = wheelPositions;
56 }
57
58 /**
59 * Returns the position of the robot on the field.
60 * @return The pose of the robot.
61 */
62 const Pose2d& GetPose() const { return m_pose; }
63
64 /**
65 * Updates the robot's position on the field using forward kinematics and
66 * integration of the pose over time. This method takes in an angle parameter
67 * which is used instead of the angular rate that is calculated from forward
68 * kinematics, in addition to the current distance measurement at each wheel.
69 *
70 * @param gyroAngle The angle reported by the gyroscope.
71 * @param wheelPositions The current distances measured by each wheel.
72 *
73 * @return The new pose of the robot.
74 */
75 const Pose2d& Update(const Rotation2d& gyroAngle,
76 const WheelPositions& wheelPositions);
77
78 private:
80 Pose2d m_pose;
81
82 WheelPositions m_previousWheelPositions;
83 Rotation2d m_previousAngle;
84 Rotation2d m_gyroOffset;
85};
86} // namespace frc
87
88#include "Odometry.inc"
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition: Kinematics.h:23
Class for odometry.
Definition: Odometry.h:25
void ResetPosition(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions, const Pose2d &pose)
Resets the robot's position on the field.
Definition: Odometry.h:50
const Pose2d & GetPose() const
Returns the position of the robot on the field.
Definition: Odometry.h:62
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: WheelPositions.h:11
Definition: AprilTagPoseEstimator.h:15