![]() |
WPILibC++ 2027.0.0-alpha-4
|
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velocities for a differential drive. More...
#include <wpi/math/kinematics/DifferentialDriveKinematics.hpp>
Public Member Functions | |
| constexpr | DifferentialDriveKinematics (wpi::units::meter_t trackwidth) |
| Constructs a differential drive kinematics object. | |
| constexpr ChassisVelocities | ToChassisVelocities (const DifferentialDriveWheelVelocities &wheelVelocities) const override |
| Returns a chassis velocity from left and right component velocities using forward kinematics. | |
| constexpr DifferentialDriveWheelVelocities | ToWheelVelocities (const ChassisVelocities &chassisVelocities) const override |
| Returns left and right component velocities from a chassis velocity using inverse kinematics. | |
| constexpr Twist2d | ToTwist2d (const wpi::units::meter_t leftDistance, const wpi::units::meter_t rightDistance) const |
| Returns a twist from left and right distance deltas using forward kinematics. | |
| constexpr Twist2d | ToTwist2d (const DifferentialDriveWheelPositions &start, const DifferentialDriveWheelPositions &end) const override |
| Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions. | |
| constexpr DifferentialDriveWheelPositions | Interpolate (const DifferentialDriveWheelPositions &start, const DifferentialDriveWheelPositions &end, double t) const override |
| Performs interpolation between two values. | |
| constexpr ChassisAccelerations | ToChassisAccelerations (const DifferentialDriveWheelAccelerations &wheelAccelerations) const override |
| Performs forward kinematics to return the resulting chassis accelerations from the wheel accelerations. | |
| constexpr DifferentialDriveWheelAccelerations | ToWheelAccelerations (const ChassisAccelerations &chassisAccelerations) const override |
| Performs inverse kinematics to return the wheel accelerations from a desired chassis acceleration. | |
| Public Member Functions inherited from wpi::math::Kinematics< DifferentialDriveWheelPositions, DifferentialDriveWheelVelocities, DifferentialDriveWheelAccelerations > | |
| virtual | ~Kinematics () noexcept=default |
Public Attributes | |
| wpi::units::meter_t | trackwidth |
| Differential drive trackwidth. | |
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velocities for a differential drive.
Inverse kinematics converts a desired chassis velocity into left and right velocity components whereas forward kinematics converts left and right component velocities into a linear and angular chassis velocity.
|
inlineexplicitconstexpr |
Constructs a differential drive kinematics object.
| trackwidth | The trackwidth of the drivetrain. Theoretically, this is the distance between the left wheels and right wheels. However, the empirical value may be larger than the physical measured value due to scrubbing effects. |
|
inlineconstexproverridevirtual |
Performs interpolation between two values.
| start | The value to start at. |
| end | The value to end at. |
| t | How far between the two values to interpolate. This should be bounded to [0, 1]. |
|
inlineconstexproverridevirtual |
Performs forward kinematics to return the resulting chassis accelerations from the wheel accelerations.
This method is often used for dynamics calculations – determining the robot's acceleration on the field using data from the real-world acceleration of each wheel on the robot.
| wheelAccelerations | The accelerations of the wheels. |
|
inlineconstexproverridevirtual |
Returns a chassis velocity from left and right component velocities using forward kinematics.
| wheelVelocities | The left and right velocities. |
|
inlineconstexproverridevirtual |
Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions.
This method is often used for odometry – determining the robot's position on the field using changes in the distance driven by each wheel on the robot.
| start | The starting distances driven by the wheels. |
| end | The ending distances driven by the wheels. |
|
inlineconstexpr |
Returns a twist from left and right distance deltas using forward kinematics.
| leftDistance | The distance measured by the left encoder. |
| rightDistance | The distance measured by the right encoder. |
|
inlineconstexproverridevirtual |
Performs inverse kinematics to return the wheel accelerations from a desired chassis acceleration.
This method is often used for dynamics calculations – converting desired robot accelerations into individual wheel accelerations.
| chassisAccelerations | The desired chassis accelerations. |
|
inlineconstexproverridevirtual |
Returns left and right component velocities from a chassis velocity using inverse kinematics.
| chassisVelocities | The linear and angular (dx and dtheta) components that represent the chassis' velocity. |
| wpi::units::meter_t wpi::math::DifferentialDriveKinematics::trackwidth |
Differential drive trackwidth.