WPILibC++ 2023.4.3-108-ge5452e3
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
14#include "Odometry.h"
18#include "SwerveModuleState.h"
19#include "frc/geometry/Pose2d.h"
20#include "units/time.h"
21
22namespace frc {
23
24/**
25 * Class for swerve drive odometry. Odometry allows you to track the robot's
26 * position on the field over a course of a match using readings from your
27 * swerve drive encoders and swerve azimuth encoders.
28 *
29 * Teams can use odometry during the autonomous period for complex tasks like
30 * path following. Furthermore, odometry can be used for latency compensation
31 * when using computer-vision systems.
32 */
33template <size_t NumModules>
35 : public Odometry<SwerveDriveWheelSpeeds<NumModules>,
36 SwerveDriveWheelPositions<NumModules>> {
37 public:
38 /**
39 * Constructs a SwerveDriveOdometry object.
40 *
41 * @param kinematics The swerve drive kinematics for your drivetrain.
42 * @param gyroAngle The angle reported by the gyroscope.
43 * @param modulePositions The wheel positions reported by each module.
44 * @param initialPose The starting position of the robot on the field.
45 */
47 SwerveDriveKinematics<NumModules> kinematics, const Rotation2d& gyroAngle,
49 const Pose2d& initialPose = Pose2d{});
50
51 /**
52 * Resets the robot's position on the field.
53 *
54 * The gyroscope angle does not need to be reset here on the user's robot
55 * code. The library automatically takes care of offsetting the gyro angle.
56 *
57 * @param gyroAngle The angle reported by the gyroscope.
58 * @param modulePositions The wheel positions reported by each module.
59 * @param pose The position on the field that your robot is at.
60 */
62 const Rotation2d& gyroAngle,
64 const Pose2d& pose) {
68 {modulePositions},
69 pose);
70 }
71
72 /**
73 * Updates the robot's position on the field using forward kinematics and
74 * integration of the pose over time. This also takes in an angle parameter
75 * which is used instead of the angular rate that is calculated from forward
76 * kinematics.
77 *
78 * @param gyroAngle The angle reported by the gyroscope.
79 * @param modulePositions The current position of all swerve modules. Please
80 * provide the positions in the same order in which you instantiated your
81 * SwerveDriveKinematics.
82 *
83 * @return The new pose of the robot.
84 */
85 const Pose2d& Update(
86 const Rotation2d& gyroAngle,
87 const wpi::array<SwerveModulePosition, NumModules>& modulePositions) {
88 return Odometry<
91 {modulePositions});
92 }
93
94 private:
95 SwerveDriveKinematics<NumModules> m_kinematicsImpl;
96};
97
98extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
99 SwerveDriveOdometry<4>;
100
101} // namespace frc
102
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
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
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module ...
Definition: SwerveDriveKinematics.h:56
Class for swerve drive odometry.
Definition: SwerveDriveOdometry.h:36
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.h:85
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.h:61
This class is a wrapper around std::array that does compile time size checking.
Definition: array.h:26
Definition: AprilTagPoseEstimator.h:15
template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) UnscentedKalmanFilter< 3
Represents the wheel positions for a swerve drive drivetrain.
Definition: SwerveDriveWheelPositions.h:18