WPILibC++ 2027.0.0-alpha-2
Loading...
Searching...
No Matches
SwerveDriveOdometry3d.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 "Odometry3d.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 Odometry3d<wpi::array<SwerveModuleState, NumModules>,
35 wpi::array<SwerveModulePosition, NumModules>> {
36 public:
37 /**
38 * Constructs a SwerveDriveOdometry3d 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 */
45#if defined(__GNUC__) && !defined(__clang__)
46#pragma GCC diagnostic push
47#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
48#endif // defined(__GNUC__) && !defined(__clang__)
50 SwerveDriveKinematics<NumModules> kinematics, const Rotation3d& gyroAngle,
52 const Pose3d& initialPose = Pose3d{})
53 : SwerveDriveOdometry3d::Odometry3d(m_kinematicsImpl, gyroAngle,
54 modulePositions, initialPose),
55 m_kinematicsImpl(kinematics) {
56 wpi::math::MathSharedStore::ReportUsage("SwerveDriveOdometry3d", "");
57 }
58#if defined(__GNUC__) && !defined(__clang__)
59#pragma GCC diagnostic pop
60#endif // defined(__GNUC__) && !defined(__clang__)
61
62 private:
63 SwerveDriveKinematics<NumModules> m_kinematicsImpl;
64};
65
66extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
67 SwerveDriveOdometry3d<4>;
68
69} // namespace frc
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.h:94
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Class for odometry.
Definition Odometry3d.h:33
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.h:31
A rotation in a 3D coordinate frame represented by a quaternion.
Definition Rotation3d.h:29
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 SwerveDriveOdometry3d.h:35
SwerveDriveOdometry3d(SwerveDriveKinematics< NumModules > kinematics, const Rotation3d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose3d &initialPose=Pose3d{})
Constructs a SwerveDriveOdometry3d object.
Definition SwerveDriveOdometry3d.h:49
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
static void ReportUsage(std::string_view resource, std::string_view data)
Definition MathShared.h:61
Definition SystemServer.h:9
SwerveDriveKinematics(ModuleTranslation, ModuleTranslations...) -> SwerveDriveKinematics< 1+sizeof...(ModuleTranslations)>