WPILibC++ 2023.4.3-108-ge5452e3
|
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel speeds. More...
#include <frc/kinematics/Kinematics.h>
Public Member Functions | |
virtual ChassisSpeeds | ToChassisSpeeds (const WheelSpeeds &wheelSpeeds) const =0 |
Performs forward kinematics to return the resulting chassis speed from the wheel speeds. More... | |
virtual WheelSpeeds | ToWheelSpeeds (const ChassisSpeeds &chassisSpeeds) const =0 |
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity. More... | |
virtual Twist2d | ToTwist2d (const WheelPositions &wheelDeltas) const =0 |
Performs forward kinematics to return the resulting Twist2d from the given wheel deltas. More... | |
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel speeds.
Robot code should not use this directly- Instead, use the particular type for your drivetrain (e.g., DifferentialDriveKinematics).
Inverse kinematics converts a desired chassis speed into wheel speeds whereas forward kinematics converts wheel speeds into chassis speed.
|
pure virtual |
Performs forward kinematics to return the resulting chassis speed from the wheel speeds.
This method is often used for odometry – determining the robot's position on the field using data from the real-world speed of each wheel on the robot.
wheelSpeeds | The speeds of the wheels. |
Implemented in frc::DifferentialDriveKinematics, and frc::MecanumDriveKinematics.
|
pure virtual |
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. |
Implemented in frc::DifferentialDriveKinematics, frc::MecanumDriveKinematics, and frc::SwerveDriveKinematics< NumModules >.
|
pure virtual |
Performs inverse kinematics to return the wheel speeds from a desired chassis velocity.
This method is often used to convert joystick values into wheel speeds.
chassisSpeeds | The desired chassis speed. |
Implemented in frc::DifferentialDriveKinematics, frc::MecanumDriveKinematics, and frc::SwerveDriveKinematics< NumModules >.