WPILibC++ 2025.0.0-alpha-1-24-g6478ba6
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"
17#include "SwerveModuleState.h"
18#include "frc/geometry/Pose2d.h"
19#include "units/time.h"
20
21namespace frc {
22
23/**
24 * Class for swerve drive odometry. Odometry allows you to track the robot's
25 * position on the field over a course of a match using readings from your
26 * swerve drive encoders and swerve azimuth encoders.
27 *
28 * Teams can use odometry during the autonomous period for complex tasks like
29 * path following. Furthermore, odometry can be used for latency compensation
30 * when using computer-vision systems.
31 */
32template <size_t NumModules>
34 : public Odometry<wpi::array<SwerveModuleState, NumModules>,
35 wpi::array<SwerveModulePosition, NumModules>> {
36 public:
37 /**
38 * Constructs a SwerveDriveOdometry object.
39 *
40 * @param kinematics The swerve drive kinematics for your drivetrain.
41 * @param gyroAngle The angle reported by the gyroscope.
42 * @param modulePositions The wheel positions reported by each module.
43 * @param initialPose The starting position of the robot on the field.
44 */
46 SwerveDriveKinematics<NumModules> kinematics, const Rotation2d& gyroAngle,
48 const Pose2d& initialPose = Pose2d{});
49
50 private:
51 SwerveDriveKinematics<NumModules> m_kinematicsImpl;
52};
53
54extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
56
57} // namespace frc
58
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Class for odometry.
Definition: Odometry.h:28
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module ...
Definition: SwerveDriveKinematics.h:52
Class for swerve drive odometry.
Definition: SwerveDriveOdometry.h:35
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
Definition: AprilTagDetector_cv.h:11
template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) LinearQuadraticRegulator< 1