MecanumDriveWithRR

class MecanumDriveWithRR(hardwareMap: HardwareMap, var pose: Pose2d = Pose2d(Vector2d(0.0, 0.0), 0.0), params: MecanumDriveWithRR.DriveParams = DriveParams()) : MecanumDrivetrain

A mecanum drivetrain integrated with the RoadRunner library.

Parameters

hardwareMap

the hardware map

params

the drive parameters

Constructors

Link copied to clipboard
constructor(hardwareMap: HardwareMap, pose: Pose2d = Pose2d(Vector2d(0.0, 0.0), 0.0), params: MecanumDriveWithRR.DriveParams = DriveParams())

Types

Link copied to clipboard
inner class DriveLocalizer(var pose: Pose2d) : Localizer
Link copied to clipboard
class DriveParams(val logoFacingDirection: RevHubOrientationOnRobot.LogoFacingDirection = LogoFacingDirection.UP, val usbFacingDirection: RevHubOrientationOnRobot.UsbFacingDirection = UsbFacingDirection.FORWARD, val inPerTick: Double = 1.0, val lateralInPerTick: Double = inPerTick, val trackWidthTicks: Double = 0.0, val kS: Double = 0.0, val kV: Double = 0.0, val kA: Double = 0.0, val maxWheelVel: Double = 50.0, val minProfileAccel: Double = -30.0, val maxProfileAccel: Double = 50.0, val maxAngVel: Double = Math.PI, val maxAngAccel: Double = Math.PI, val axialGain: Double = 0.0, val lateralGain: Double = 0.0, val headingGain: Double = 0.0, val axialVelGain: Double = 0.0, val lateralVelGain: Double = 0.0, val headingVelGain: Double = 0.0)

Parameters for the robot's mecanum drive.

Link copied to clipboard
inner class FollowTrajectoryAction(timeTrajectory: TimeTrajectory) : Action
Link copied to clipboard
inner class TurnAction(turn: TimeTurn) : Action

Properties

Link copied to clipboard
val lazyImu: LazyHardwareMapImu

the lazy IMU

Link copied to clipboard
val leftBack: DcMotorEx

the left back motor

Link copied to clipboard
val leftFront: DcMotorEx

the left front motor

Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
var pose: Pose2d

the pose

Link copied to clipboard
val rightBack: DcMotorEx

the right back motor

Link copied to clipboard
val rightFront: DcMotorEx

the right front motor

Link copied to clipboard
val state: StateFlow<AttachmentState>
Link copied to clipboard
val voltageSensor: VoltageSensor

the voltage sensor

Functions

Link copied to clipboard
fun driveActionBuilder(beginPose: Pose2d): TrajectoryActionBuilder

Create a new trajectory action builder.

Link copied to clipboard

Checks if the attachment is currently busy (Running).

Link copied to clipboard

Checks if the attachment is currently in a faulted state.

Link copied to clipboard

Ensures the attachment is in the Idle state, throwing an exception if not.

Link copied to clipboard
open override fun setDrivePowers(powers: PoseVelocity2d)

Set the drive powers.

Link copied to clipboard
open fun stop()

Stops the attachment and resets its state to Idle.

Link copied to clipboard
fun strafeTo(from: Pose2d, to: Vector2d): Action

Strafe from from to to.

Link copied to clipboard
fun strafeToLinearHeading(from: Pose2d, to: Pose2d): Action

Strafe from from to to.

Link copied to clipboard
fun trajectory(from: Pose2d = localizer.pose, block: TrajectoryActionBuilder.() -> TrajectoryActionBuilder): Action

Build a trajectory action.

Link copied to clipboard
fun turn(from: Pose2d, degrees: Degrees): Action

Turn a certain number of degrees.

fun turn(from: Pose2d, radians: Radians): Action

Turn a certain number of radians.

Link copied to clipboard
fun turnTo(from: Pose2d, to: Degrees): Action
fun turnTo(from: Pose2d, to: Radians): Action

Turn from from to to.

Link copied to clipboard
context(telemetry: Telemetry)
open override fun update()

Updates the telemetry with the current state of the attachment.