SwerveDrive6KinematicsBase
- class wpimath.SwerveDrive6KinematicsBase
Bases:
pybind11_objectHelper 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.
- interpolate(start: Tuple[wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition], end: Tuple[wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition], t: SupportsFloat | SupportsIndex) Tuple[wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition]
Performs interpolation between two values.
- Parameters:
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].
- Returns:
The interpolated value.
- toChassisAccelerations(wheelAccelerations: Tuple[wpimath._wpimath.SwerveModuleAcceleration, wpimath._wpimath.SwerveModuleAcceleration, wpimath._wpimath.SwerveModuleAcceleration, wpimath._wpimath.SwerveModuleAcceleration, wpimath._wpimath.SwerveModuleAcceleration, wpimath._wpimath.SwerveModuleAcceleration]) wpimath._wpimath.ChassisAccelerations
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.
- Parameters:
wheelAccelerations – The accelerations of the wheels.
- Returns:
The chassis accelerations.
- toChassisVelocities(wheelVelocities: Tuple[wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity]) wpimath._wpimath.ChassisVelocities
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.
- Parameters:
wheelVelocities – The velocities of the wheels.
- Returns:
The chassis velocity.
- toTwist2d(start: Tuple[wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition], end: Tuple[wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition, wpimath._wpimath.SwerveModulePosition]) wpimath._wpimath.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.
- toWheelAccelerations(chassisAccelerations: wpimath._wpimath.ChassisAccelerations) Tuple[wpimath._wpimath.SwerveModuleAcceleration, wpimath._wpimath.SwerveModuleAcceleration, wpimath._wpimath.SwerveModuleAcceleration, wpimath._wpimath.SwerveModuleAcceleration, wpimath._wpimath.SwerveModuleAcceleration, wpimath._wpimath.SwerveModuleAcceleration]
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.
- Parameters:
chassisAccelerations – The desired chassis accelerations.
- Returns:
The wheel accelerations.
- toWheelVelocities(chassisVelocities: wpimath._wpimath.ChassisVelocities) Tuple[wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity, wpimath._wpimath.SwerveModuleVelocity]
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.
- Parameters:
chassisVelocities – The desired chassis velocity.
- Returns:
The wheel velocities.