Switch

A generic servo controller subsystem that may be used to hold two positions and to control movements in between these setpoints. This is similar to a DualServos subsystem but only controls a singular servo.

Author

Lucas Bubner, 2024

Since

5.1.0

Constructors

Link copied to clipboard
constructor(@Nullable servo: Servo, openPosition: Double, closePosition: Double)
Constructs a new Switch.
constructor(@Nullable servo: Servo)
Constructs a new Switch with default open and close positions.

Types

Link copied to clipboard
open inner class Tasks
Tasks for Switch, access with tasks.

Properties

Link copied to clipboard
open val target: Double
Link copied to clipboard
Tasks for Switch.

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 close(): Switch
Close the switch.
Link copied to clipboard
open fun getPosition(): Double
Link copied to clipboard
open fun isClosed(): Boolean
Query whether the switch is closed.
Link copied to clipboard
open fun isOpen(): Boolean
Query whether the switch is open.
Link copied to clipboard
open fun open(): Switch
Open the switch.
Link copied to clipboard
protected open fun periodic()
To be updated periodically on every hardware loop.
Link copied to clipboard
open fun setPosition(position: Double): Switch
Set a custom position that is clipped between the closed and open bounds.
Link copied to clipboard
Set a custom position that is not affected by the closed and open bounds.
Link copied to clipboard
open fun toggle(): Switch
Toggles the switch between the open and closed positions, moving to the closest position if the servo is not in one of the two open or closed positions.
Link copied to clipboard
open fun withBounds(openPosition: Double, closePosition: Double): Switch
Set the new bounds this servo should respect for opened and closed positions.
Link copied to clipboard
open fun withClosedBound(closePosition: Double): Switch
Set the new closed position.
Link copied to clipboard
open fun withOpenBound(openPosition: Double): Switch
Set the new open position.

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 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 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
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.