WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
MecanumDrivePoseEstimator3d.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 MecanumDriveOdometry3d. It is also intended to be an easy
21 * replacement for PoseEstimator, only requiring the addition of a standard
22 * deviation for Z and appropriate conversions between 2D and 3D versions of
23 * geometry classes. (See Pose3d(Pose2d), Rotation3d(Rotation2d),
24 * Translation3d(Translation2d), and Pose3d.ToPose2d().)
25 *
26 * Update() should be called every robot loop. If your loops are faster or
27 * slower than the default of 20 ms, then you should change the nominal delta
28 * time by specifying it in the constructor.
29 *
30 * AddVisionMeasurement() can be called as infrequently as you want; if you
31 * never call it, then this class will behave mostly like regular encoder
32 * odometry.
33 */
35 : public PoseEstimator3d<MecanumDriveWheelPositions,
36 MecanumDriveWheelVelocities,
37 MecanumDriveWheelAccelerations> {
38 public:
39 /**
40 * Constructs a MecanumDrivePoseEstimator3d 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.45
46 * meters for x, 0.45 meters for y, 0.45 meters for z, and 0.45 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 wheelPositions The distance measured by each wheel.
53 * @param initialPose The starting pose estimate.
54 */
56 const Rotation3d& gyroAngle,
57 const MecanumDriveWheelPositions& wheelPositions,
58 const Pose3d& initialPose);
59
60 /**
61 * Constructs a MecanumDrivePoseEstimator3d.
62 *
63 * @param kinematics A correctly-configured kinematics object for your
64 * drivetrain.
65 * @param gyroAngle The current gyro angle.
66 * @param wheelPositions The distance measured by each wheel.
67 * @param initialPose The starting pose estimate.
68 * @param stateStdDevs Standard deviations of the pose estimate (x position in
69 * meters, y position in meters, z position in meters, and angle in
70 * radians). Increase these numbers to trust your state estimate less.
71 * @param visionMeasurementStdDevs Standard deviations of the vision pose
72 * measurement (x position in meters, y position in meters, z position in
73 * meters, and angle in radians). Increase these numbers to trust the vision
74 * pose measurement less.
75 */
77 MecanumDriveKinematics& kinematics, const Rotation3d& gyroAngle,
78 const MecanumDriveWheelPositions& wheelPositions,
79 const Pose3d& initialPose,
80 const wpi::util::array<double, 4>& stateStdDevs,
81 const wpi::util::array<double, 4>& visionMeasurementStdDevs);
82
83 private:
84 MecanumDriveOdometry3d m_odometryImpl;
85};
86
87} // 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 MecanumDriveOdometry3d.hpp:27
MecanumDrivePoseEstimator3d(MecanumDriveKinematics &kinematics, const Rotation3d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose3d &initialPose, const wpi::util::array< double, 4 > &stateStdDevs, const wpi::util::array< double, 4 > &visionMeasurementStdDevs)
Constructs a MecanumDrivePoseEstimator3d.
MecanumDrivePoseEstimator3d(MecanumDriveKinematics &kinematics, const Rotation3d &gyroAngle, const MecanumDriveWheelPositions &wheelPositions, const Pose3d &initialPose)
Constructs a MecanumDrivePoseEstimator3d with default standard deviations for the model and vision me...
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.hpp:28
PoseEstimator3d(Kinematics< MecanumDriveWheelPositions, MecanumDriveWheelVelocities, MecanumDriveWheelAccelerations > &kinematics, Odometry3d< MecanumDriveWheelPositions, MecanumDriveWheelVelocities, MecanumDriveWheelAccelerations > &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
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