WPILibC++ 2023.4.3
SwerveDriveOdometry.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 <chrono>
8#include <cstddef>
9#include <ctime>
10
11#include <wpi/SymbolExports.h>
12#include <wpi/timestamp.h>
13
16#include "frc/geometry/Pose2d.h"
17#include "units/time.h"
18
19namespace frc {
20
21/**
22 * Class for swerve drive odometry. Odometry allows you to track the robot's
23 * position on the field over a course of a match using readings from your
24 * swerve drive encoders and swerve azimuth encoders.
25 *
26 * Teams can use odometry during the autonomous period for complex tasks like
27 * path following. Furthermore, odometry can be used for latency compensation
28 * when using computer-vision systems.
29 */
30template <size_t NumModules>
32 public:
33 /**
34 * Constructs a SwerveDriveOdometry object.
35 *
36 * @param kinematics The swerve drive kinematics for your drivetrain.
37 * @param gyroAngle The angle reported by the gyroscope.
38 * @param modulePositions The wheel positions reported by each module.
39 * @param initialPose The starting position of the robot on the field.
40 */
42 SwerveDriveKinematics<NumModules> kinematics, const Rotation2d& gyroAngle,
44 const Pose2d& initialPose = Pose2d{});
45
46 /**
47 * Resets the robot's position on the field.
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 gyroAngle The angle reported by the gyroscope.
53 * @param modulePositions The wheel positions reported by each module.
54 * @param pose The position on the field that your robot is at.
55 */
56 void ResetPosition(
57 const Rotation2d& gyroAngle,
59 const Pose2d& pose);
60
61 /**
62 * Returns the position of the robot on the field.
63 * @return The pose of the robot.
64 */
65 const Pose2d& GetPose() const { return m_pose; }
66
67 /**
68 * Updates the robot's position on the field using forward kinematics and
69 * integration of the pose over time. This also takes in an angle parameter
70 * which is used instead of the angular rate that is calculated from forward
71 * kinematics.
72 *
73 * @param gyroAngle The angle reported by the gyroscope.
74 * @param modulePositions The current position of all swerve modules. Please
75 * provide the positions in the same order in which you instantiated your
76 * SwerveDriveKinematics.
77 *
78 * @return The new pose of the robot.
79 */
80 const Pose2d& Update(
81 const Rotation2d& gyroAngle,
83
84 private:
86 Pose2d m_pose;
87
88 Rotation2d m_previousAngle;
89 Rotation2d m_gyroOffset;
90
91 wpi::array<SwerveModulePosition, NumModules> m_previousModulePositions{
93};
94
95extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
96 SwerveDriveOdometry<4>;
97
98} // namespace frc
99
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
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
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module ...
Definition: SwerveDriveKinematics.h:47
Class for swerve drive odometry.
Definition: SwerveDriveOdometry.h:31
const Pose2d & Update(const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions)
Updates the robot's position on the field using forward kinematics and integration of the pose over t...
Definition: SwerveDriveOdometry.inc:44
SwerveDriveOdometry(SwerveDriveKinematics< NumModules > kinematics, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose=Pose2d{})
Constructs a SwerveDriveOdometry object.
Definition: SwerveDriveOdometry.inc:12
void ResetPosition(const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &pose)
Resets the robot's position on the field.
Definition: SwerveDriveOdometry.inc:30
const Pose2d & GetPose() const
Returns the position of the robot on the field.
Definition: SwerveDriveOdometry.h:65
This class is a wrapper around std::array that does compile time size checking.
Definition: array.h:25
Definition: AprilTagFieldLayout.h:22
template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) LinearQuadraticRegulator< 1
constexpr empty_array_t empty_array
Definition: array.h:15