Skip to content

Commit

Permalink
Timings
Browse files Browse the repository at this point in the history
  • Loading branch information
penguinencounter committed Mar 10, 2024
1 parent 9c70934 commit 964de39
Show file tree
Hide file tree
Showing 4 changed files with 60 additions and 21 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -36,11 +36,11 @@ class Robot(map: HardwareMap) : RobotConfiguration() {

@JvmField
var liftLeftB // 0
: DcMotor = map.typedGet("slideLeft")
: DcMotor? = map.typedMaybeGet("slideLeft")

@JvmField
var liftRightB // 1
: DcMotor = map.typedGet("slideRight")
: DcMotor? = map.typedMaybeGet("slideRight")

@JvmField
var dumperRotateB // 2
Expand All @@ -67,8 +67,8 @@ class Robot(map: HardwareMap) : RobotConfiguration() {
0.0
)
}
override val liftLeft: DcMotor get() = liftLeftB
override val liftRight: DcMotor get() = liftRightB
override val liftLeft: DcMotor get() = liftLeftB!!
override val liftRight: DcMotor get() = liftRightB!!
override val liftLock: SharedResource = SharedResource("lift") {
liftLeft.power = 0.0
liftRight.power = 0.0
Expand Down Expand Up @@ -108,15 +108,19 @@ class Robot(map: HardwareMap) : RobotConfiguration() {
setReverse(backLeft)
enableBrakes(frontLeft, frontRight, backLeft, backRight)

liftLeftB.mode = DcMotor.RunMode.STOP_AND_RESET_ENCODER
liftLeftB.targetPosition = 0
liftLeftB.power = 1.0
liftLeftB.mode = DcMotor.RunMode.RUN_TO_POSITION
liftRightB.mode = DcMotor.RunMode.STOP_AND_RESET_ENCODER
liftRightB.targetPosition = 0
liftRightB.power = 1.0
liftRightB.mode = DcMotor.RunMode.RUN_TO_POSITION
setReverse(liftRightB)
if (liftLeftB != null) {
liftLeftB!!.mode = DcMotor.RunMode.STOP_AND_RESET_ENCODER
liftLeftB!!.targetPosition = 0
liftLeftB!!.power = 1.0
liftLeftB!!.mode = DcMotor.RunMode.RUN_TO_POSITION
}
if (liftRightB != null) {
liftRightB!!.mode = DcMotor.RunMode.STOP_AND_RESET_ENCODER
liftRightB!!.targetPosition = 0
liftRightB!!.power = 1.0
liftRightB!!.mode = DcMotor.RunMode.RUN_TO_POSITION
setReverse(liftRightB!!)
}

// Adjust the orientation parameters to match your robot
val parameters = IMU.Parameters(
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
package org.firstinspires.ftc.teamcode.opmodes;

import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.DcMotor;
Expand All @@ -10,7 +9,7 @@

import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;

@Disabled
//@Disabled
@TeleOp
public class Crab extends LinearOpMode {
DcMotor.RunMode baseMode = DcMotor.RunMode.RUN_WITHOUT_ENCODER;
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
package org.firstinspires.ftc.teamcode.opmodes

import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode
import com.qualcomm.robotcore.eventloop.opmode.TeleOp
import org.firstinspires.ftc.teamcode.configurations.RobotConfiguration
import kotlin.math.abs
import kotlin.math.max

@TeleOp
class MinimalTeleOp : LinearOpMode() {
override fun runOpMode() {
// Declare our motors
// Make sure your ID's match your configuration
val robot = RobotConfiguration.currentConfiguration()(hardwareMap)

waitForStart()
while (opModeIsActive()) {
val y = -gamepad1.left_stick_y.toDouble() // Remember, this is reversed!
val x = gamepad1.left_stick_x * 1.1 // Counteract imperfect strafing
val rx = gamepad1.right_stick_x.toDouble()

// Denominator is the largest motor power (absolute value) or 1
// This ensures all the powers maintain the same ratio, but only when
// at least one is out of the range [-1, 1]
val denominator = max(abs(y) + abs(x) + abs(rx), 1.0) * 1
val frontLeftPower: Double = (y + x + rx) / denominator
val backLeftPower: Double = (y - x + rx) / denominator
val frontRightPower: Double = (y - x - rx) / denominator
val backRightPower: Double = (y + x - rx) / denominator

robot.driveMotors().frontLeft.power = frontLeftPower
robot.driveMotors().backLeft.power = backLeftPower
robot.driveMotors().frontRight.power = frontRightPower
robot.driveMotors().backRight.power = backRightPower
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -484,9 +484,9 @@ private void frontstage(AdvSphereProcess.Result result, int targetTag) {
Consumer<Double> rightOnBlue = allianceColor() == AllianceColor.Blue ? why::strafeRight : why::strafeLeft;
navFrontstage(result, rightOnBlue);

sleep(200);
sleep(500);
alignTag(aprilTag, targetTag);
sleep(200);
sleep(500);
alignTag(aprilTag, targetTag);
scoreYellowPixel(scheduler, robot, theXButton, newOdo);

Expand Down Expand Up @@ -540,10 +540,9 @@ private void backstage(AdvSphereProcess.Result result, boolean posLeft, int targ

navBackstage(scheduler, result, awayFromWall);

sleep(200);

sleep(500);
alignTag(aprilTag, targetTag);
sleep(200);
sleep(500);
alignTag(aprilTag, targetTag);
scoreYellowPixel(scheduler, robot, theXButton, newOdo);

Expand Down Expand Up @@ -638,7 +637,7 @@ private void navBackstage(
scheduler.runToCompletion(this::panic_button);
}

public static final double[] frontstageTravelDistances = {18.5, 20.0, 27.0};
public static final double[] frontstageTravelDistances = {18.5, 20.0, 24.0};

private void frontstageLeft() {
turnPID.TurnRobot(-45.0);
Expand Down

0 comments on commit 964de39

Please sign in to comment.