abstract class MecanumDrive : Drive
This class provides the basic functionality of a mecanum drive using MecanumKinematics.
trackWidth
- lateral distance between pairs of wheels on different sides of the robot
wheelBase
- distance between pairs of wheels on the same side of the robot
class MecanumLocalizer : Localizer
Default localizer for mecanum drives based on the drive encoders and (optionally) a heading sensor. |
MecanumDrive(trackWidth: Double, wheelBase: Double = trackWidth, clock: NanoClock = NanoClock.system())
This class provides the basic functionality of a mecanum drive using MecanumKinematics. |
open var localizer: Localizer
Localizer used to determine the evolution of poseEstimate. |
|
val trackWidth: Double
lateral distance between pairs of wheels on different sides of the robot |
|
val wheelBase: Double
distance between pairs of wheels on the same side of the robot |
var poseEstimate: Pose2d
The robot's current pose estimate. |
abstract fun getExternalHeading(): Double
Returns the robot's heading in radians as measured by an external sensor (e.g., IMU, gyroscope). Heading is measured counter-clockwise from the x-axis. |
|
abstract fun getWheelPositions(): List<Double>
Returns the positions of the wheels in linear distance units. Positions should exactly match the ordering in setMotorPowers. |
|
abstract fun setMotorPowers(frontLeft: Double, rearLeft: Double, rearRight: Double, frontRight: Double): Unit
Sets the following motor powers (normalized voltages). All arguments are on the interval |
|
open fun setVelocity(poseVelocity: Pose2d): Unit
Sets the poseVelocity of the robot. |
fun updatePoseEstimate(): Unit
Updates poseEstimate with the most recent positional change. |