Creating your first Attachment
Rapidly develop and test new attachments for your robot with the Volt library.
What is an Attachment?
An Attachment is anything that has a function on the Robot. This could be a motor, a servo, a sensor, or anything else that can be controlled. Attachments are used to control the Robot and interact with the environment.
There should be one Attachment per “interaction” your Robot can perform.
Creating an Attachment
Create a new Kotlin class in TeamCode/src/main/kotlin/org/firstinspires/ftc/teamcode/attachment
that inherits the Attachment class.
The Attachment class contains:
- A list of motors
- A list of servos
- A list of continuous rotation servos
- A boolean that is true when the attachment’s ControlAction is running
- The function
update(telemetry: Telemetry)
that is called every tick - The function
stop()
that is called when the robot is stopped
class Example : Attachment() { init { // Initialize }
override fun update(telemetry: Telemetry) { // Update }}
(Coming Soon)
Add a motor
Defining the motor
Add the parameters hardwareMap
and name
for initializing a motor. Create a new DcMotor
.
class Example(hardwareMap: HardwareMap, name: String) : Attachment() { val motor = hardwareMap.dcMotor[name]
init { // Initialize }
override fun update(telemetry: Telemetry) { // Update }}
(Coming Soon)
Setting up the motor
Set the motor’s mode to DcMotor.RunMode.RUN_USING_ENCODER
to use the motor’s built-in encoder.
Set the motor’s zero-power behavior
to DcMotor.ZeroPowerBehavior.BRAKE
so the motor holds its position when the motor’s power is set to 0.0
.
Add the motor to the motors
list
so that it can be managed by the Attachment class.
class Example(hardwareMap: HardwareMap, name: String) : Attachment() { val motor = hardwareMap.dcMotor[name]
init { // Set mode motor.mode = DcMotorSimple.RunMode.RUN_USING_ENCODER
// Set zero power behavior motor.zeroPowerBehavior = DcMotor.ZeroPowerBehavior.BRAKE
// Add to list motors = listOf(motor) }
override fun update(telemetry: Telemetry) { // Update }}
(Coming Soon)
Add logic
Setup the ControlAction
Create a new inner class
called Control
that inherits ControlAction.
This class will be used to define the Attachment’s logic.
The ControlAction class contains:
- A function called
init()
that is called when the action is triggered - A function called
update(packet: TelemetryPacket): Boolean
that is called while the action is running and returns whether the action is complete - A function called
handleStop()
that is called when the action is stopped
inner class Control : ControlAction() { override fun init() { // Start }
override fun update(packet: TelemetryPacket): Boolean { // Logic return true }
override fun handleStop() { // End }}
(Coming Soon)
Control the motor
Add parameters for a power
and a targetPosition
. Create an instance variable for whether the motor is reversing
.
Set the motor’s power in the init()
function.
Determine whether the motor has reached the targetPosition
. Stop the motor in the handleStop()
function.
inner class Control( private val power: Double, private val targetPosition: Int) : ControlAction() { private var reversing = false
override fun init() { // Determine reversing reversing = targetPosition < motor.currentPosition
// Set power motor.power = if (reversing) -power else power }
override fun update(packet: TelemetryPacket): Boolean { // Get position val currentPosition = motor.currentPosition
// Determine if at target position if ((currentPosition < targetPosition) xor reversing) return false return true }
override fun handleStop() { // Stop the motor motor.power = 0.0 }}
(Coming Soon)
Add a callable action
Create a function called goTo(power: Double, position: Int)
that returns a new Action
.
fun goTo(power: Double, position: Int): Action { // Return Control return Control(power, position)}
(Coming Soon)
Log the position of the motor
Modify the update(telemetry: Telemetry)
function to log the position of motor
.
override fun update(telemetry: Telemetry) { // Log motor position telemetry.addLine("==== EXAMPLE ====") telemetry.addData("Position", motor.currentPosition) telemetry.addLine()}
(Coming Soon)
Result
package org.firstinspires.ftc.teamcode.attachment
import com.acmerobotics.dashboard.telemetry.TelemetryPacketimport com.acmerobotics.roadrunner.Actionimport dev.kingssack.volt.attachment.Attachmentimport com.qualcomm.robotcore.hardware.DcMotorimport com.qualcomm.robotcore.hardware.DcMotorSimpleimport com.qualcomm.robotcore.hardware.HardwareMapimport org.firstinspires.ftc.robotcore.external.Telemetry
class Example(hardwareMap: HardwareMap, name: String) : Attachment() { val motor = hardwareMap.dcMotor[name]
init { motor.mode = DcMotorSimple.RunMode.RUN_USING_ENCODER motor.zeroPowerBehavior = DcMotor.ZeroPowerBehavior.BRAKE motors = listOf(motor) }
inner class Control( private val power: Double, private val targetPosition: Int ) : ControlAction() { private var reversing = false
override fun init() { reversing = targetPosition < motor.currentPosition motor.power = if (reversing) -power else power }
override fun update(packet: TelemetryPacket): Boolean { val currentPosition = motor.currentPosition if ((currentPosition < targetPosition) xor reversing) return false return true }
override fun handleStop() { motor.power = 0.0 } } fun goTo(power: Double, position: Int): Action { return Control(power, position) }
override fun update(telemetry: Telemetry) { telemetry.addLine("==== EXAMPLE ====") telemetry.addData("Position", motor.currentPosition) telemetry.addLine() }}
(Coming Soon)