WPILibC++ 2025.0.0-alpha-1-24-g6478ba6
SwerveDrivePoseEstimator.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 <cmath>
8
9#include <wpi/SymbolExports.h>
10#include <wpi/array.h>
11
13#include "frc/geometry/Pose2d.h"
17#include "units/time.h"
18
19namespace frc {
20
21/**
22 * This class wraps Swerve Drive Odometry to fuse latency-compensated
23 * vision measurements with swerve drive encoder distance measurements. It is
24 * intended to be a drop-in for SwerveDriveOdometry.
25 *
26 * Update() should be called every robot loop.
27 *
28 * AddVisionMeasurement() can be called as infrequently as you want; if you
29 * never call it, then this class will behave as regular encoder
30 * odometry.
31 */
32template <size_t NumModules>
34 : public PoseEstimator<wpi::array<SwerveModuleState, NumModules>,
35 wpi::array<SwerveModulePosition, NumModules>> {
36 public:
37 /**
38 * Constructs a SwerveDrivePoseEstimator with default standard deviations
39 * for the model and vision measurements.
40 *
41 * The default standard deviations of the model states are
42 * 0.1 meters for x, 0.1 meters for y, and 0.1 radians for heading.
43 * The default standard deviations of the vision measurements are
44 * 0.9 meters for x, 0.9 meters for y, and 0.9 radians for heading.
45 *
46 * @param kinematics A correctly-configured kinematics object for your
47 * drivetrain.
48 * @param gyroAngle The current gyro angle.
49 * @param modulePositions The current distance and rotation measurements of
50 * the swerve modules.
51 * @param initialPose The starting pose estimate.
52 */
55 const Rotation2d& gyroAngle,
57 const Pose2d& initialPose)
58 : SwerveDrivePoseEstimator{kinematics, gyroAngle,
59 modulePositions, initialPose,
60 {0.1, 0.1, 0.1}, {0.9, 0.9, 0.9}} {}
61
62 /**
63 * Constructs a SwerveDrivePoseEstimator.
64 *
65 * @param kinematics A correctly-configured kinematics object for your
66 * drivetrain.
67 * @param gyroAngle The current gyro angle.
68 * @param modulePositions The current distance and rotation measurements of
69 * the swerve modules.
70 * @param initialPose The starting pose estimate.
71 * @param stateStdDevs Standard deviations of the pose estimate (x position in
72 * meters, y position in meters, and heading in radians). Increase these
73 * numbers to trust your state estimate less.
74 * @param visionMeasurementStdDevs Standard deviations of the vision pose
75 * measurement (x position in meters, y position in meters, and heading in
76 * radians). Increase these numbers to trust the vision pose measurement
77 * less.
78 */
81 const Rotation2d& gyroAngle,
83 const Pose2d& initialPose, const wpi::array<double, 3>& stateStdDevs,
84 const wpi::array<double, 3>& visionMeasurementStdDevs)
85 : PoseEstimator<wpi::array<SwerveModuleState, NumModules>,
86 wpi::array<SwerveModulePosition, NumModules>>(
87 kinematics, m_odometryImpl, stateStdDevs, visionMeasurementStdDevs),
88 m_odometryImpl{kinematics, gyroAngle, modulePositions, initialPose} {}
89
90 private:
92};
93
94extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
95 SwerveDrivePoseEstimator<4>;
96
97} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
#define EXPORT_TEMPLATE_DECLARE(export)
Definition: SymbolExports.hpp:92
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
This class wraps odometry to fuse latency-compensated vision measurements with encoder measurements.
Definition: PoseEstimator.h:43
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
This class wraps Swerve Drive Odometry to fuse latency-compensated vision measurements with swerve dr...
Definition: SwerveDrivePoseEstimator.h:35
SwerveDrivePoseEstimator(SwerveDriveKinematics< NumModules > &kinematics, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose, const wpi::array< double, 3 > &stateStdDevs, const wpi::array< double, 3 > &visionMeasurementStdDevs)
Constructs a SwerveDrivePoseEstimator.
Definition: SwerveDrivePoseEstimator.h:79
SwerveDrivePoseEstimator(SwerveDriveKinematics< NumModules > &kinematics, const Rotation2d &gyroAngle, const wpi::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose)
Constructs a SwerveDrivePoseEstimator with default standard deviations for the model and vision measu...
Definition: SwerveDrivePoseEstimator.h:53
Definition: AprilTagDetector_cv.h:11
Definition: ntcore_cpp.h:26
Represents the position of one swerve module.
Definition: SwerveModulePosition.h:19
Represents the state of one swerve module.
Definition: SwerveModuleState.h:18