WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
SwerveDrivePoseEstimator3d.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
13#include "wpi/util/array.hpp"
14
15namespace wpi::math {
16
17/**
18 * This class wraps Swerve Drive Odometry to fuse latency-compensated
19 * vision measurements with swerve drive encoder distance measurements. It is
20 * intended to be a drop-in for SwerveDriveOdometry3d. It is also intended to be
21 * an easy replacement for PoseEstimator, only requiring the addition of a
22 * standard deviation for Z and appropriate conversions between 2D and 3D
23 * versions of geometry classes. (See Pose3d(Pose2d), Rotation3d(Rotation2d),
24 * Translation3d(Translation2d), and Pose3d.ToPose2d().)
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 PoseEstimator3d<
35 wpi::util::array<SwerveModulePosition, NumModules>,
36 wpi::util::array<SwerveModuleVelocity, NumModules>,
37 wpi::util::array<SwerveModuleAcceleration, NumModules>> {
38 public:
39 /**
40 * Constructs a SwerveDrivePoseEstimator3d with default standard deviations
41 * for the model and vision measurements.
42 *
43 * The default standard deviations of the model states are
44 * 0.1 meters for x, 0.1 meters for y, 0.1 meters for z, and 0.1 radians for
45 * angle. The default standard deviations of the vision measurements are 0.9
46 * meters for x, 0.9 meters for y, 0.9 meters for z, and 0.9 radians for
47 * angle.
48 *
49 * @param kinematics A correctly-configured kinematics object for your
50 * drivetrain.
51 * @param gyroAngle The current gyro angle.
52 * @param modulePositions The current distance and rotation measurements of
53 * the swerve modules.
54 * @param initialPose The starting pose estimate.
55 */
58 const Rotation3d& gyroAngle,
60 const Pose3d& initialPose)
61 : SwerveDrivePoseEstimator3d{kinematics, gyroAngle,
62 modulePositions, initialPose,
63 {0.1, 0.1, 0.1, 0.1}, {0.9, 0.9, 0.9, 0.9}} {
64 }
65
66 /**
67 * Constructs a SwerveDrivePoseEstimator3d.
68 *
69 * @param kinematics A correctly-configured kinematics object for your
70 * drivetrain.
71 * @param gyroAngle The current gyro angle.
72 * @param modulePositions The current distance and rotation measurements of
73 * the swerve modules.
74 * @param initialPose The starting pose estimate.
75 * @param stateStdDevs Standard deviations of the pose estimate (x position in
76 * meters, y position in meters, and heading in radians). Increase these
77 * numbers to trust your state estimate less.
78 * @param visionMeasurementStdDevs Standard deviations of the vision pose
79 * measurement (x position in meters, y position in meters, and heading in
80 * radians). Increase these numbers to trust the vision pose measurement
81 * less.
82 */
85 const Rotation3d& gyroAngle,
87 const Pose3d& initialPose,
88 const wpi::util::array<double, 4>& stateStdDevs,
89 const wpi::util::array<double, 4>& visionMeasurementStdDevs)
91 kinematics, m_odometryImpl, stateStdDevs, visionMeasurementStdDevs),
92 m_odometryImpl{kinematics, gyroAngle, modulePositions, initialPose} {
93 this->ResetPose(initialPose);
94 }
95
96 private:
98};
99
100extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
101 SwerveDrivePoseEstimator3d<4>;
102
103} // namespace wpi::math
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:94
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.hpp:28
PoseEstimator3d(Kinematics< wpi::util::array< SwerveModulePosition, NumModules >, wpi::util::array< SwerveModuleVelocity, NumModules >, wpi::util::array< SwerveModuleAcceleration, NumModules > > &kinematics, Odometry3d< wpi::util::array< SwerveModulePosition, NumModules >, wpi::util::array< SwerveModuleVelocity, NumModules >, wpi::util::array< SwerveModuleAcceleration, NumModules > > &odometry, const wpi::util::array< double, 4 > &stateStdDevs, const wpi::util::array< double, 4 > &visionMeasurementStdDevs)
Definition PoseEstimator3d.hpp:71
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.hpp:69
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 SwerveDriveOdometry3d.hpp:32
SwerveDrivePoseEstimator3d(SwerveDriveKinematics< NumModules > &kinematics, const Rotation3d &gyroAngle, const wpi::util::array< SwerveModulePosition, NumModules > &modulePositions, const Pose3d &initialPose)
Constructs a SwerveDrivePoseEstimator3d with default standard deviations for the model and vision mea...
Definition SwerveDrivePoseEstimator3d.hpp:56
SwerveDrivePoseEstimator3d(SwerveDriveKinematics< NumModules > &kinematics, const Rotation3d &gyroAngle, const wpi::util::array< SwerveModulePosition, NumModules > &modulePositions, const Pose3d &initialPose, const wpi::util::array< double, 4 > &stateStdDevs, const wpi::util::array< double, 4 > &visionMeasurementStdDevs)
Constructs a SwerveDrivePoseEstimator3d.
Definition SwerveDrivePoseEstimator3d.hpp:83
This class is a wrapper around std::array that does compile time size checking.
Definition array.hpp:26
Definition LinearSystem.hpp:20