![]() |
WPILibC++ 2027.0.0-alpha-4
|
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel velocities. More...
#include <wpi/math/kinematics/Kinematics.hpp>
Public Member Functions | |
| virtual | ~Kinematics () noexcept=default |
| virtual ChassisVelocities | ToChassisVelocities (const WheelVelocities &wheelVelocities) const =0 |
| Performs forward kinematics to return the resulting chassis velocity from the wheel velocities. | |
| virtual WheelVelocities | ToWheelVelocities (const ChassisVelocities &chassisVelocities) const =0 |
| Performs inverse kinematics to return the wheel velocities from a desired chassis velocity. | |
| 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 WheelPositions | Interpolate (const WheelPositions &start, const WheelPositions &end, double t) const =0 |
| Performs interpolation between two values. | |
| virtual ChassisAccelerations | ToChassisAccelerations (const WheelAccelerations &wheelAccelerations) const =0 |
| Performs forward kinematics to return the resulting chassis accelerations from the wheel accelerations. | |
| virtual WheelAccelerations | ToWheelAccelerations (const ChassisAccelerations &chassisAccelerations) const =0 |
| Performs inverse kinematics to return the wheel accelerations from a desired chassis acceleration. | |
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel velocities.
Robot code should not use this directly- Instead, use the particular type for your drivetrain (e.g., DifferentialDriveKinematics).
Inverse kinematics converts a desired chassis velocity into wheel velocities whereas forward kinematics converts wheel velocities into chassis velocity.
|
virtualdefaultnoexcept |
|
pure virtual |
Performs interpolation between two values.
| start | The value to start at. |
| end | The value to end at. |
| t | How far between the two values to interpolate. This should be bounded to [0, 1]. |
Implemented in wpi::math::DifferentialDriveKinematics, wpi::math::MecanumDriveKinematics, and wpi::math::SwerveDriveKinematics< NumModules >.
|
pure virtual |
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.
| wheelAccelerations | The accelerations of the wheels. |
Implemented in wpi::math::DifferentialDriveKinematics, wpi::math::MecanumDriveKinematics, and wpi::math::SwerveDriveKinematics< NumModules >.
|
pure virtual |
Performs forward kinematics to return the resulting chassis velocity from the wheel velocities.
This method is often used for odometry – determining the robot's position on the field using data from the real-world velocity of each wheel on the robot.
| wheelVelocities | The velocities of the wheels. |
Implemented in wpi::math::DifferentialDriveKinematics, wpi::math::MecanumDriveKinematics, and wpi::math::SwerveDriveKinematics< NumModules >.
|
pure virtual |
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.
| start | The starting distances driven by the wheels. |
| end | The ending distances driven by the wheels. |
Implemented in wpi::math::DifferentialDriveKinematics, wpi::math::MecanumDriveKinematics, and wpi::math::SwerveDriveKinematics< NumModules >.
|
pure virtual |
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.
| chassisAccelerations | The desired chassis accelerations. |
Implemented in wpi::math::DifferentialDriveKinematics, wpi::math::MecanumDriveKinematics, and wpi::math::SwerveDriveKinematics< NumModules >.
|
pure virtual |
Performs inverse kinematics to return the wheel velocities from a desired chassis velocity.
This method is often used to convert joystick values into wheel velocities.
| chassisVelocities | The desired chassis velocity. |
Implemented in wpi::math::DifferentialDriveKinematics, wpi::math::MecanumDriveKinematics, and wpi::math::SwerveDriveKinematics< NumModules >.