22template <
typename WheelSpeeds,
typename WheelPositions>
23 requires std::copy_constructible<WheelPositions> &&
24 std::assignable_from<WheelPositions&, const WheelPositions&>
39 const WheelSpeeds& wheelSpeeds) const = 0;
49 virtual WheelSpeeds ToWheelSpeeds(
63 virtual
Twist2d ToTwist2d(const WheelPositions& start,
64 const WheelPositions& end) const = 0;
75 virtual WheelPositions Interpolate(const WheelPositions& start,
76 const WheelPositions& end,
#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:25
virtual ~Kinematics() noexcept=default
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:22