WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
MecanumDrivePoseEstimator.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 * This class wraps Mecanum Drive Odometry to fuse latency-compensated
18 * vision measurements with mecanum drive encoder velocity measurements. It will
19 * correct for noisy measurements and encoder drift. It is intended to be an
20 * easy drop-in for MecanumDriveOdometry.
21 *
22 * Update() should be called every robot loop. If your loops are faster or
23 * slower than the default of 20 ms, then you should change the nominal delta
24 * time by specifying it in the constructor.
25 *
26 * AddVisionMeasurement() can be called as infrequently as you want; if you
27 * never call it, then this class will behave mostly like regular encoder
28 * odometry.
29 */
31 : public PoseEstimator<MecanumDriveWheelPositions,
32 MecanumDriveWheelVelocities,
33 MecanumDriveWheelAccelerations> {
34 public:
35 /**
36 * Constructs a MecanumDrivePoseEstimator 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.45 meters for x, 0.45 meters for y, and 0.45 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 wheelPositions The distance measured by each wheel.
48 * @param initialPose The starting pose estimate.
49 */
51 const Rotation2d& gyroAngle,
52 const MecanumDriveWheelPositions& wheelPositions,
53 const Pose2d& initialPose);
54
55 /**
56 * Constructs a MecanumDrivePoseEstimator.
57 *
58 * @param kinematics A correctly-configured kinematics object for your
59 * drivetrain.
60 * @param gyroAngle The current gyro angle.
61 * @param wheelPositions The distance measured by each wheel.
62 * @param initialPose The starting pose estimate.
63 * @param stateStdDevs Standard deviations of the pose estimate (x position in
64 * meters, y position in meters, and heading in radians). Increase these
65 * numbers to trust your state estimate less.
66 * @param visionMeasurementStdDevs Standard deviations of the vision pose
67 * measurement (x position in meters, y position in meters, and heading in
68 * radians). Increase these numbers to trust the vision pose measurement
69 * less.
70 */
72 MecanumDriveKinematics& kinematics, const Rotation2d& gyroAngle,
73 const MecanumDriveWheelPositions& wheelPositions,
74 const Pose2d& initialPose,
75 const wpi::util::array<double, 3>& stateStdDevs,
76 const wpi::util::array<double, 3>& visionMeasurementStdDevs);
77
78 private:
79 MecanumDriveOdometry m_odometryImpl;
80};
81
82} // namespace wpi::math
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel v...
Definition MecanumDriveKinematics.hpp:48
Class for mecanum drive odometry.
Definition MecanumDriveOdometry.hpp:27
MecanumDrivePoseEstimator(MecanumDriveKinematics &kinematics, const Rotation2d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose2d &initialPose, const wpi::util::array< double, 3 > &stateStdDevs, const wpi::util::array< double, 3 > &visionMeasurementStdDevs)
Constructs a MecanumDrivePoseEstimator.
MecanumDrivePoseEstimator(MecanumDriveKinematics &kinematics, const Rotation2d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose2d &initialPose)
Constructs a MecanumDrivePoseEstimator with default standard deviations for the model and vision meas...
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
PoseEstimator(Kinematics< MecanumDriveWheelPositions, MecanumDriveWheelVelocities, MecanumDriveWheelAccelerations > &kinematics, Odometry< MecanumDriveWheelPositions, MecanumDriveWheelVelocities, MecanumDriveWheelAccelerations > &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
This class is a wrapper around std::array that does compile time size checking.
Definition array.hpp:26
Definition LinearSystem.hpp:20
Represents the wheel positions for a mecanum drive drivetrain.
Definition MecanumDriveWheelPositions.hpp:15