Loading [MathJax]/extensions/tex2jax.js
WPILibC++ 2025.3.2
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Modules Pages Concepts
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 <cstddef>
8#include <ctime>
9
10#include <wpi/SymbolExports.h>
11#include <wpi/timestamp.h>
12
13#include "Odometry.h"
16#include "SwerveModuleState.h"
17#include "frc/geometry/Pose2d.h"
18#include "wpimath/MathShared.h"
19
20namespace frc {
21
22/**
23 * Class for swerve drive odometry. Odometry allows you to track the robot's
24 * position on the field over a course of a match using readings from your
25 * swerve drive encoders and swerve azimuth encoders.
26 *
27 * Teams can use odometry during the autonomous period for complex tasks like
28 * path following. Furthermore, odometry can be used for latency compensation
29 * when using computer-vision systems.
30 */
31template <size_t NumModules>
33 : public Odometry<wpi::array<SwerveModuleState, NumModules>,
34 wpi::array<SwerveModulePosition, NumModules>> {
35 public:
36 /**
37 * Constructs a SwerveDriveOdometry object.
38 *
39 * @param kinematics The swerve drive kinematics for your drivetrain.
40 * @param gyroAngle The angle reported by the gyroscope.
41 * @param modulePositions The wheel positions reported by each module.
42 * @param initialPose The starting position of the robot on the field.
43 */
45 SwerveDriveKinematics<NumModules> kinematics, const Rotation2d& gyroAngle,
47 const Pose2d& initialPose = Pose2d{})
48 : SwerveDriveOdometry::Odometry(m_kinematicsImpl, gyroAngle,
49 modulePositions, initialPose),
50 m_kinematicsImpl(kinematics) {
53 }
54
55 private:
56 SwerveDriveKinematics<NumModules> m_kinematicsImpl;
57};
58
59extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
60 SwerveDriveOdometry<4>;
61
62} // namespace frc
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:92
Class for odometry.
Definition Odometry.h:30
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module ...
Definition SwerveDriveKinematics.h:54
Class for swerve drive odometry.
Definition SwerveDriveOdometry.h:34
SwerveDriveOdometry(SwerveDriveKinematics< NumModules > kinematics, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose=Pose2d{})
Constructs a SwerveDriveOdometry object.
Definition SwerveDriveOdometry.h:44
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
static void ReportUsage(MathUsageId id, int count)
Definition MathShared.h:75
Definition CAN.h:11
SwerveDriveKinematics(ModuleTranslation, ModuleTranslations...) -> SwerveDriveKinematics< 1+sizeof...(ModuleTranslations)>