12#include "wpi/units/length.hpp"
29 :
public Odometry<DifferentialDriveWheelPositions,
30 DifferentialDriveWheelVelocities,
31 DifferentialDriveWheelAccelerations> {
45 wpi::units::meter_t leftDistance,
46 wpi::units::meter_t rightDistance,
64 wpi::units::meter_t leftDistance,
65 wpi::units::meter_t rightDistance,
const Pose2d& pose) {
81 wpi::units::meter_t leftDistance,
82 wpi::units::meter_t rightDistance) {
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition DifferentialDriveKinematics.hpp:33
DifferentialDriveOdometry(const Rotation2d &gyroAngle, wpi::units::meter_t leftDistance, wpi::units::meter_t rightDistance, const Pose2d &initialPose=Pose2d{})
Constructs a DifferentialDriveOdometry object.
const Pose2d & Update(const Rotation2d &gyroAngle, wpi::units::meter_t leftDistance, wpi::units::meter_t rightDistance)
Updates the robot position on the field using distance measurements from encoders.
Definition DifferentialDriveOdometry.hpp:80
void ResetPosition(const Rotation2d &gyroAngle, wpi::units::meter_t leftDistance, wpi::units::meter_t rightDistance, const Pose2d &pose)
Resets the robot's position on the field.
Definition DifferentialDriveOdometry.hpp:63
const Pose2d & Update(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions)
Updates the robot's position on the field using forward kinematics and integration of the pose over t...
Definition Odometry.hpp:120
void ResetPosition(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions, const Pose2d &pose)
Resets the robot's position on the field.
Definition Odometry.hpp:63
Odometry(const Kinematics< DifferentialDriveWheelPositions, DifferentialDriveWheelVelocities, DifferentialDriveWheelAccelerations > &kinematics, const Rotation2d &gyroAngle, const DifferentialDriveWheelPositions &wheelPositions, const Pose2d &initialPose=Pose2d{})
Definition Odometry.hpp:41
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
Definition LinearSystem.hpp:20