WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
SwerveDrivePoseEstimator.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 SwerveDriveOdometry.
21 *
22 * Update() should be called every robot loop.
23 *
24 * AddVisionMeasurement() can be called as infrequently as you want; if you
25 * never call it, then this class will behave as regular encoder
26 * odometry.
27 */
28template <size_t NumModules>
30 : public PoseEstimator<
31 wpi::util::array<SwerveModulePosition, NumModules>,
32 wpi::util::array<SwerveModuleVelocity, NumModules>,
33 wpi::util::array<SwerveModuleAcceleration, NumModules>> {
34 public:
35 /**
36 * Constructs a SwerveDrivePoseEstimator with default standard deviations
37 * for the model and vision measurements.
38 *
39 * The default standard deviations of the model states are
40 * 0.1 meters for x, 0.1 meters for y, and 0.1 radians for heading.
41 * The default standard deviations of the vision measurements are
42 * 0.9 meters for x, 0.9 meters for y, and 0.9 radians for heading.
43 *
44 * @param kinematics A correctly-configured kinematics object for your
45 * drivetrain.
46 * @param gyroAngle The current gyro angle.
47 * @param modulePositions The current distance and rotation measurements of
48 * the swerve modules.
49 * @param initialPose The starting pose estimate.
50 */
53 const Rotation2d& gyroAngle,
55 const Pose2d& initialPose)
56 : SwerveDrivePoseEstimator{kinematics, gyroAngle,
57 modulePositions, initialPose,
58 {0.1, 0.1, 0.1}, {0.9, 0.9, 0.9}} {}
59
60 /**
61 * Constructs a SwerveDrivePoseEstimator.
62 *
63 * @param kinematics A correctly-configured kinematics object for your
64 * drivetrain.
65 * @param gyroAngle The current gyro angle.
66 * @param modulePositions The current distance and rotation measurements of
67 * the swerve modules.
68 * @param initialPose The starting pose estimate.
69 * @param stateStdDevs Standard deviations of the pose estimate (x position in
70 * meters, y position in meters, and heading in radians). Increase these
71 * numbers to trust your state estimate less.
72 * @param visionMeasurementStdDevs Standard deviations of the vision pose
73 * measurement (x position in meters, y position in meters, and heading in
74 * radians). Increase these numbers to trust the vision pose measurement
75 * less.
76 */
79 const Rotation2d& gyroAngle,
81 const Pose2d& initialPose,
82 const wpi::util::array<double, 3>& stateStdDevs,
83 const wpi::util::array<double, 3>& visionMeasurementStdDevs)
85 kinematics, m_odometryImpl, stateStdDevs, visionMeasurementStdDevs),
86 m_odometryImpl{kinematics, gyroAngle, modulePositions, initialPose} {
87 this->ResetPose(initialPose);
88 }
89
90 private:
92};
93
94extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT)
95 SwerveDrivePoseEstimator<4>;
96
97} // namespace wpi::math
#define EXPORT_TEMPLATE_DECLARE(export)
Definition SymbolExports.hpp:94
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
PoseEstimator(Kinematics< wpi::util::array< SwerveModulePosition, NumModules >, wpi::util::array< SwerveModuleVelocity, NumModules >, wpi::util::array< SwerveModuleAcceleration, NumModules > > &kinematics, Odometry< wpi::util::array< SwerveModulePosition, NumModules >, wpi::util::array< SwerveModuleVelocity, NumModules >, wpi::util::array< SwerveModuleAcceleration, NumModules > > &odometry, const wpi::util::array< double, 3 > &stateStdDevs, const wpi::util::array< double, 3 > &visionMeasurementStdDevs)
Definition PoseEstimator.hpp:66
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
SwerveDrivePoseEstimator(SwerveDriveKinematics< NumModules > &kinematics, const Rotation2d &gyroAngle, const wpi::util::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose)
Constructs a SwerveDrivePoseEstimator with default standard deviations for the model and vision measu...
Definition SwerveDrivePoseEstimator.hpp:51
SwerveDrivePoseEstimator(SwerveDriveKinematics< NumModules > &kinematics, const Rotation2d &gyroAngle, const wpi::util::array< SwerveModulePosition, NumModules > &modulePositions, const Pose2d &initialPose, const wpi::util::array< double, 3 > &stateStdDevs, const wpi::util::array< double, 3 > &visionMeasurementStdDevs)
Constructs a SwerveDrivePoseEstimator.
Definition SwerveDrivePoseEstimator.hpp:77
This class is a wrapper around std::array that does compile time size checking.
Definition array.hpp:26
Definition LinearSystem.hpp:20