abstract class MecanumDrive : Drive
(source)
This class provides the basic functionality of a mecanum drive using MecanumKinematics.
kStatic
- additive constant feedforward
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
lateralMultiplier
- lateral multiplier
MecanumLocalizer |
Default localizer for mecanum drives based on the drive encoders and (optionally) a heading sensor. class MecanumLocalizer : Localizer |
<init> |
This class provides the basic functionality of a mecanum drive using MecanumKinematics. MecanumDrive(kV: Double, kA: Double, kStatic: Double, trackWidth: Double, wheelBase: Double = trackWidth, lateralMultiplier: Double = 1.0) |
localizer |
Localizer used to determine the evolution of poseEstimate. open var localizer: Localizer |
getWheelPositions |
Returns the positions of the wheels in linear distance units. Positions should exactly match the ordering in setMotorPowers. abstract fun getWheelPositions(): List<Double> |
getWheelVelocities |
Returns the velocities of the wheels in linear distance units. Positions should exactly match the ordering in setMotorPowers. open fun getWheelVelocities(): List<Double>? |
setDrivePower |
Sets the current commanded drive state of the robot. Feedforward is not applied to drivePower. open fun setDrivePower(drivePower: Pose2d): Unit |
setDriveSignal |
Sets the current commanded drive state of the robot. Feedforward is applied to driveSignal before it reaches the motors. open fun setDriveSignal(driveSignal: DriveSignal): Unit |
setMotorPowers |
Sets the following motor powers (normalized voltages). All arguments are on the interval abstract fun setMotorPowers(frontLeft: Double, rearLeft: Double, rearRight: Double, frontRight: Double): Unit |