Skip to content
This repository has been archived by the owner on Mar 17, 2024. It is now read-only.

Commit

Permalink
feat: cherry-pick changes from red-green scrimmage (#33)
Browse files Browse the repository at this point in the history
  • Loading branch information
BD103 authored Dec 5, 2023
2 parents 3efb038 + 59f845b commit fad8be7
Show file tree
Hide file tree
Showing 5 changed files with 58 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,6 @@ import com.qualcomm.robotcore.hardware.DcMotor
import com.qualcomm.robotcore.hardware.DcMotorSimple
import com.qualcomm.robotcore.util.ElapsedTime
import org.firstinspires.ftc.teamcode.api.TriWheels
import org.firstinspires.ftc.teamcode.api.linear.Encoders.driveTo
import org.firstinspires.ftc.teamcode.api.linear.Encoders.spinTo
import org.firstinspires.ftc.teamcode.utils.RobotConfig
import kotlin.math.abs
import kotlin.math.min
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@ package org.firstinspires.ftc.teamcode.components
import com.qualcomm.robotcore.eventloop.opmode.OpMode
import org.firstinspires.ftc.teamcode.api.TeleOpState
import org.firstinspires.ftc.teamcode.api.TriWheels
import org.firstinspires.ftc.teamcode.utils.RobotConfig
import kotlin.math.PI
import kotlin.math.atan2
import kotlin.math.sqrt
Expand Down Expand Up @@ -48,6 +49,10 @@ object TeleOpMovement : Component {
}

// movement of all wheels
TriWheels.driveWithRotation(joyRadians, joyMagnitude, rotationPower)
TriWheels.driveWithRotation(
joyRadians,
joyMagnitude * RobotConfig.TeleOpMovement.DRIVE_SPEED,
rotationPower * RobotConfig.TeleOpMovement.ROTATE_SPEED
)
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
package org.firstinspires.ftc.teamcode.opmode.autonomous

import com.qualcomm.robotcore.eventloop.opmode.Autonomous
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode
import org.firstinspires.ftc.teamcode.api.Telemetry
import org.firstinspires.ftc.teamcode.api.TriWheels
import org.firstinspires.ftc.teamcode.api.linear.Encoders
import org.firstinspires.ftc.teamcode.utils.Reset
import org.firstinspires.ftc.teamcode.utils.RobotConfig

@Autonomous(name = "Auto Forward")
class AutoForward : LinearOpMode() {
override fun runOpMode() {
Reset.init(this)

Telemetry.init(this)
TriWheels.init(this)
Encoders.init(this)

Telemetry.sayInitialized()

waitForStart()

Telemetry.sayStarted()

Encoders.driveTo(
when (RobotConfig.model) {
RobotConfig.Model.RobotA -> Encoders.Direction.Blue
RobotConfig.Model.RobotB -> Encoders.Direction.Red
},
20.0,
)
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,10 @@ abstract class AutoMain : LinearOpMode() {
abstract val config: Config

/** The axis the robot should move along. */
private val forward = Encoders.Direction.Red
private val forward = when (RobotConfig.model) {
RobotConfig.Model.RobotA -> Encoders.Direction.Blue
RobotConfig.Model.RobotB -> Encoders.Direction.Red
}

/** How many inches the robot is from the starting tile */
private val startingOffset = 2.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ object RobotConfig {
*
* @see Model
*/
val model: Model = Model.RobotB
val model: Model = Model.RobotA

/**
* When true, enables debugging features like camera streaming and more logs.
Expand Down Expand Up @@ -48,7 +48,10 @@ object RobotConfig {
* increase accuracy.
*/
@JvmField
var TICKS_PER_INCH: Double = 44.0
var TICKS_PER_INCH: Double = when (model) {
Model.RobotA -> 27.0
Model.RobotB -> 44.0
}

/**
* How many ticks a wheel needs to rotate for the robot to spin a single degree.
Expand Down Expand Up @@ -130,6 +133,15 @@ object RobotConfig {
var WAIT_TIME: Long = 0
}

@Config
object TeleOpMovement {
@JvmField
var DRIVE_SPEED: Double = 0.6

@JvmField
var ROTATE_SPEED: Double = 0.5
}

/**
* Represents what model of robot is running the code.
*
Expand Down

0 comments on commit fad8be7

Please sign in to comment.