WPILibC++ 2023.4.3-108-ge5452e3
|
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 override |
Returns a chassis speed from left and right component velocities using forward kinematics. More... | |
constexpr DifferentialDriveWheelSpeeds | ToWheelSpeeds (const ChassisSpeeds &chassisSpeeds) const override |
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... | |
Twist2d | ToTwist2d (const DifferentialDriveWheelPositions &wheelDeltas) const override |
Performs forward kinematics to return the resulting Twist2d from the given wheel deltas. More... | |
virtual ChassisSpeeds | ToChassisSpeeds (const DifferentialDriveWheelSpeeds &wheelSpeeds) const=0 |
Performs forward kinematics to return the resulting chassis speed from the wheel speeds. More... | |
virtual DifferentialDriveWheelSpeeds | ToWheelSpeeds (const ChassisSpeeds &chassisSpeeds) const=0 |
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity. More... | |
virtual Twist2d | ToTwist2d (const DifferentialDriveWheelPositions &wheelDeltas) const=0 |
Performs forward kinematics to return the resulting Twist2d from the given wheel deltas. More... | |
Public Attributes | |
units::meter_t | 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 speed into left and right velocity components whereas forward kinematics converts left and right component velocities into a linear and angular chassis speed.
|
inlineexplicit |
Constructs a differential drive kinematics object.
trackWidth | The 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. |
|
inlineconstexproverridevirtual |
Returns a chassis speed from left and right component velocities using forward kinematics.
wheelSpeeds | The left and right velocities. |
Implements frc::Kinematics< DifferentialDriveWheelSpeeds, DifferentialDriveWheelPositions >.
|
inlineoverridevirtual |
Performs forward kinematics to return the resulting Twist2d from the given wheel deltas.
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.
wheelDeltas | The distances driven by each wheel. |
Implements frc::Kinematics< DifferentialDriveWheelSpeeds, DifferentialDriveWheelPositions >.
|
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 |
Returns left and right component velocities from a chassis speed using inverse kinematics.
chassisSpeeds | The linear and angular (dx and dtheta) components that represent the chassis' speed. |
Implements frc::Kinematics< DifferentialDriveWheelSpeeds, DifferentialDriveWheelPositions >.
units::meter_t frc::DifferentialDriveKinematics::trackWidth |