DifferentialDriveKinematicsBase

class wpimath.kinematics.DifferentialDriveKinematicsBase

Bases: pybind11_object

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.

toChassisSpeeds(wheelSpeeds: wpimath.kinematics._kinematics.DifferentialDriveWheelSpeeds) wpimath.kinematics._kinematics.ChassisSpeeds

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.

Parameters:

wheelSpeeds – The speeds of the wheels.

Returns:

The chassis speed.

toTwist2d(start: wpimath.kinematics._kinematics.DifferentialDriveWheelPositions, end: wpimath.kinematics._kinematics.DifferentialDriveWheelPositions) wpimath.geometry._geometry.Twist2d

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.

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.

toWheelSpeeds(chassisSpeeds: wpimath.kinematics._kinematics.ChassisSpeeds) wpimath.kinematics._kinematics.DifferentialDriveWheelSpeeds

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.

Parameters:

chassisSpeeds – The desired chassis speed.

Returns:

The wheel speeds.