WPILibC++ 2025.1.1
Loading...
Searching...
No Matches
DifferentialDrivePoseEstimator3d.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 <wpi/SymbolExports.h>
8#include <wpi/array.h>
9
11#include "frc/geometry/Pose2d.h"
15#include "units/time.h"
16
17namespace frc {
18/**
19 * This class wraps Differential Drive Odometry to fuse latency-compensated
20 * vision measurements with differential drive encoder measurements. It will
21 * correct for noisy vision measurements and encoder drift. It is intended to be
22 * an easy drop-in for DifferentialDriveOdometry3d. In fact, if you never call
23 * AddVisionMeasurement(), and only call Update(), this will behave exactly the
24 * same as DifferentialDriveOdometry3d. It is also intended to be an easy
25 * replacement for PoseEstimator, only requiring the addition of a standard
26 * deviation for Z and appropriate conversions between 2D and 3D versions of
27 * geometry classes. (See Pose3d(Pose2d), Rotation3d(Rotation2d),
28 * Translation3d(Translation2d), and Pose3d.ToPose2d().)
29 *
30 * Update() should be called every robot loop (if your robot loops are faster or
31 * slower than the default of 20 ms, then you should change the nominal delta
32 * time via the constructor).
33 *
34 * AddVisionMeasurement() can be called as infrequently as you want; if you
35 * never call it, then this class will behave like regular encoder odometry.
36 */
38 : public PoseEstimator3d<DifferentialDriveWheelSpeeds,
39 DifferentialDriveWheelPositions> {
40 public:
41 /**
42 * Constructs a DifferentialDrivePoseEstimator3d with default standard
43 * deviations for the model and vision measurements.
44 *
45 * The default standard deviations of the model states are
46 * 0.02 meters for x, 0.02 meters for y, 0.02 meters for z, and 0.01 radians
47 * for angle. The default standard deviations of the vision measurements are
48 * 0.1 meters for x, 0.1 meters for y, 0.1 meters for z, and 0.1 radians for
49 * angle.
50 *
51 * @param kinematics A correctly-configured kinematics object for your
52 * drivetrain.
53 * @param gyroAngle The gyro angle of the robot.
54 * @param leftDistance The distance traveled by the left encoder.
55 * @param rightDistance The distance traveled by the right encoder.
56 * @param initialPose The estimated initial pose.
57 */
59 const Rotation3d& gyroAngle,
60 units::meter_t leftDistance,
61 units::meter_t rightDistance,
62 const Pose3d& initialPose);
63
64 /**
65 * Constructs a DifferentialDrivePoseEstimator3d.
66 *
67 * @param kinematics A correctly-configured kinematics object for your
68 * drivetrain.
69 * @param gyroAngle The gyro angle of the robot.
70 * @param leftDistance The distance traveled by the left encoder.
71 * @param rightDistance The distance traveled by the right encoder.
72 * @param initialPose The estimated initial pose.
73 * @param stateStdDevs Standard deviations of the pose estimate (x position in
74 * meters, y position in meters, z position in meters, and angle in
75 * radians). Increase these numbers to trust your state estimate less.
76 * @param visionMeasurementStdDevs Standard deviations of the vision pose
77 * measurement (x position in meters, y position in meters, z position in
78 * meters, and angle in radians). Increase these numbers to trust the vision
79 * pose measurement less.
80 */
82 DifferentialDriveKinematics& kinematics, const Rotation3d& gyroAngle,
83 units::meter_t leftDistance, units::meter_t rightDistance,
84 const Pose3d& initialPose, const wpi::array<double, 4>& stateStdDevs,
85 const wpi::array<double, 4>& visionMeasurementStdDevs);
86
87 /**
88 * Resets the robot's position on the field.
89 *
90 * @param gyroAngle The current gyro angle.
91 * @param leftDistance The distance traveled by the left encoder.
92 * @param rightDistance The distance traveled by the right encoder.
93 * @param pose The estimated pose of the robot on the field.
94 */
95 void ResetPosition(const Rotation3d& gyroAngle, units::meter_t leftDistance,
96 units::meter_t rightDistance, const Pose3d& pose) {
97 PoseEstimator3d::ResetPosition(gyroAngle, {leftDistance, rightDistance},
98 pose);
99 }
100
101 /**
102 * Updates the pose estimator with wheel encoder and gyro information. This
103 * should be called every loop.
104 *
105 * @param gyroAngle The current gyro angle.
106 * @param leftDistance The distance traveled by the left encoder.
107 * @param rightDistance The distance traveled by the right encoder.
108 *
109 * @return The estimated pose of the robot.
110 */
111 Pose3d Update(const Rotation3d& gyroAngle, units::meter_t leftDistance,
112 units::meter_t rightDistance) {
113 return PoseEstimator3d::Update(gyroAngle, {leftDistance, rightDistance});
114 }
115
116 /**
117 * Updates the pose estimator with wheel encoder and gyro information. This
118 * should be called every loop.
119 *
120 * @param currentTime The time at which this method was called.
121 * @param gyroAngle The current gyro angle.
122 * @param leftDistance The distance traveled by the left encoder.
123 * @param rightDistance The distance traveled by the right encoder.
124 *
125 * @return The estimated pose of the robot.
126 */
127 Pose3d UpdateWithTime(units::second_t currentTime,
128 const Rotation3d& gyroAngle,
129 units::meter_t leftDistance,
130 units::meter_t rightDistance) {
131 return PoseEstimator3d::UpdateWithTime(currentTime, gyroAngle,
132 {leftDistance, rightDistance});
133 }
134
135 private:
136 DifferentialDriveOdometry3d m_odometryImpl;
137};
138
139} // namespace frc
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition DifferentialDriveKinematics.h:31
Class for differential drive odometry.
Definition DifferentialDriveOdometry3d.h:31
This class wraps Differential Drive Odometry to fuse latency-compensated vision measurements with dif...
Definition DifferentialDrivePoseEstimator3d.h:39
Pose3d UpdateWithTime(units::second_t currentTime, const Rotation3d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance)
Updates the pose estimator with wheel encoder and gyro information.
Definition DifferentialDrivePoseEstimator3d.h:127
void ResetPosition(const Rotation3d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose3d &pose)
Resets the robot's position on the field.
Definition DifferentialDrivePoseEstimator3d.h:95
Pose3d Update(const Rotation3d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance)
Updates the pose estimator with wheel encoder and gyro information.
Definition DifferentialDrivePoseEstimator3d.h:111
DifferentialDrivePoseEstimator3d(DifferentialDriveKinematics &kinematics, const Rotation3d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose3d &initialPose, const wpi::array< double, 4 > &stateStdDevs, const wpi::array< double, 4 > &visionMeasurementStdDevs)
Constructs a DifferentialDrivePoseEstimator3d.
DifferentialDrivePoseEstimator3d(DifferentialDriveKinematics &kinematics, const Rotation3d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose3d &initialPose)
Constructs a DifferentialDrivePoseEstimator3d with default standard deviations for the model and visi...
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.h:28
This class wraps odometry to fuse latency-compensated vision measurements with encoder measurements.
Definition PoseEstimator3d.h:49
A rotation in a 3D coordinate frame represented by a quaternion.
Definition Rotation3d.h:29
This class is a wrapper around std::array that does compile time size checking.
Definition array.h:26
Definition CAN.h:11