30 :
public Odometry3d<DifferentialDriveWheelSpeeds,
31 DifferentialDriveWheelPositions> {
45 units::meter_t leftDistance,
46 units::meter_t rightDistance,
64 units::meter_t rightDistance,
const Pose3d& pose) {
65 Odometry3d::ResetPosition(gyroAngle, {leftDistance, rightDistance}, pose);
80 units::meter_t rightDistance) {
81 return Odometry3d::Update(gyroAngle, {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
DifferentialDriveOdometry3d(const Rotation3d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance, const Pose3d &initialPose=Pose3d{})
Constructs a DifferentialDriveOdometry3d object.
const Pose3d & Update(const Rotation3d &gyroAngle, units::meter_t leftDistance, units::meter_t rightDistance)
Updates the robot position on the field using distance measurements from encoders.
Definition DifferentialDriveOdometry3d.h:79
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 DifferentialDriveOdometry3d.h:63
Class for odometry.
Definition Odometry3d.h:33
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.h:28
A rotation in a 3D coordinate frame represented by a quaternion.
Definition Rotation3d.h:29