Vision

Component wrapper to support the v8.2+ SDK's included libraries for Camera operation. This is an expansible system to run Processor components using the VisionPortal.

You will pass your own processors that you manage, and Vision will handle the data collection.

Vision is not a traditional subsystem where updates are propagated on the main thread, as processing is on another thread and updates are managed at the discretion of the VisionPortal. Once set up, Vision will automatically manage the camera stream and defined processor updates. All you will need to do is collect the data from the processors and use it in your OpMode. The update() method in this subsystem will simply add telemetry of the VisionPortal's status.

Author

Lucas Bubner, 2023

Since

1.0.0-pre

Constructors

Link copied to clipboard
constructor(@Nullable camera: CameraName, cameraWidth: Int, cameraHeight: Int)
Create a new Vision instance with the specified camera and resolution.
constructor(@Nullable camera: CameraName)
Create a new Vision instance with the specified camera and default resolution.

Properties

Link copied to clipboard
Default camera height resolution to use.
Link copied to clipboard
Default camera width resolution to use.
Link copied to clipboard
open var raw: Vision.Raw
A built-in raw feed Processor that will do nothing but provide the raw camera feed.
Link copied to clipboard
@get:NonNull
open val visionPortal: VisionPortal

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 flip(): Vision
Flip all processor feeds horizontally and vertically (180deg, useful if your camera is mounted upside-down).
open fun flip(@NonNull attachedProcessors: Array<Processor>): Vision
Flip a processor feed horizontally and vertically (rotate 180deg).
Link copied to clipboard
Get the culmination of data from all attached processors.
Link copied to clipboard
Get all VisionProcessors attached to the VisionPortal (read-only).
Link copied to clipboard
open fun getFps(): Double
Get the current Frames Per Second of the VisionPortal.
Link copied to clipboard
open fun getStatus(): VisionPortal.CameraState
Get the current status of the camera attached to the VisionPortal.
Link copied to clipboard
open fun init(@NonNull newProcessors: Array<Processor>): Vision
Initialises the Vision class with the specified processors.
Link copied to clipboard
Returns the state of VisionPortal.
Link copied to clipboard
protected open fun periodic()
Optional telemetry for subsystem attachment
Link copied to clipboard
open fun setPreview(@NonNull processor: Processor)
open fun setPreview(@NonNull processorName: String)
Set the processor to display on FtcDashboard/DS from startPreview().
Link copied to clipboard
open fun start(@NonNull attachedProcessors: Array<Processor>): Vision
Start desired processors.
Link copied to clipboard
open fun startPreview()
Start the VisionSender thread to send all processor data to FtcDashboard/DS with dynamic switching.
Link copied to clipboard
open fun stop(): Vision
Stop all processors and pause the camera stream (Level 3).
open fun stop(@NonNull attachedProcessors: Array<Processor>): Vision
Stop desired processors (Level 2).
Link copied to clipboard
open fun stopAllPreviews()
Stop the VisionSender thread to stop sending all processor data to FtcDashboard/DS.
Link copied to clipboard
Terminate all VisionPortal resources (Level 4).

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.