WPILibC++ 2023.4.3
frc::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 <frc/kinematics/DifferentialDriveKinematics.h>

Public Member Functions

 DifferentialDriveKinematics (units::meter_t trackWidth)
 Constructs a differential drive kinematics object. More...
 
constexpr ChassisSpeeds ToChassisSpeeds (const DifferentialDriveWheelSpeeds &wheelSpeeds) const
 Returns a chassis speed from left and right component velocities using forward kinematics. More...
 
constexpr DifferentialDriveWheelSpeeds ToWheelSpeeds (const ChassisSpeeds &chassisSpeeds) const
 Returns left and right component velocities from a chassis speed using inverse kinematics. More...
 
constexpr Twist2d ToTwist2d (const units::meter_t leftDistance, const units::meter_t rightDistance) const
 Returns a twist from left and right distance deltas using forward kinematics. More...
 

Public Attributes

units::meter_t 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 speed into left and right velocity components whereas forward kinematics converts left and right component velocities into a linear and angular chassis speed.

Constructor & Destructor Documentation

◆ DifferentialDriveKinematics()

frc::DifferentialDriveKinematics::DifferentialDriveKinematics ( units::meter_t  trackWidth)
inlineexplicit

Constructs a differential drive kinematics object.

Parameters
trackWidthThe track width 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

◆ ToChassisSpeeds()

constexpr ChassisSpeeds frc::DifferentialDriveKinematics::ToChassisSpeeds ( const DifferentialDriveWheelSpeeds wheelSpeeds) const
inlineconstexpr

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

Parameters
wheelSpeedsThe left and right velocities.
Returns
The chassis speed.

◆ ToTwist2d()

constexpr Twist2d frc::DifferentialDriveKinematics::ToTwist2d ( const units::meter_t  leftDistance,
const 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.

◆ ToWheelSpeeds()

constexpr DifferentialDriveWheelSpeeds frc::DifferentialDriveKinematics::ToWheelSpeeds ( const ChassisSpeeds chassisSpeeds) const
inlineconstexpr

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

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

Member Data Documentation

◆ trackWidth

units::meter_t frc::DifferentialDriveKinematics::trackWidth

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