WPILibC++ 2023.4.3
MecanumDriveOdometry.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#include <wpi/timestamp.h>
9
10#include "frc/geometry/Pose2d.h"
13#include "units/time.h"
14
15namespace frc {
16
17/**
18 * Class for mecanum drive odometry. Odometry allows you to track the robot's
19 * position on the field over a course of a match using readings from your
20 * mecanum wheel encoders.
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 */
27 public:
28 /**
29 * Constructs a MecanumDriveOdometry object.
30 *
31 * @param kinematics The mecanum drive kinematics for your drivetrain.
32 * @param gyroAngle The angle reported by the gyroscope.
33 * @param wheelPositions The current distances measured by each wheel.
34 * @param initialPose The starting position of the robot on the field.
35 */
37 MecanumDriveKinematics kinematics, const Rotation2d& gyroAngle,
38 const MecanumDriveWheelPositions& wheelPositions,
39 const Pose2d& initialPose = Pose2d{});
40
41 /**
42 * Resets the robot's position on the field.
43 *
44 * The gyroscope angle does not need to be reset here on the user's robot
45 * code. The library automatically takes care of offsetting the gyro angle.
46 *
47 * @param gyroAngle The angle reported by the gyroscope.
48 * @param wheelPositions The current distances measured by each wheel.
49 * @param pose The position on the field that your robot is at.
50 */
51 void ResetPosition(const Rotation2d& gyroAngle,
52 const MecanumDriveWheelPositions& wheelPositions,
53 const Pose2d& pose) {
54 m_pose = pose;
55 m_previousAngle = pose.Rotation();
56 m_gyroOffset = m_pose.Rotation() - gyroAngle;
57 m_previousWheelPositions = wheelPositions;
58 }
59
60 /**
61 * Returns the position of the robot on the field.
62 * @return The pose of the robot.
63 */
64 const Pose2d& GetPose() const { return m_pose; }
65
66 /**
67 * Updates the robot's position on the field using forward kinematics and
68 * integration of the pose over time. This method takes in an angle parameter
69 * which is used instead of the angular rate that is calculated from forward
70 * kinematics, in addition to the current distance measurement at each wheel.
71 *
72 * @param gyroAngle The angle reported by the gyroscope.
73 * @param wheelPositions The current distances measured by each wheel.
74 *
75 * @return The new pose of the robot.
76 */
77 const Pose2d& Update(const Rotation2d& gyroAngle,
78 const MecanumDriveWheelPositions& wheelPositions);
79
80 private:
81 MecanumDriveKinematics m_kinematics;
82 Pose2d m_pose;
83
84 MecanumDriveWheelPositions m_previousWheelPositions;
85 Rotation2d m_previousAngle;
86 Rotation2d m_gyroOffset;
87};
88
89} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition: MecanumDriveKinematics.h:42
Class for mecanum drive odometry.
Definition: MecanumDriveOdometry.h:26
const Pose2d & GetPose() const
Returns the position of the robot on the field.
Definition: MecanumDriveOdometry.h:64
MecanumDriveOdometry(MecanumDriveKinematics kinematics, const Rotation2d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose2d &initialPose=Pose2d{})
Constructs a MecanumDriveOdometry object.
const Pose2d & Update(const Rotation2d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions)
Updates the robot's position on the field using forward kinematics and integration of the pose over t...
void ResetPosition(const Rotation2d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose2d &pose)
Resets the robot's position on the field.
Definition: MecanumDriveOdometry.h:51
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
Represents the wheel speeds for a mecanum drive drivetrain.
Definition: MecanumDriveWheelPositions.h:15