22template <
typename WheelSpeeds,
typename WheelPositions>
35 const WheelSpeeds& wheelSpeeds)
const = 0;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition: Kinematics.h:23
virtual Twist2d ToTwist2d(const WheelPositions &start, const WheelPositions &end) const =0
Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions.
virtual ChassisSpeeds ToChassisSpeeds(const WheelSpeeds &wheelSpeeds) const =0
Performs forward kinematics to return the resulting chassis speed from the wheel speeds.
virtual WheelSpeeds ToWheelSpeeds(const ChassisSpeeds &chassisSpeeds) const =0
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity.
Definition: WheelPositions.h:11
Definition: AprilTagPoseEstimator.h:15
Represents the speed of a robot chassis.
Definition: ChassisSpeeds.h:25
A change in distance along a 2D arc since the last pose update.
Definition: Twist2d.h:21