WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
SwerveDriveOdometry.hpp
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
16
17namespace wpi::math {
18
19/**
20 * Class for swerve drive odometry. Odometry allows you to track the robot's
21 * position on the field over a course of a match using readings from your
22 * swerve drive encoders and swerve azimuth encoders.
23 *
24 * Teams can use odometry during the autonomous period for complex tasks like
25 * path following. Furthermore, odometry can be used for latency compensation
26 * when using computer-vision systems.
27 */
28template <size_t NumModules>
30 : public Odometry<wpi::util::array<SwerveModulePosition, NumModules>,
31 wpi::util::array<SwerveModuleVelocity, NumModules>,
32 wpi::util::array<SwerveModuleAcceleration, NumModules>> {
33 public:
34 /**
35 * Constructs a SwerveDriveOdometry object.
36 *
37 * @param kinematics The swerve drive kinematics for your drivetrain.
38 * @param gyroAngle The angle reported by the gyroscope.
39 * @param modulePositions The wheel positions reported by each module.
40 * @param initialPose The starting position of the robot on the field.
41 */
43 SwerveDriveKinematics<NumModules> kinematics, const Rotation2d& gyroAngle,
45 const Pose2d& initialPose = Pose2d{})
46 : SwerveDriveOdometry::Odometry(m_kinematicsImpl, gyroAngle,
47 modulePositions, initialPose),
48 m_kinematicsImpl(kinematics) {
49 wpi::math::MathSharedStore::ReportUsage("SwerveDriveOdometry", "");
50 }
51
52 private:
53 SwerveDriveKinematics<NumModules> m_kinematicsImpl;
54};
55
56extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
57 SwerveDriveOdometry<4>;
58
59} // namespace wpi::math
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:94
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
static void ReportUsage(std::string_view resource, std::string_view data)
Definition MathShared.hpp:61
Class for odometry.
Definition Odometry.hpp:31
Odometry(const Kinematics< wpi::util::array< SwerveModulePosition, NumModules >, wpi::util::array< SwerveModuleVelocity, NumModules >, wpi::util::array< SwerveModuleAcceleration, NumModules > > &kinematics, const Rotation2d &gyroAngle, const wpi::util::array< SwerveModulePosition, NumModules > &wheelPositions, const Pose2d &initialPose=Pose2d{})
Definition Odometry.hpp:41
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module ...
Definition SwerveDriveKinematics.hpp:59
Class for swerve drive odometry.
Definition SwerveDriveOdometry.hpp:32
SwerveDriveOdometry(SwerveDriveKinematics< NumModules > kinematics, const Rotation2d &gyroAngle, const wpi::util::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose=Pose2d{})
Constructs a SwerveDriveOdometry object.
Definition SwerveDriveOdometry.hpp:42
This class is a wrapper around std::array that does compile time size checking.
Definition array.hpp:26
Definition LinearSystem.hpp:20
SwerveDriveKinematics(ModuleTranslation, ModuleTranslations...) -> SwerveDriveKinematics< 1+sizeof...(ModuleTranslations)>