SimpleMecanumDrive

A minimal Mecanum drive implementation that does not include a RoadRunner configuration. This is useful for implementations where localizer information is not required at all times, such as in TeleOp, and RoadRunner features are not required to be active.

Author

Lucas Bubner, 2024

Since

6.0.0

Constructors

Link copied to clipboard
constructor(@Nullable leftFront: DcMotor, @Nullable leftBack: DcMotor, @Nullable rightBack: DcMotor, @Nullable rightFront: DcMotor)
Construct a new SimpleMecanumDrive.

Types

Link copied to clipboard
Mecanum control prioritisation.

Properties

Link copied to clipboard
Link copied to clipboard
open var speedR: Double
Counter-clockwise rotational speed.
Link copied to clipboard
open var speedX: Double
Forward speed.
Link copied to clipboard
open var speedY: Double
Left speed.

Inherited properties

Link copied to clipboard
open var currentTask: Task
Link copied to clipboard
protected open var name: String
Reference to the unmodified name of this subsystem.
Link copied to clipboard
Get a reference to the currently running BunyipsOpMode.

Functions

Link copied to clipboard
open fun getPose(): Pose2d
Calculate the accumulated pose from an internal localizer.
Link copied to clipboard
open fun getVelocity(): PoseVelocity2d
Calculate the first derivative of the accumulated pose from an internal localizer.
Link copied to clipboard
protected open fun onDisable()
User callback that runs once when this subsystem is disabled by a call to disable or by an assertion failure.
Link copied to clipboard
protected open fun periodic()
To be updated periodically on every hardware loop.
Link copied to clipboard
open fun setPose(@NonNull newPose: Pose2d)
Reset the accumulated pose estimate to this pose.
Link copied to clipboard
open fun setPower(@NonNull target: PoseVelocity2d)
Set the current commanded state of the robot in the Robot Coordinate System.
Link copied to clipboard
Link copied to clipboard
Swap the priority of the drive system.
Link copied to clipboard
Set the pose accumulator this drive instance should use.
Link copied to clipboard
Set the localizer for this drive.

Inherited functions

Link copied to clipboard
protected fun assertParamsNotNull(@NonNull parameters: Array<Any>): Boolean
Utility function to run NullSafety.assertComponentArgs() on the given parameters, usually on the motors/hardware/critical objects passed into the constructor.
Link copied to clipboard
Cancel the current task immediately and return to the default task, if available.
Link copied to clipboard
infix fun BunyipsSubsystem.default(defaultTask: Task)

Default task setter extension for BunyipsSubsystem to set the default task of a subsystem.

Link copied to clipboard
protected fun delegate(@NonNull child: BunyipsSubsystem)
Call to delegate the update of this subsystem, usually a component of another subsystem, to this subsystem.
Link copied to clipboard
fun disable()
Prevent a subsystem from running.
Link copied to clipboard
fun enable()
Re-enable a subsystem if it was previously disabled via a disable() call.
Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
Determine if the subsystem is idle, meaning an IdleTask is running.
Link copied to clipboard
protected open fun onEnable()
User callback that runs once when this subsystem is enabled by a call to enable or the first active call to periodic.
Link copied to clipboard
protected fun opMode(@NonNull ifRunning: Consumer<BunyipsOpMode>)
Null check consumer for the opMode field which will no-op the given consumer if an active BunyipsOpMode is not present (i.e.
Link copied to clipboard
protected fun require(@Nullable nullableOpMode: BunyipsOpMode): BunyipsOpMode
Null assertion for the opMode field which throws a NullPointerException if an active BunyipsOpMode is not present (i.e.
Link copied to clipboard
open fun resetForOpMode()
Reset stored static instances of BunyipsSubsystem.
Link copied to clipboard
fun setDefaultTask(@NonNull defaultTask: Task)
Set the default task for this subsystem, which will be run when no other task is running.
Link copied to clipboard
Set the current task to the given task, overriding any current task.
Link copied to clipboard
open fun setPose(@NonNull vector: Vector2d, @NonNull vectorUnit: Distance, heading: Double, @NonNull headingUnit: Angle)
Reset the accumulated pose estimate to this pose.
Link copied to clipboard
fun startThread(@NonNull loopSleepDuration: Measure<Time>)
Call to delegate all updates of this subsystem to a thread that will begin execution on this method call.
Link copied to clipboard
Call to stop delegating updates of this subsystem to a thread.
Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
fun update()
Update the subsystem and run the current task, if tasks are not set up this will just call periodic.
Link copied to clipboard
open fun updateAll()
Update all instances of BunyipsSubsystem that has been constructed since the last clearing.
Link copied to clipboard
fun <T : BunyipsSubsystem?> withName(@NonNull subsystemName: String): T
Set the name of this subsystem that will be used in telemetry and references.