WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
wpi::math::DifferentialDriveKinematics Class Reference

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>

Inheritance diagram for wpi::math::DifferentialDriveKinematics:
wpi::math::Kinematics< DifferentialDriveWheelPositions, DifferentialDriveWheelVelocities, DifferentialDriveWheelAccelerations >

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.

Detailed Description

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.

Constructor & Destructor Documentation

◆ DifferentialDriveKinematics()

wpi::math::DifferentialDriveKinematics::DifferentialDriveKinematics ( wpi::units::meter_t trackwidth)
inlineexplicitconstexpr

Constructs a differential drive kinematics object.

Parameters
trackwidthThe 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.

Member Function Documentation

◆ Interpolate()

DifferentialDriveWheelPositions wpi::math::DifferentialDriveKinematics::Interpolate ( const DifferentialDriveWheelPositions & start,
const DifferentialDriveWheelPositions & end,
double t ) const
inlineconstexproverridevirtual

Performs interpolation between two values.

Parameters
startThe value to start at.
endThe value to end at.
tHow far between the two values to interpolate. This should be bounded to [0, 1].
Returns
The interpolated value.

Implements wpi::math::Kinematics< DifferentialDriveWheelPositions, DifferentialDriveWheelVelocities, DifferentialDriveWheelAccelerations >.

◆ ToChassisAccelerations()

ChassisAccelerations wpi::math::DifferentialDriveKinematics::ToChassisAccelerations ( const DifferentialDriveWheelAccelerations & wheelAccelerations) const
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.

Parameters
wheelAccelerationsThe accelerations of the wheels.
Returns
The chassis accelerations.

Implements wpi::math::Kinematics< DifferentialDriveWheelPositions, DifferentialDriveWheelVelocities, DifferentialDriveWheelAccelerations >.

◆ ToChassisVelocities()

ChassisVelocities wpi::math::DifferentialDriveKinematics::ToChassisVelocities ( const DifferentialDriveWheelVelocities & wheelVelocities) const
inlineconstexproverridevirtual

Returns a chassis velocity from left and right component velocities using forward kinematics.

Parameters
wheelVelocitiesThe left and right velocities.
Returns
The chassis velocity.

Implements wpi::math::Kinematics< DifferentialDriveWheelPositions, DifferentialDriveWheelVelocities, DifferentialDriveWheelAccelerations >.

◆ ToTwist2d() [1/2]

Twist2d wpi::math::DifferentialDriveKinematics::ToTwist2d ( const DifferentialDriveWheelPositions & start,
const DifferentialDriveWheelPositions & end ) const
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.

Parameters
startThe starting distances driven by the wheels.
endThe ending distances driven by the wheels.
Returns
The resulting Twist2d in the robot's movement.

Implements wpi::math::Kinematics< DifferentialDriveWheelPositions, DifferentialDriveWheelVelocities, DifferentialDriveWheelAccelerations >.

◆ ToTwist2d() [2/2]

Twist2d wpi::math::DifferentialDriveKinematics::ToTwist2d ( const wpi::units::meter_t leftDistance,
const wpi::units::meter_t rightDistance ) const
inlineconstexpr

Returns a twist from left and right distance deltas using forward kinematics.

Parameters
leftDistanceThe distance measured by the left encoder.
rightDistanceThe distance measured by the right encoder.
Returns
The resulting Twist2d.

◆ ToWheelAccelerations()

DifferentialDriveWheelAccelerations wpi::math::DifferentialDriveKinematics::ToWheelAccelerations ( const ChassisAccelerations & chassisAccelerations) const
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.

Parameters
chassisAccelerationsThe desired chassis accelerations.
Returns
The wheel accelerations.

Implements wpi::math::Kinematics< DifferentialDriveWheelPositions, DifferentialDriveWheelVelocities, DifferentialDriveWheelAccelerations >.

◆ ToWheelVelocities()

DifferentialDriveWheelVelocities wpi::math::DifferentialDriveKinematics::ToWheelVelocities ( const ChassisVelocities & chassisVelocities) const
inlineconstexproverridevirtual

Returns left and right component velocities from a chassis velocity using inverse kinematics.

Parameters
chassisVelocitiesThe linear and angular (dx and dtheta) components that represent the chassis' velocity.
Returns
The left and right velocities.

Implements wpi::math::Kinematics< DifferentialDriveWheelPositions, DifferentialDriveWheelVelocities, DifferentialDriveWheelAccelerations >.

Member Data Documentation

◆ trackwidth

wpi::units::meter_t wpi::math::DifferentialDriveKinematics::trackwidth

Differential drive trackwidth.


The documentation for this class was generated from the following file: