Package edu.wpi.first.math.kinematics
Class DifferentialDriveKinematics
java.lang.Object
edu.wpi.first.math.kinematics.DifferentialDriveKinematics
- All Implemented Interfaces:
Interpolator<DifferentialDriveWheelPositions>
,Kinematics<DifferentialDriveWheelSpeeds,
,DifferentialDriveWheelPositions> ProtobufSerializable
,StructSerializable
,WPISerializable
public class DifferentialDriveKinematics
extends Object
implements Kinematics<DifferentialDriveWheelSpeeds,DifferentialDriveWheelPositions>, ProtobufSerializable, StructSerializable
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.
-
Field Summary
Modifier and TypeFieldDescriptionstatic final DifferentialDriveKinematicsProto
DifferentialDriveKinematics protobuf for serialization.static final DifferentialDriveKinematicsStruct
DifferentialDriveKinematics struct for serialization.final double
Differential drive trackwidth. -
Constructor Summary
ConstructorDescriptionDifferentialDriveKinematics
(double trackWidthMeters) Constructs a differential drive kinematics object.DifferentialDriveKinematics
(Distance trackWidth) Constructs a differential drive kinematics object. -
Method Summary
Modifier and TypeMethodDescriptioncopy
(DifferentialDriveWheelPositions positions) Returns a copy of the wheel positions object.void
copyInto
(DifferentialDriveWheelPositions positions, DifferentialDriveWheelPositions output) Copies the value of the wheel positions object into the output.interpolate
(DifferentialDriveWheelPositions startValue, DifferentialDriveWheelPositions endValue, double t) Perform interpolation between two values.toChassisSpeeds
(DifferentialDriveWheelSpeeds wheelSpeeds) Returns a chassis speed from left and right component velocities using forward kinematics.toTwist2d
(double leftDistanceMeters, double rightDistanceMeters) Performs forward kinematics to return the resulting Twist2d from the given left and right side distance deltas.Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions.toWheelSpeeds
(ChassisSpeeds chassisSpeeds) Returns left and right component velocities from a chassis speed using inverse kinematics.
-
Field Details
-
trackWidthMeters
Differential drive trackwidth. -
proto
DifferentialDriveKinematics protobuf for serialization. -
struct
DifferentialDriveKinematics struct for serialization.
-
-
Constructor Details
-
DifferentialDriveKinematics
Constructs a differential drive kinematics object.- Parameters:
trackWidthMeters
- 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.
-
DifferentialDriveKinematics
Constructs a differential drive kinematics object.- Parameters:
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.
-
-
Method Details
-
toChassisSpeeds
Returns a chassis speed from left and right component velocities using forward kinematics.- Specified by:
toChassisSpeeds
in interfaceKinematics<DifferentialDriveWheelSpeeds,
DifferentialDriveWheelPositions> - Parameters:
wheelSpeeds
- The left and right velocities.- Returns:
- The chassis speed.
-
toWheelSpeeds
Returns left and right component velocities from a chassis speed using inverse kinematics.- Specified by:
toWheelSpeeds
in interfaceKinematics<DifferentialDriveWheelSpeeds,
DifferentialDriveWheelPositions> - Parameters:
chassisSpeeds
- The linear and angular (dx and dtheta) components that represent the chassis' speed.- Returns:
- The left and right velocities.
-
toTwist2d
public Twist2d toTwist2d(DifferentialDriveWheelPositions start, DifferentialDriveWheelPositions end) Description copied from interface:Kinematics
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.- Specified by:
toTwist2d
in interfaceKinematics<DifferentialDriveWheelSpeeds,
DifferentialDriveWheelPositions> - Parameters:
start
- The starting distances driven by the wheels.end
- The ending distances driven by the wheels.- Returns:
- The resulting Twist2d in the robot's movement.
-
toTwist2d
Performs forward kinematics to return the resulting Twist2d from the given left and right side distance 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.- Parameters:
leftDistanceMeters
- The distance measured by the left side encoder.rightDistanceMeters
- The distance measured by the right side encoder.- Returns:
- The resulting Twist2d.
-
copy
Description copied from interface:Kinematics
Returns a copy of the wheel positions object.- Specified by:
copy
in interfaceKinematics<DifferentialDriveWheelSpeeds,
DifferentialDriveWheelPositions> - Parameters:
positions
- The wheel positions object to copy.- Returns:
- A copy.
-
copyInto
public void copyInto(DifferentialDriveWheelPositions positions, DifferentialDriveWheelPositions output) Description copied from interface:Kinematics
Copies the value of the wheel positions object into the output.- Specified by:
copyInto
in interfaceKinematics<DifferentialDriveWheelSpeeds,
DifferentialDriveWheelPositions> - Parameters:
positions
- The wheel positions object to copy. Will not be modified.output
- The output variable of the copy operation. Will have the same value as the positions object after the call.
-
interpolate
public DifferentialDriveWheelPositions interpolate(DifferentialDriveWheelPositions startValue, DifferentialDriveWheelPositions endValue, double t) Description copied from interface:Interpolator
Perform interpolation between two values.- Specified by:
interpolate
in interfaceInterpolator<DifferentialDriveWheelPositions>
- Parameters:
startValue
- The value to start at.endValue
- The value to end at.t
- How far between the two values to interpolate. This should be bounded to [0, 1].- Returns:
- The interpolated value.
-