Skip to content
This repository has been archived by the owner on Jan 29, 2025. It is now read-only.

Commit

Permalink
feat: drone redesign
Browse files Browse the repository at this point in the history
  • Loading branch information
BD103 committed Feb 19, 2024
1 parent 7b47f1f commit de49a83
Show file tree
Hide file tree
Showing 2 changed files with 17 additions and 13 deletions.
24 changes: 13 additions & 11 deletions TeamCode/src/main/java/org/firstinspires/ftc/teamcode/api/Drone.kt
Original file line number Diff line number Diff line change
@@ -1,30 +1,32 @@
package org.firstinspires.ftc.teamcode.api

import com.qualcomm.robotcore.eventloop.opmode.OpMode
import com.qualcomm.robotcore.hardware.Servo
import org.firstinspires.ftc.teamcode.utils.RobotConfig
import com.qualcomm.robotcore.hardware.DcMotor
import com.qualcomm.robotcore.hardware.DcMotorSimple

/**
* An API to control the drone launcher.
*/
object Drone : API() {
private lateinit var pin: Servo
private lateinit var droneLeft: DcMotor
private lateinit var droneRight: DcMotor

override fun init(opMode: OpMode) {
super.init(opMode)

this.pin = this.opMode.hardwareMap.get(Servo::class.java, "pin")
this.droneLeft = this.opMode.hardwareMap.get(DcMotor::class.java, "droneLeft")
this.droneRight = this.opMode.hardwareMap.get(DcMotor::class.java, "droneRight")

this.resetPin()
this.droneRight.direction = DcMotorSimple.Direction.REVERSE
}

/** Moves the pin to the open position, releasing the drone. */
fun releasePin() {
this.pin.position = RobotConfig.Drone.OPEN_PIN
fun spin() {
this.droneLeft.power = 1.0
this.droneRight.power = 1.0
}

/** Resets the pin to its default, closed, position. */
private fun resetPin() {
this.pin.position = RobotConfig.Drone.CLOSE_PIN
fun stop() {
this.droneLeft.power = 0.0
this.droneRight.power = 0.0
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ class TeleOpMain : OpMode() {
Claw.init(this)

// Drone controls
// Drone.init(this)
Drone.init(this)

// Log that we are initialized
Telemetry.sayInitialized()
Expand Down Expand Up @@ -107,7 +107,9 @@ class TeleOpMain : OpMode() {

// Input to launch drone.
if (gamepad.x && gamepad.y) {
Drone.releasePin()
Drone.spin()
} else {
Drone.stop()
}

// movement of all wheels
Expand Down

0 comments on commit de49a83

Please sign in to comment.