39                             DifferentialDriveWheelPositions> {
 
   60                                   units::meter_t leftDistance,
 
   61                                   units::meter_t rightDistance,
 
   62                                   const Pose3d& initialPose);
 
   83      units::meter_t leftDistance, units::meter_t rightDistance,
 
   96                     units::meter_t rightDistance, 
const Pose3d& pose) {
 
   97    PoseEstimator3d::ResetPosition(gyroAngle, {leftDistance, rightDistance},
 
 
  112                units::meter_t rightDistance) {
 
  113    return PoseEstimator3d::Update(gyroAngle, {leftDistance, rightDistance});
 
 
  129                        units::meter_t leftDistance,
 
  130                        units::meter_t rightDistance) {
 
  131    return PoseEstimator3d::UpdateWithTime(currentTime, gyroAngle,
 
  132                                           {leftDistance, rightDistance});
 
 
 
#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