diff --git a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/Localizer.java b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/Localizer.java index ac2ca8a..aa3112e 100644 --- a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/Localizer.java +++ b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/Localizer.java @@ -13,16 +13,18 @@ import dev.cyberarm.engine.V2.Utilities; public class Localizer { private final RedCrabMinibot robot; private double rawX = 0, rawY = 0, rawR = 0, offsetX = 0, offsetY = 0; - private final double trackWidthMM = 387.35, forwardOffsetMM = 133.35, wheelDiameterMM = 90.0; + private double trackWidthMM = 387.35, forwardOffsetMM = 133.35, wheelDiameterMM = 90.0; private final int encoderTicksPerRevolution = 8192; private final double encoderGearRatio = 1; private double lastEncoderXLeftMM, lastEncoderXRightMM, lastEncoderYCenterMM; // private double xDeltaMultiplier = 0.87012987, yDeltaMultiplier = 0.25; - private double xPosMultiplier = 0.675956739, yPosMultiplier = 0.941867531; + private double xPosMultiplier = 0.675956739, yPosMultiplier = 0.675956739; private HolonomicOdometry odometry; public Localizer(RedCrabMinibot robot) { this.robot = robot; + loadConfigConstants(); + // Preset last encoder to current location to not require resetting encoders, ever. (🤞) this.lastEncoderXLeftMM = ticksToMM(robot.deadWheelXLeft.getCurrentPosition()); this.lastEncoderXRightMM = ticksToMM(robot.deadWheelXRight.getCurrentPosition()); @@ -37,6 +39,22 @@ public class Localizer { ); } + public void loadConfigConstants() { +// trackWidthMM = 387.35; +// forwardOffsetMM = 133.35; +// wheelDiameterMM = 90.0; +// +// xPosMultiplier = 0.675956739; +// yPosMultiplier = 0.675956739; + + trackWidthMM = robot.config.variable("Robot", "Localizer", "track_width_mm").value(); + forwardOffsetMM = robot.config.variable("Robot", "Localizer", "forward_offset_mm").value(); + wheelDiameterMM = robot.config.variable("Robot", "Localizer", "wheel_diameter_mm").value(); + + xPosMultiplier = robot.config.variable("Robot", "Localizer", "x_position_multiplier").value(); + yPosMultiplier = robot.config.variable("Robot", "Localizer", "y_position_multiplier").value(); + } + public void reset() { robot.resetDeadWheels(); @@ -104,7 +122,7 @@ public class Localizer { } public double yMM() { - return odometry.getPose().getY() * xPosMultiplier + offsetY; //rawY; + return odometry.getPose().getY() * yPosMultiplier + offsetY; //rawY; } public double xIn() { diff --git a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/RedCrabMinibot.java b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/RedCrabMinibot.java index 7bb1b33..fb01e87 100644 --- a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/RedCrabMinibot.java +++ b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/RedCrabMinibot.java @@ -22,6 +22,8 @@ import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfig import org.timecrafters.TimeCraftersConfigurationTool.library.backend.config.Action; import org.timecrafters.TimeCraftersConfigurationTool.library.backend.config.Variable; +import java.util.ArrayList; + import dev.cyberarm.drivers.EncoderCustomKB2040; import dev.cyberarm.engine.V2.CyberarmEngine; import dev.cyberarm.engine.V2.Utilities; @@ -87,8 +89,15 @@ public class RedCrabMinibot { public final Servo leftClaw, rightClaw, clawWrist, droneLatch, hookArm; public final DcMotorEx deadWheelXLeft, deadWheelXRight; public final EncoderCustomKB2040 deadWheelYCenter; - public final DigitalChannel greenLED, redLED; - public final boolean LED_OFF = true, LED_ON = false; + public final DigitalChannel ledTopGreen, ledTopRed, ledRail0Green, ledRail0Red, ledRail1Green, ledRail1Red, ledRail2Green, ledRail2Red, + ledRail3Green, ledRail3Red; + public final ArrayList railGreenLEDs = new ArrayList<>(), railRedLEDs = new ArrayList<>(); + public int ledChaserIndex = 0; + public final long ledChaserIntervalMS; + public long lastLedChaserTimeMS; + public final boolean LED_OFF = true; + public final boolean LED_ON = false; + public boolean ledChaseUp = true; final CyberarmEngine engine; public final boolean autonomous; @@ -252,13 +261,51 @@ public class RedCrabMinibot { resetDeadWheels(); /// LED(s) /// - greenLED = engine.hardwareMap.get(DigitalChannel.class, "led_green"); // GREEN LED NOT WORKING - redLED = engine.hardwareMap.get(DigitalChannel.class, "led_red"); + ledTopGreen = engine.hardwareMap.get(DigitalChannel.class, "led_top_green"); + ledTopRed = engine.hardwareMap.get(DigitalChannel.class, "led_top_red"); + // RED and GREEN are swapped for the 'new' LEDs, and I'm to lazy to fix the robot config + ledRail0Green = engine.hardwareMap.get(DigitalChannel.class, "led_rail_0_red"); + ledRail0Red = engine.hardwareMap.get(DigitalChannel.class, "led_rail_0_green"); + ledRail1Green = engine.hardwareMap.get(DigitalChannel.class, "led_rail_1_red"); + ledRail1Red = engine.hardwareMap.get(DigitalChannel.class, "led_rail_1_green"); + ledRail2Green = engine.hardwareMap.get(DigitalChannel.class, "led_rail_2_red"); + ledRail2Red = engine.hardwareMap.get(DigitalChannel.class, "led_rail_2_green"); + ledRail3Green = engine.hardwareMap.get(DigitalChannel.class, "led_rail_3_red"); + ledRail3Red = engine.hardwareMap.get(DigitalChannel.class, "led_rail_3_green"); - greenLED.setMode(DigitalChannel.Mode.OUTPUT); - redLED.setMode(DigitalChannel.Mode.OUTPUT); - greenLED.setState(LED_OFF); - redLED.setState(LED_ON); + railGreenLEDs.add(ledRail0Green); + railGreenLEDs.add(ledRail1Green); + railGreenLEDs.add(ledRail2Green); + railGreenLEDs.add(ledRail3Green); + + railRedLEDs.add(ledRail0Red); + railRedLEDs.add(ledRail1Red); + railRedLEDs.add(ledRail2Red); + railRedLEDs.add(ledRail3Red); + + ledTopGreen.setMode(DigitalChannel.Mode.OUTPUT); + ledTopRed.setMode(DigitalChannel.Mode.OUTPUT); + ledRail0Green.setMode(DigitalChannel.Mode.OUTPUT); + ledRail0Red.setMode(DigitalChannel.Mode.OUTPUT); + ledRail1Green.setMode(DigitalChannel.Mode.OUTPUT); + ledRail1Red.setMode(DigitalChannel.Mode.OUTPUT); + ledRail2Green.setMode(DigitalChannel.Mode.OUTPUT); + ledRail2Red.setMode(DigitalChannel.Mode.OUTPUT); + ledRail3Green.setMode(DigitalChannel.Mode.OUTPUT); + ledRail3Red.setMode(DigitalChannel.Mode.OUTPUT); + + /// Turn off green LEDs and turn red ones on + ledTopGreen.setState(LED_OFF); + ledTopRed.setState(LED_ON); + for (DigitalChannel led : railGreenLEDs) { + led.setState(LED_OFF); + } + for (DigitalChannel led : railRedLEDs) { + led.setState(LED_ON); + } + + ledChaserIntervalMS = 250; + lastLedChaserTimeMS = System.currentTimeMillis(); // Bulk read from hubs Utilities.hubsBulkReadMode(engine.hardwareMap, LynxModule.BulkCachingMode.MANUAL); @@ -274,8 +321,16 @@ public class RedCrabMinibot { public void shutdown() { // Prevent LED(s) from being on while idle - greenLED.setMode(DigitalChannel.Mode.INPUT); - redLED.setMode(DigitalChannel.Mode.INPUT); + ledTopGreen.setMode(DigitalChannel.Mode.INPUT); + ledTopRed.setMode(DigitalChannel.Mode.INPUT); + ledRail0Green.setMode(DigitalChannel.Mode.INPUT); + ledRail0Red.setMode(DigitalChannel.Mode.INPUT); + ledRail1Green.setMode(DigitalChannel.Mode.INPUT); + ledRail1Red.setMode(DigitalChannel.Mode.INPUT); + ledRail2Green.setMode(DigitalChannel.Mode.INPUT); + ledRail2Red.setMode(DigitalChannel.Mode.INPUT); + ledRail3Green.setMode(DigitalChannel.Mode.INPUT); + ledRail3Red.setMode(DigitalChannel.Mode.INPUT); } public void reloadConfig() { @@ -331,6 +386,8 @@ public class RedCrabMinibot { RedCrabMinibot.DRONE_LATCH_INITIAL_POSITION = config.variable("Robot", "DroneLauncher_Tuning", "initial_position").value(); RedCrabMinibot.DRONE_LATCH_LAUNCH_POSITION = config.variable("Robot", "DroneLauncher_Tuning", "launch_position").value(); RedCrabMinibot.DRONE_LAUNCH_CONFIRMATION_TIME_MS = config.variable("Robot", "DroneLauncher_Tuning", "launch_confirmation_time_ms").value(); + + localizer.loadConfigConstants(); } public void resetDeadWheels() { @@ -571,4 +628,131 @@ public class RedCrabMinibot { return Utilities.isBetween(distanceMM, travelledDistanceMM - toleranceMM, travelledDistanceMM + toleranceMM); } + + public void ledController() { + if (autonomous) { + if (engine.runTime() < 20_000.0) { // KEEP CALM and CARRY ON + ledTopRed.setState(LED_OFF); + ledTopGreen.setState(LED_ON); + + ledAnimateChaser(LED_OFF, LED_ON, false); + } else if (engine.runTime() < 23_000.0) { // RUNNING LOW ON TIME + ledTopRed.setState(LED_OFF); + ledTopGreen.setState(LED_ON); + + ledAnimateChaser(LED_ON, LED_ON, false); + } else { // 5 SECONDS LEFT! + if (engine.runTime() < 29_000.0) { + ledTopRed.setState(LED_ON); + ledTopGreen.setState(LED_ON); + } else { + ledTopRed.setState(LED_ON); + ledTopGreen.setState(LED_OFF); + } + + ledAnimateProgress(LED_ON, LED_OFF, (engine.runTime() - 23_000.0) / 5_000.0); + } + } else { + if (engine.runTime() >= 90_000.0) { // LAUNCH DRONE and DO CHIN UP + ledTopRed.setState(LED_OFF); + ledTopGreen.setState(LED_ON); + + ledSetRailRedLEDs(LED_OFF); + ledSetRailGreenLEDs(LED_ON); + } else if (engine.runTime() >= 80_000.0) { // GET READY + if (ledChaserIndex == railRedLEDs.size() - 1) { + ledTopRed.setState(LED_OFF); + ledTopGreen.setState(LED_OFF); + } else { + ledTopRed.setState(LED_ON); + ledTopGreen.setState(LED_ON); + } + + ledAnimateChaser(LED_ON, LED_ON, false); + } else { // KEEP CALM and CARRY ON + ledTopRed.setState(LED_ON); + ledTopGreen.setState(LED_OFF); + + ledAnimateChaser(LED_ON, LED_OFF, false); + } + } + } + + public void ledSetRailGreenLEDs(boolean ledState) { + for (DigitalChannel led : railGreenLEDs) { + led.setState(ledState); + } + } + + public void ledSetRailRedLEDs(boolean ledState) { + for (DigitalChannel led : railRedLEDs) { + led.setState(ledState); + } + } + + public void ledAnimateChaser(boolean ledRed, boolean ledGreen, boolean invert) { + if (System.currentTimeMillis() - lastLedChaserTimeMS >= ledChaserIntervalMS) { + lastLedChaserTimeMS = System.currentTimeMillis(); + } else { + return; + } + + // Turn off current LED + if (invert) { + railRedLEDs.get(ledChaserIndex).setState(ledRed); + railGreenLEDs.get(ledChaserIndex).setState(ledGreen); + } else { + railRedLEDs.get(ledChaserIndex).setState(LED_OFF); + railGreenLEDs.get(ledChaserIndex).setState(LED_OFF); + } + + // Cycle up/down + if (ledChaseUp) { + ledChaserIndex++; + } else { + ledChaserIndex--; + } + + // Switch active LED + if (ledChaserIndex >= railRedLEDs.size()) { + ledChaseUp = !ledChaseUp; + ledChaserIndex = railRedLEDs.size() - 2; + } else if (ledChaserIndex < 0) { + ledChaseUp = !ledChaseUp; + ledChaserIndex = 1; + } + + // Control active LED + if (!invert) { + railRedLEDs.get(ledChaserIndex).setState(ledRed); + railGreenLEDs.get(ledChaserIndex).setState(ledGreen); + } else { + railRedLEDs.get(ledChaserIndex).setState(LED_OFF); + railGreenLEDs.get(ledChaserIndex).setState(LED_OFF); + } + } + + public void ledAnimateProgress(boolean progressLEDsRed, boolean progressLEDsGreen, double ratio) { + double i = 0.0; + for (DigitalChannel led : railRedLEDs) { + i += 1.0 / railRedLEDs.size(); + + if (ratio < i) { + led.setState(LED_OFF); + } else { + led.setState(progressLEDsRed); + } + } + + i = 0.0; + for (DigitalChannel led : railGreenLEDs) { + i += 1.0 / railGreenLEDs.size(); + + if (ratio < i) { + led.setState(LED_OFF); + } else { + led.setState(progressLEDsGreen); + } + } + } } diff --git a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/cyberarm_RedCrab.json b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/cyberarm_RedCrab.json index a036019..4e290a2 100644 --- a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/cyberarm_RedCrab.json +++ b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/cyberarm_RedCrab.json @@ -1 +1 @@ -{"config":{"created_at":"2023-12-11 09:31:55 -0600","updated_at":"2024-02-01 20:00:47 -0600","spec_version":2,"revision":1220},"data":{"groups":[{"name":"Autonomous_BLUE_Audience","actions":[{"name":"00-00","comment":"@ClawArmMove - Move claw arm up high","enabled":true,"variables":[{"name":"angle","value":"Dx130.0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix2500"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"00-01","comment":"@ServoMove - Move wrist to position camera","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1"},{"name":"position","value":"Dx0.74"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix1000"}]},{"name":"01-00","comment":"@PathSelector - Pick path; default Center","enabled":true,"variables":[{"name":"minConfidence","value":"Dx18.0"},{"name":"path","value":"Ix1"},{"name":"timeoutMS","value":"Ix500"}]},{"name":"02-00","comment":"@Move - Move forward","enabled":true,"variables":[{"name":"distanceMM","value":"Dx415"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"02-01","comment":"@ClawArmMove - Move claw arm down","enabled":true,"variables":[{"name":"angle","value":"Dx220"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix10"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"02-02","comment":"@ServoMove - Move wrist servo","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx10"},{"name":"position","value":"Dx0.51"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix10"}]},{"name":"04-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"05-00","comment":"@PathEnactor - Enact path; paths must return to \"origin\" when done","enabled":true,"variables":[{"name":"forcePath","value":"Ix-1"}]},{"name":"06-00","comment":"@ClawArmMove - Move claw arm to stow position","enabled":true,"variables":[{"name":"angle","value":"Dx0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix1"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"06-01","comment":"@ServoMove - Move wrist to stow position","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.74"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix1"}]},{"name":"07-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"08-00","comment":"@Move - Move back","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-207"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"09-00","comment":"@Rotate - Rotate to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"10-00","comment":"@Move - Strafe to right","enabled":true,"variables":[{"name":"distanceMM","value":"Dx610"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxtrue"},{"name":"timeoutMS","value":"Ix3000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"11-00","comment":"@Rotate - Rotate to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"12-00","comment":"@Move - Move forward unto Dawn","enabled":true,"variables":[{"name":"distanceMM","value":"Dx1043"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx900"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix8000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"13-00","comment":"@Rotate - Rotate to 270d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx270"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"14-00","comment":"@Move - Move forward to backstage","enabled":true,"variables":[{"name":"distanceMM","value":"Dx2844"},{"name":"lerpMM_DOWN","value":"Dx500"},{"name":"lerpMM_UP","value":"Dx500"},{"name":"maxVelocityMM","value":"Dx1220"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix8000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"15-00","comment":"@ClawArmMove - Move claw arm down","enabled":true,"variables":[{"name":"angle","value":"Dx180"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"16-00","comment":"@ServoMove - Open left claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.5"},{"name":"servoName","value":"SxleftClaw"},{"name":"timeoutMS","value":"Ix250"}]},{"name":"17-00","comment":"@ClawArmMove - Move claw arm to stow","enabled":true,"variables":[{"name":"angle","value":"Dx0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix2500"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"17-01","comment":"@ServoMove - close left claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.2"},{"name":"servoName","value":"SxleftClaw"},{"name":"timeoutMS","value":"Ix250"}]}]},{"name":"Autonomous_RED_Audience","actions":[{"name":"00-00","comment":"@ClawArmMove - Move claw arm up high","enabled":true,"variables":[{"name":"angle","value":"Dx130.0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix2500"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"00-01","comment":"@ServoMove - Move wrist to position camera","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1"},{"name":"position","value":"Dx0.74"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix1000"}]},{"name":"01-00","comment":"@PathSelector - Pick path; default Center","enabled":true,"variables":[{"name":"minConfidence","value":"Dx18.0"},{"name":"path","value":"Ix1"},{"name":"timeoutMS","value":"Ix500"}]},{"name":"02-00","comment":"@Move - Move forward","enabled":true,"variables":[{"name":"distanceMM","value":"Dx415"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"02-01","comment":"@ClawArmMove - Move claw arm down","enabled":true,"variables":[{"name":"angle","value":"Dx220"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix10"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"02-02","comment":"@ServoMove - Move wrist servo","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx10"},{"name":"position","value":"Dx0.51"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix10"}]},{"name":"04-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"05-00","comment":"@PathEnactor - Enact path; paths must return to \"origin\" when done","enabled":true,"variables":[{"name":"forcePath","value":"Ix-1"}]},{"name":"06-00","comment":"@ClawArmMove - Move claw arm to stow position","enabled":true,"variables":[{"name":"angle","value":"Dx0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix1"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"06-01","comment":"@ServoMove - Move wrist to stow position","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.74"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix1"}]},{"name":"07-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"08-00","comment":"@Move - Move back","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-207"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"09-00","comment":"@Rotate - Rotate to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"10-00","comment":"@Move - Strafe to left","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-610"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxtrue"},{"name":"timeoutMS","value":"Ix3000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"11-00","comment":"@Rotate - Rotate to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"12-00","comment":"@Move - Move forward unto Dawn","enabled":true,"variables":[{"name":"distanceMM","value":"Dx1043"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx900"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix8000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"13-00","comment":"@Rotate - Rotate to 90d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx90"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"14-00","comment":"@Move - Move forward to backstage","enabled":true,"variables":[{"name":"distanceMM","value":"Dx2844"},{"name":"lerpMM_DOWN","value":"Dx500"},{"name":"lerpMM_UP","value":"Dx500"},{"name":"maxVelocityMM","value":"Dx1220"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix8000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"15-00","comment":"@ClawArmMove - Move claw arm down","enabled":true,"variables":[{"name":"angle","value":"Dx180"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"16-00","comment":"@ServoMove - Open left claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.5"},{"name":"servoName","value":"SxleftClaw"},{"name":"timeoutMS","value":"Ix250"}]},{"name":"17-00","comment":"@ClawArmMove - Move claw arm to stow","enabled":true,"variables":[{"name":"angle","value":"Dx0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix2500"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"17-01","comment":"@ServoMove - close left claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.2"},{"name":"servoName","value":"SxleftClaw"},{"name":"timeoutMS","value":"Ix250"}]}]},{"name":"Autonomous_RED_Backstage","actions":[{"name":"00-00","comment":"@ClawArmMove - Move claw arm up high","enabled":true,"variables":[{"name":"angle","value":"Dx130.0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix2500"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"00-01","comment":"@ServoMove - Move wrist to position camera","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1"},{"name":"position","value":"Dx0.74"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix1000"}]},{"name":"01-00","comment":"@PathSelector - Pick path; default Center","enabled":true,"variables":[{"name":"minConfidence","value":"Dx18.0"},{"name":"path","value":"Ix1"},{"name":"timeoutMS","value":"Ix500"}]},{"name":"02-00","comment":"@Move - Move forward","enabled":true,"variables":[{"name":"distanceMM","value":"Dx415"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"02-01","comment":"@ClawArmMove - Move claw arm down","enabled":true,"variables":[{"name":"angle","value":"Dx220"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix10"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"02-02","comment":"@ServoMove - Move wrist servo","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx10"},{"name":"position","value":"Dx0.51"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix10"}]},{"name":"04-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"05-00","comment":"@PathEnactor - Enact path; paths must return to \"origin\" when done","enabled":true,"variables":[{"name":"forcePath","value":"Ix-1"}]},{"name":"06-00","comment":"@ClawArmMove - Move claw arm to deposit position","enabled":true,"variables":[{"name":"angle","value":"Dx165.0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix1"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"06-01","comment":"@ServoMove - Move wrist to deposit position","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.508"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix1"}]},{"name":"07-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"08-00","comment":"@Move - Move back","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-207"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"09-00","comment":"@Rotate - Rotate to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"10-00","comment":"@Move - Strafe to the right","enabled":true,"variables":[{"name":"distanceMM","value":"Dx610"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxtrue"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"11-00","comment":"@Rotate - Rotate to 90d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx90"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"12-00","comment":"@Move - Strafe to the left","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-101"},{"name":"lerpMM_DOWN","value":"Dx25"},{"name":"lerpMM_UP","value":"Dx25"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxtrue"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"13-00","comment":"@Rotate - Rotate to 90d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx90"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"14-00","comment":"@Move - Move to backboard","enabled":true,"variables":[{"name":"distanceMM","value":"Dx475"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"15-00","comment":"@ServoMove - Open left claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1"},{"name":"position","value":"Dx0.5"},{"name":"servoName","value":"SxleftClaw"},{"name":"timeoutMS","value":"Ix1000"}]},{"name":"16-00","comment":"@Move - Move back a bit","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-75"},{"name":"lerpMM_DOWN","value":"Dx25"},{"name":"lerpMM_UP","value":"Dx25"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"17-00","comment":"@Move - Move right the right","enabled":true,"variables":[{"name":"distanceMM","value":"Dx600"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxtrue"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"17-01","comment":"@ClawArmMove - Move claw arm to stow position","enabled":true,"variables":[{"name":"angle","value":"Dx0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix1"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"17-02","comment":"@ServoMove - Move wrist to stow position","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1"},{"name":"position","value":"Dx0.74"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix1000"}]},{"name":"17-03","comment":"@ServoMove - Close left claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1"},{"name":"position","value":"Dx0.2"},{"name":"servoName","value":"SxleftClaw"},{"name":"timeoutMS","value":"Ix1000"}]}]},{"name":"Autonomous_SpikePath_CENTER","actions":[{"name":"01-00","comment":"@Move - Move forward to spike mark","enabled":true,"variables":[{"name":"distanceMM","value":"Dx152"},{"name":"lerpMM_DOWN","value":"Dx50"},{"name":"lerpMM_UP","value":"Dx50"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"02-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"02-01","comment":"@ServoMove - Open right claw (purple)","enabled":true,"variables":[{"name":"lerp","value":"Bxtrue"},{"name":"lerpMS","value":"Dx500"},{"name":"position","value":"Dx0.5"},{"name":"servoName","value":"SxrightClaw"},{"name":"timeoutMS","value":"Ix750"}]},{"name":"04-00","comment":"@Move - Move back from spike mark","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-152"},{"name":"lerpMM_DOWN","value":"Dx50"},{"name":"lerpMM_UP","value":"Dx50"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"05-00","comment":"@ServoMove - Close right claw (purple)","enabled":true,"variables":[{"name":"lerp","value":"Bxtrue"},{"name":"lerpMS","value":"Dx500"},{"name":"position","value":"Dx0.74"},{"name":"servoName","value":"SxrightClaw"},{"name":"timeoutMS","value":"Ix750"}]},{"name":"05-01","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]}]},{"name":"Autonomous_SpikePath_LEFT","actions":[{"name":"00-00","comment":"@Rotate - Rotate robot to towards left spike mark","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx316"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"01-00","comment":"@Move - Move up a bit","enabled":false,"variables":[{"name":"distanceMM","value":"Dx101"},{"name":"lerpMM_DOWN","value":"Dx25"},{"name":"lerpMM_UP","value":"Dx25"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"02-00","comment":"@ServoMove - Drop pixel","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.5"},{"name":"servoName","value":"SxrightClaw"},{"name":"timeoutMS","value":"Ix500"}]},{"name":"03-00","comment":"@ServoMove - Close claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.72"},{"name":"servoName","value":"SxrightClaw"},{"name":"timeoutMS","value":"Ix100"}]},{"name":"04-00","comment":"@Move - Move back a bit","enabled":false,"variables":[{"name":"distanceMM","value":"Dx-101"},{"name":"lerpMM_DOWN","value":"Dx25"},{"name":"lerpMM_UP","value":"Dx25"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"05-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]}]},{"name":"Autonomous_SpikePath_RIGHT","actions":[{"name":"00-00","comment":"@Rotate - Rotate robot to towards right spike mark","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx45"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"01-00","comment":"@Move - Move up a bit","enabled":true,"variables":[{"name":"distanceMM","value":"Dx50"},{"name":"lerpMM_DOWN","value":"Dx25"},{"name":"lerpMM_UP","value":"Dx10"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"02-00","comment":"@ServoMove - Drop pixel","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.5"},{"name":"servoName","value":"SxrightClaw"},{"name":"timeoutMS","value":"Ix500"}]},{"name":"03-00","comment":"@ServoMove - Close claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.72"},{"name":"servoName","value":"SxrightClaw"},{"name":"timeoutMS","value":"Ix100"}]},{"name":"04-00","comment":"@Move - Move back a bit","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-50"},{"name":"lerpMM_DOWN","value":"Dx25"},{"name":"lerpMM_UP","value":"Dx2"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"05-00","comment":"@Rotate - Rotate robot to 0d","enabled":false,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]}]},{"name":"Autonomous_Z_DEBUG","actions":[{"name":"00-00","comment":"@MoveToCoordinate - Trial run(s)","enabled":true,"variables":[{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"lerpMM_DOWN","value":"Dx305"},{"name":"lerpMM_UP","value":"Dx305"},{"name":"maxVelocityMM","value":"Dx610.0"},{"name":"minDistanceMM","value":"Dx30.0"},{"name":"minVelocityMM","value":"Dx125.0"},{"name":"stopDrivetrain","value":"Bxtrue"},{"name":"targetAngleDEGREES","value":"Dx45"},{"name":"targetAngleToleranceDEGREES","value":"Dx0"},{"name":"targetPosMM","value":"Sx0x-1220"},{"name":"timeoutMS","value":"Ix15000"}]},{"name":"01-00","comment":"@MoveToCoordinate - Trial run(s)","enabled":false,"variables":[{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"lerpMM_DOWN","value":"Dx305"},{"name":"lerpMM_UP","value":"Dx305"},{"name":"maxVelocityMM","value":"Dx610.0"},{"name":"minDistanceMM","value":"Dx30.0"},{"name":"minVelocityMM","value":"Dx125.0"},{"name":"stopDrivetrain","value":"Bxtrue"},{"name":"targetAngleDEGREES","value":"Dx45"},{"name":"targetAngleToleranceDEGREES","value":"Dx0"},{"name":"targetPosMM","value":"Sx0.0x0.0"},{"name":"timeoutMS","value":"Ix15000"}]},{"name":"02-00","comment":"@MoveToCoordinate - Trial run(s)","enabled":false,"variables":[{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"lerpMM_DOWN","value":"Dx305"},{"name":"lerpMM_UP","value":"Dx305"},{"name":"maxVelocityMM","value":"Dx610.0"},{"name":"minDistanceMM","value":"Dx30.0"},{"name":"minVelocityMM","value":"Dx125.0"},{"name":"stopDrivetrain","value":"Bxtrue"},{"name":"targetAngleDEGREES","value":"Dx45"},{"name":"targetAngleToleranceDEGREES","value":"Dx0"},{"name":"targetPosMM","value":"Sx2420x0"},{"name":"timeoutMS","value":"Ix15000"}]},{"name":"03-00","comment":"@MoveToCoordinate - Trial run(s)","enabled":false,"variables":[{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"lerpMM_DOWN","value":"Dx305"},{"name":"lerpMM_UP","value":"Dx305"},{"name":"maxVelocityMM","value":"Dx610.0"},{"name":"minDistanceMM","value":"Dx30.0"},{"name":"minVelocityMM","value":"Dx125.0"},{"name":"stopDrivetrain","value":"Bxtrue"},{"name":"targetAngleDEGREES","value":"Dx45"},{"name":"targetAngleToleranceDEGREES","value":"Dx0"},{"name":"targetPosMM","value":"Sx0.0x0.0"},{"name":"timeoutMS","value":"Ix15000"}]},{"name":"99-00","comment":"@PathSelector - Pick path","enabled":true,"variables":[{"name":"minConfidence","value":"Dx0.7"},{"name":"path","value":"Ix-1"},{"name":"timeoutMS","value":"Ix2000000"}]}]},{"name":"Robot","actions":[{"name":"Claw_Tuning","comment":"Claws","enabled":true,"variables":[{"name":"claw_left_closed_position","value":"Dx0.2"},{"name":"claw_left_open_position","value":"Dx0.5"},{"name":"claw_right_closed_position","value":"Dx0.78"},{"name":"claw_right_open_position","value":"Dx0.5"}]},{"name":"ClawArm_Tuning","comment":"Claw Arm","enabled":true,"variables":[{"name":"collect_angle","value":"Dx242"},{"name":"collect_float_angle","value":"Dx237"},{"name":"deposit_angle","value":"Dx165.0"},{"name":"gear_ratio","value":"Dx1"},{"name":"kD","value":"Dx1"},{"name":"kF","value":"Dx0.0"},{"name":"kI","value":"Dx1.5"},{"name":"kP","value":"Dx6"},{"name":"KPosP","value":"Dx1"},{"name":"max_current_milliamps","value":"Dx1588.0"},{"name":"max_speed","value":"Dx0.5"},{"name":"max_velocityDEGREES","value":"Dx60"},{"name":"motor_ticks","value":"Ix8192"},{"name":"stow_angle","value":"Dx0"},{"name":"tolerance","value":"Ix288"},{"name":"warn_overcurrent_after_ms","value":"Lx5000"}]},{"name":"ClawWrist_Tuning","comment":"Claw Wrist","enabled":true,"variables":[{"name":"collect_float_position","value":"Dx0.52"},{"name":"collect_position","value":"Dx0.505"},{"name":"deposit_position","value":"Dx0.508"},{"name":"stow_position","value":"Dx0.74"}]},{"name":"Drivetrain_Tuning","comment":"Drivetrain","enabled":true,"variables":[{"name":"gear_ratio","value":"Dx13.0321"},{"name":"max_speed","value":"Dx0.5"},{"name":"motor_ticks","value":"Ix28"},{"name":"velocity_max_in_mm","value":"Dx610"},{"name":"velocity_slow_in_mm","value":"Dx250"},{"name":"wheel_diameter_mm","value":"Dx90"}]},{"name":"DroneLauncher_Tuning","comment":"Drone Launcher","enabled":true,"variables":[{"name":"initial_position","value":"Dx0.5"},{"name":"launch_confirmation_time_ms","value":"Ix1000"},{"name":"launch_position","value":"Dx0"}]},{"name":"HookArm_Tuning","comment":"Hook Arm","enabled":true,"variables":[{"name":"stow_position","value":"Dx0.35"},{"name":"up_position","value":"Dx0.8"}]},{"name":"Winch_Tuning","comment":"Winch","enabled":true,"variables":[{"name":"max_speed","value":"Dx1.0"}]}]},{"name":"zAutonomous_BLUE_Audience","actions":[]},{"name":"zAutonomous_BLUE_Backstage","actions":[]}],"presets":{"groups":[],"actions":[{"name":"ClawArmMove","comment":"@ClawArmMove - Move claw arm","enabled":true,"variables":[{"name":"angle","value":"Dx0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix1000"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"Move","comment":"@Move - Move ta wheels matey!","enabled":true,"variables":[{"name":"distanceMM","value":"Dx300"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"MoveToCoordinate","comment":"@MoveToCoordinate - Trial run(s)","enabled":true,"variables":[{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"lerpMM_DOWN","value":"Dx305"},{"name":"lerpMM_UP","value":"Dx305"},{"name":"maxVelocityMM","value":"Dx610.0"},{"name":"minDistanceMM","value":"Dx25.0"},{"name":"minVelocityMM","value":"Dx125.0"},{"name":"stopDrivetrain","value":"Bxtrue"},{"name":"targetAngleDEGREES","value":"Dx45"},{"name":"targetAngleToleranceDEGREES","value":"Dx5"},{"name":"targetPosMM","value":"Sx610.0x0.0"},{"name":"timeoutMS","value":"Ix15000"}]},{"name":"PathEnactor","comment":"@PathEnactor - Enact path","enabled":true,"variables":[]},{"name":"PathSelector","comment":"@PathSelector - Pick path","enabled":true,"variables":[{"name":"minConfidence","value":"Dx0.7"},{"name":"path","value":"Ix-1"},{"name":"timeoutMS","value":"Ix2000"}]},{"name":"Rotate","comment":"@Rotate - Rotate robot to face degree heading","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"ServoMove","comment":"@ServoMove - Move servo to position","enabled":true,"variables":[{"name":"lerp","value":"Bxtrue"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.5"},{"name":"servoName","value":"SxleftClaw"},{"name":"timeoutMS","value":"Ix2000"}]}]}}} \ No newline at end of file +{"config":{"created_at":"2023-12-11 09:31:55 -0600","updated_at":"2024-02-10 13:20:30 -0600","spec_version":2,"revision":1237},"data":{"groups":[{"name":"Autonomous_BLUE_Audience","actions":[{"name":"00-00","comment":"@ClawArmMove - Move claw arm up high","enabled":true,"variables":[{"name":"angle","value":"Dx130.0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix2500"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"00-01","comment":"@ServoMove - Move wrist to position camera","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1"},{"name":"position","value":"Dx0.74"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix1000"}]},{"name":"01-00","comment":"@PathSelector - Pick path; default Center","enabled":true,"variables":[{"name":"minConfidence","value":"Dx18.0"},{"name":"path","value":"Ix1"},{"name":"timeoutMS","value":"Ix500"}]},{"name":"02-00","comment":"@Move - Move forward","enabled":true,"variables":[{"name":"distanceMM","value":"Dx415"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"02-01","comment":"@ClawArmMove - Move claw arm down","enabled":true,"variables":[{"name":"angle","value":"Dx220"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix10"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"02-02","comment":"@ServoMove - Move wrist servo","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx10"},{"name":"position","value":"Dx0.51"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix10"}]},{"name":"04-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"05-00","comment":"@PathEnactor - Enact path; paths must return to \"origin\" when done","enabled":true,"variables":[{"name":"forcePath","value":"Ix-1"}]},{"name":"06-00","comment":"@ClawArmMove - Move claw arm to stow position","enabled":true,"variables":[{"name":"angle","value":"Dx0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix1"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"06-01","comment":"@ServoMove - Move wrist to stow position","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.74"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix1"}]},{"name":"07-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"08-00","comment":"@Move - Move back","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-207"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"09-00","comment":"@Rotate - Rotate to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"10-00","comment":"@Move - Strafe to right","enabled":true,"variables":[{"name":"distanceMM","value":"Dx610"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxtrue"},{"name":"timeoutMS","value":"Ix3000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"11-00","comment":"@Rotate - Rotate to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"12-00","comment":"@Move - Move forward unto Dawn","enabled":true,"variables":[{"name":"distanceMM","value":"Dx1043"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx900"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix8000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"13-00","comment":"@Rotate - Rotate to 270d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx270"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"14-00","comment":"@Move - Move forward to backstage","enabled":true,"variables":[{"name":"distanceMM","value":"Dx2844"},{"name":"lerpMM_DOWN","value":"Dx500"},{"name":"lerpMM_UP","value":"Dx500"},{"name":"maxVelocityMM","value":"Dx1220"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix8000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"15-00","comment":"@ClawArmMove - Move claw arm down","enabled":true,"variables":[{"name":"angle","value":"Dx180"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"16-00","comment":"@ServoMove - Open left claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.5"},{"name":"servoName","value":"SxleftClaw"},{"name":"timeoutMS","value":"Ix250"}]},{"name":"17-00","comment":"@ClawArmMove - Move claw arm to stow","enabled":true,"variables":[{"name":"angle","value":"Dx0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix2500"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"17-01","comment":"@ServoMove - close left claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.2"},{"name":"servoName","value":"SxleftClaw"},{"name":"timeoutMS","value":"Ix250"}]}]},{"name":"Autonomous_RED_Audience","actions":[{"name":"00-00","comment":"@ClawArmMove - Move claw arm up high","enabled":true,"variables":[{"name":"angle","value":"Dx130.0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix2500"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"00-01","comment":"@ServoMove - Move wrist to position camera","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1"},{"name":"position","value":"Dx0.74"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix1000"}]},{"name":"01-00","comment":"@PathSelector - Pick path; default Center","enabled":true,"variables":[{"name":"minConfidence","value":"Dx18.0"},{"name":"path","value":"Ix1"},{"name":"timeoutMS","value":"Ix500"}]},{"name":"02-00","comment":"@Move - Move forward","enabled":true,"variables":[{"name":"distanceMM","value":"Dx415"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"02-01","comment":"@ClawArmMove - Move claw arm down","enabled":true,"variables":[{"name":"angle","value":"Dx220"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix10"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"02-02","comment":"@ServoMove - Move wrist servo","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx10"},{"name":"position","value":"Dx0.51"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix10"}]},{"name":"04-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"05-00","comment":"@PathEnactor - Enact path; paths must return to \"origin\" when done","enabled":true,"variables":[{"name":"forcePath","value":"Ix-1"}]},{"name":"06-00","comment":"@ClawArmMove - Move claw arm to stow position","enabled":true,"variables":[{"name":"angle","value":"Dx0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix1"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"06-01","comment":"@ServoMove - Move wrist to stow position","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.74"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix1"}]},{"name":"07-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"08-00","comment":"@Move - Move back","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-207"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"09-00","comment":"@Rotate - Rotate to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"10-00","comment":"@Move - Strafe to left","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-610"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxtrue"},{"name":"timeoutMS","value":"Ix3000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"11-00","comment":"@Rotate - Rotate to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"12-00","comment":"@Move - Move forward unto Dawn","enabled":true,"variables":[{"name":"distanceMM","value":"Dx1043"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx900"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix8000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"13-00","comment":"@Rotate - Rotate to 90d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx90"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"14-00","comment":"@Move - Move forward to backstage","enabled":true,"variables":[{"name":"distanceMM","value":"Dx2844"},{"name":"lerpMM_DOWN","value":"Dx500"},{"name":"lerpMM_UP","value":"Dx500"},{"name":"maxVelocityMM","value":"Dx1220"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix8000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"15-00","comment":"@ClawArmMove - Move claw arm down","enabled":true,"variables":[{"name":"angle","value":"Dx180"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"16-00","comment":"@ServoMove - Open left claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.5"},{"name":"servoName","value":"SxleftClaw"},{"name":"timeoutMS","value":"Ix250"}]},{"name":"17-00","comment":"@ClawArmMove - Move claw arm to stow","enabled":true,"variables":[{"name":"angle","value":"Dx0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix2500"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"17-01","comment":"@ServoMove - close left claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.2"},{"name":"servoName","value":"SxleftClaw"},{"name":"timeoutMS","value":"Ix250"}]}]},{"name":"Autonomous_RED_Backstage","actions":[{"name":"00-00","comment":"@ClawArmMove - Move claw arm up high","enabled":true,"variables":[{"name":"angle","value":"Dx130.0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix2500"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"00-01","comment":"@ServoMove - Move wrist to position camera","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1"},{"name":"position","value":"Dx0.74"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix1000"}]},{"name":"01-00","comment":"@PathSelector - Pick path; default Center","enabled":true,"variables":[{"name":"minConfidence","value":"Dx18.0"},{"name":"path","value":"Ix1"},{"name":"timeoutMS","value":"Ix500"}]},{"name":"02-00","comment":"@Move - Move forward","enabled":true,"variables":[{"name":"distanceMM","value":"Dx415"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"02-01","comment":"@ClawArmMove - Move claw arm down","enabled":true,"variables":[{"name":"angle","value":"Dx220"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix10"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"02-02","comment":"@ServoMove - Move wrist servo","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx10"},{"name":"position","value":"Dx0.51"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix10"}]},{"name":"04-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"05-00","comment":"@PathEnactor - Enact path; paths must return to \"origin\" when done","enabled":true,"variables":[{"name":"forcePath","value":"Ix-1"}]},{"name":"06-00","comment":"@ClawArmMove - Move claw arm to deposit position","enabled":true,"variables":[{"name":"angle","value":"Dx165.0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix1"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"06-01","comment":"@ServoMove - Move wrist to deposit position","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.508"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix1"}]},{"name":"07-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"08-00","comment":"@Move - Move back","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-207"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"09-00","comment":"@Rotate - Rotate to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"10-00","comment":"@Move - Strafe to the right","enabled":true,"variables":[{"name":"distanceMM","value":"Dx610"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxtrue"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"11-00","comment":"@Rotate - Rotate to 90d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx90"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"12-00","comment":"@Move - Strafe to the left","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-101"},{"name":"lerpMM_DOWN","value":"Dx25"},{"name":"lerpMM_UP","value":"Dx25"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxtrue"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"13-00","comment":"@Rotate - Rotate to 90d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx90"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"14-00","comment":"@Move - Move to backboard","enabled":true,"variables":[{"name":"distanceMM","value":"Dx475"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"15-00","comment":"@ServoMove - Open left claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1"},{"name":"position","value":"Dx0.5"},{"name":"servoName","value":"SxleftClaw"},{"name":"timeoutMS","value":"Ix1000"}]},{"name":"16-00","comment":"@Move - Move back a bit","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-75"},{"name":"lerpMM_DOWN","value":"Dx25"},{"name":"lerpMM_UP","value":"Dx25"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"17-00","comment":"@Move - Move right the right","enabled":true,"variables":[{"name":"distanceMM","value":"Dx600"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxtrue"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"17-01","comment":"@ClawArmMove - Move claw arm to stow position","enabled":true,"variables":[{"name":"angle","value":"Dx0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix1"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"17-02","comment":"@ServoMove - Move wrist to stow position","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1"},{"name":"position","value":"Dx0.74"},{"name":"servoName","value":"SxclawWrist"},{"name":"timeoutMS","value":"Ix1000"}]},{"name":"17-03","comment":"@ServoMove - Close left claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1"},{"name":"position","value":"Dx0.2"},{"name":"servoName","value":"SxleftClaw"},{"name":"timeoutMS","value":"Ix1000"}]}]},{"name":"Autonomous_SpikePath_CENTER","actions":[{"name":"01-00","comment":"@Move - Move forward to spike mark","enabled":true,"variables":[{"name":"distanceMM","value":"Dx152"},{"name":"lerpMM_DOWN","value":"Dx50"},{"name":"lerpMM_UP","value":"Dx50"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"02-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"02-01","comment":"@ServoMove - Open right claw (purple)","enabled":true,"variables":[{"name":"lerp","value":"Bxtrue"},{"name":"lerpMS","value":"Dx500"},{"name":"position","value":"Dx0.5"},{"name":"servoName","value":"SxrightClaw"},{"name":"timeoutMS","value":"Ix750"}]},{"name":"04-00","comment":"@Move - Move back from spike mark","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-152"},{"name":"lerpMM_DOWN","value":"Dx50"},{"name":"lerpMM_UP","value":"Dx50"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"05-00","comment":"@ServoMove - Close right claw (purple)","enabled":true,"variables":[{"name":"lerp","value":"Bxtrue"},{"name":"lerpMS","value":"Dx500"},{"name":"position","value":"Dx0.74"},{"name":"servoName","value":"SxrightClaw"},{"name":"timeoutMS","value":"Ix750"}]},{"name":"05-01","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]}]},{"name":"Autonomous_SpikePath_LEFT","actions":[{"name":"00-00","comment":"@Rotate - Rotate robot to towards left spike mark","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx316"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"01-00","comment":"@Move - Move up a bit","enabled":false,"variables":[{"name":"distanceMM","value":"Dx101"},{"name":"lerpMM_DOWN","value":"Dx25"},{"name":"lerpMM_UP","value":"Dx25"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"02-00","comment":"@ServoMove - Drop pixel","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.5"},{"name":"servoName","value":"SxrightClaw"},{"name":"timeoutMS","value":"Ix500"}]},{"name":"03-00","comment":"@ServoMove - Close claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.72"},{"name":"servoName","value":"SxrightClaw"},{"name":"timeoutMS","value":"Ix100"}]},{"name":"04-00","comment":"@Move - Move back a bit","enabled":false,"variables":[{"name":"distanceMM","value":"Dx-101"},{"name":"lerpMM_DOWN","value":"Dx25"},{"name":"lerpMM_UP","value":"Dx25"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"05-00","comment":"@Rotate - Rotate robot to 0d","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]}]},{"name":"Autonomous_SpikePath_RIGHT","actions":[{"name":"00-00","comment":"@Rotate - Rotate robot to towards right spike mark","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx45"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"01-00","comment":"@Move - Move up a bit","enabled":true,"variables":[{"name":"distanceMM","value":"Dx50"},{"name":"lerpMM_DOWN","value":"Dx25"},{"name":"lerpMM_UP","value":"Dx10"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"02-00","comment":"@ServoMove - Drop pixel","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.5"},{"name":"servoName","value":"SxrightClaw"},{"name":"timeoutMS","value":"Ix500"}]},{"name":"03-00","comment":"@ServoMove - Close claw","enabled":true,"variables":[{"name":"lerp","value":"Bxfalse"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.72"},{"name":"servoName","value":"SxrightClaw"},{"name":"timeoutMS","value":"Ix100"}]},{"name":"04-00","comment":"@Move - Move back a bit","enabled":true,"variables":[{"name":"distanceMM","value":"Dx-50"},{"name":"lerpMM_DOWN","value":"Dx25"},{"name":"lerpMM_UP","value":"Dx2"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"05-00","comment":"@Rotate - Rotate robot to 0d","enabled":false,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]}]},{"name":"Autonomous_Z_DEBUG","actions":[{"name":"00-00","comment":"@MoveToCoordinate - Trial run(s)","enabled":false,"variables":[{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"lerpMM_DOWN","value":"Dx305"},{"name":"lerpMM_UP","value":"Dx305"},{"name":"maxVelocityMM","value":"Dx610.0"},{"name":"minDistanceMM","value":"Dx30.0"},{"name":"minVelocityMM","value":"Dx125.0"},{"name":"stopDrivetrain","value":"Bxtrue"},{"name":"targetAngleDEGREES","value":"Dx45"},{"name":"targetAngleToleranceDEGREES","value":"Dx0"},{"name":"targetPosMM","value":"Sx2420x0"},{"name":"timeoutMS","value":"Ix15000"}]},{"name":"01-00","comment":"@MoveToCoordinate - Trial run(s)","enabled":false,"variables":[{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"lerpMM_DOWN","value":"Dx305"},{"name":"lerpMM_UP","value":"Dx305"},{"name":"maxVelocityMM","value":"Dx610.0"},{"name":"minDistanceMM","value":"Dx30.0"},{"name":"minVelocityMM","value":"Dx125.0"},{"name":"stopDrivetrain","value":"Bxtrue"},{"name":"targetAngleDEGREES","value":"Dx45"},{"name":"targetAngleToleranceDEGREES","value":"Dx0"},{"name":"targetPosMM","value":"Sx0.0x0.0"},{"name":"timeoutMS","value":"Ix15000"}]},{"name":"02-00","comment":"@MoveToCoordinate - Trial run(s)","enabled":false,"variables":[{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"lerpMM_DOWN","value":"Dx305"},{"name":"lerpMM_UP","value":"Dx305"},{"name":"maxVelocityMM","value":"Dx610.0"},{"name":"minDistanceMM","value":"Dx30.0"},{"name":"minVelocityMM","value":"Dx125.0"},{"name":"stopDrivetrain","value":"Bxtrue"},{"name":"targetAngleDEGREES","value":"Dx45"},{"name":"targetAngleToleranceDEGREES","value":"Dx0"},{"name":"targetPosMM","value":"Sx2420x0"},{"name":"timeoutMS","value":"Ix15000"}]},{"name":"03-00","comment":"@MoveToCoordinate - Trial run(s)","enabled":false,"variables":[{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"lerpMM_DOWN","value":"Dx305"},{"name":"lerpMM_UP","value":"Dx305"},{"name":"maxVelocityMM","value":"Dx610.0"},{"name":"minDistanceMM","value":"Dx30.0"},{"name":"minVelocityMM","value":"Dx125.0"},{"name":"stopDrivetrain","value":"Bxtrue"},{"name":"targetAngleDEGREES","value":"Dx45"},{"name":"targetAngleToleranceDEGREES","value":"Dx0"},{"name":"targetPosMM","value":"Sx0.0x0.0"},{"name":"timeoutMS","value":"Ix15000"}]},{"name":"99-00","comment":"@PathSelector - Pick path","enabled":true,"variables":[{"name":"minConfidence","value":"Dx0.7"},{"name":"path","value":"Ix-1"},{"name":"timeoutMS","value":"Ix2000000"}]}]},{"name":"Robot","actions":[{"name":"Claw_Tuning","comment":"Claws","enabled":true,"variables":[{"name":"claw_left_closed_position","value":"Dx0.2"},{"name":"claw_left_open_position","value":"Dx0.5"},{"name":"claw_right_closed_position","value":"Dx0.78"},{"name":"claw_right_open_position","value":"Dx0.5"}]},{"name":"ClawArm_Tuning","comment":"Claw Arm","enabled":true,"variables":[{"name":"collect_angle","value":"Dx242"},{"name":"collect_float_angle","value":"Dx237"},{"name":"deposit_angle","value":"Dx165.0"},{"name":"gear_ratio","value":"Dx1"},{"name":"kD","value":"Dx1"},{"name":"kF","value":"Dx0.0"},{"name":"kI","value":"Dx1.5"},{"name":"kP","value":"Dx6"},{"name":"KPosP","value":"Dx1"},{"name":"max_current_milliamps","value":"Dx1588.0"},{"name":"max_speed","value":"Dx0.5"},{"name":"max_velocityDEGREES","value":"Dx60"},{"name":"motor_ticks","value":"Ix8192"},{"name":"stow_angle","value":"Dx0"},{"name":"tolerance","value":"Ix288"},{"name":"warn_overcurrent_after_ms","value":"Lx5000"}]},{"name":"ClawWrist_Tuning","comment":"Claw Wrist","enabled":true,"variables":[{"name":"collect_float_position","value":"Dx0.52"},{"name":"collect_position","value":"Dx0.505"},{"name":"deposit_position","value":"Dx0.508"},{"name":"stow_position","value":"Dx0.74"}]},{"name":"Drivetrain_Tuning","comment":"Drivetrain","enabled":true,"variables":[{"name":"gear_ratio","value":"Dx13.0321"},{"name":"max_speed","value":"Dx0.5"},{"name":"motor_ticks","value":"Ix28"},{"name":"velocity_max_in_mm","value":"Dx610"},{"name":"velocity_slow_in_mm","value":"Dx250"},{"name":"wheel_diameter_mm","value":"Dx90"}]},{"name":"DroneLauncher_Tuning","comment":"Drone Launcher","enabled":true,"variables":[{"name":"initial_position","value":"Dx0.5"},{"name":"launch_confirmation_time_ms","value":"Ix1000"},{"name":"launch_position","value":"Dx0"}]},{"name":"HookArm_Tuning","comment":"Hook Arm","enabled":true,"variables":[{"name":"stow_position","value":"Dx0.35"},{"name":"up_position","value":"Dx0.8"}]},{"name":"Localizer","comment":"Deadwheel Odometry","enabled":true,"variables":[{"name":"forward_offset_mm","value":"Dx133.35"},{"name":"track_width_mm","value":"Dx387.35"},{"name":"wheel_diameter_mm","value":"Dx90.0"},{"name":"x_position_multiplier","value":"Dx0.675956739"},{"name":"y_position_multiplier","value":"Dx0.675956739"}]},{"name":"Winch_Tuning","comment":"Winch","enabled":true,"variables":[{"name":"max_speed","value":"Dx1.0"}]}]},{"name":"zAutonomous_BLUE_Audience","actions":[]},{"name":"zAutonomous_BLUE_Backstage","actions":[]}],"presets":{"groups":[],"actions":[{"name":"ClawArmMove","comment":"@ClawArmMove - Move claw arm","enabled":true,"variables":[{"name":"angle","value":"Dx0"},{"name":"power","value":"Dx0.5"},{"name":"timeoutMS","value":"Ix1000"},{"name":"toleranceAngle","value":"Dx1.5"}]},{"name":"Move","comment":"@Move - Move ta wheels matey!","enabled":true,"variables":[{"name":"distanceMM","value":"Dx300"},{"name":"lerpMM_DOWN","value":"Dx100"},{"name":"lerpMM_UP","value":"Dx100"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx250"},{"name":"strafe","value":"Bxfalse"},{"name":"timeoutMS","value":"Ix2000"},{"name":"toleranceMM","value":"Dx10"}]},{"name":"MoveToCoordinate","comment":"@MoveToCoordinate - Trial run(s)","enabled":true,"variables":[{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"lerpMM_DOWN","value":"Dx305"},{"name":"lerpMM_UP","value":"Dx305"},{"name":"maxVelocityMM","value":"Dx610.0"},{"name":"minDistanceMM","value":"Dx25.0"},{"name":"minVelocityMM","value":"Dx125.0"},{"name":"stopDrivetrain","value":"Bxtrue"},{"name":"targetAngleDEGREES","value":"Dx45"},{"name":"targetAngleToleranceDEGREES","value":"Dx5"},{"name":"targetPosMM","value":"Sx610.0x0.0"},{"name":"timeoutMS","value":"Ix15000"}]},{"name":"PathEnactor","comment":"@PathEnactor - Enact path","enabled":true,"variables":[]},{"name":"PathSelector","comment":"@PathSelector - Pick path","enabled":true,"variables":[{"name":"minConfidence","value":"Dx0.7"},{"name":"path","value":"Ix-1"},{"name":"timeoutMS","value":"Ix2000"}]},{"name":"Rotate","comment":"@Rotate - Rotate robot to face degree heading","enabled":true,"variables":[{"name":"headingDEGREES","value":"Dx0"},{"name":"lerpDEGREES","value":"Dx90.0"},{"name":"maxVelocityMM","value":"Dx610"},{"name":"minVelocityMM","value":"Dx50"},{"name":"timeoutMS","value":"Ix5000"},{"name":"toleranceDEGREES","value":"Dx0.5"}]},{"name":"ServoMove","comment":"@ServoMove - Move servo to position","enabled":true,"variables":[{"name":"lerp","value":"Bxtrue"},{"name":"lerpMS","value":"Dx1000"},{"name":"position","value":"Dx0.5"},{"name":"servoName","value":"SxleftClaw"},{"name":"timeoutMS","value":"Ix2000"}]}]}}} \ No newline at end of file diff --git a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/LEDControllerTask.java b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/LEDControllerTask.java new file mode 100644 index 0000000..9fae11e --- /dev/null +++ b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/LEDControllerTask.java @@ -0,0 +1,16 @@ +package dev.cyberarm.minibots.red_crab.engines; + +import dev.cyberarm.engine.V2.CyberarmState; +import dev.cyberarm.minibots.red_crab.RedCrabMinibot; + +public class LEDControllerTask extends CyberarmState { + private final RedCrabMinibot robot; + public LEDControllerTask(RedCrabMinibot robot) { + this.robot = robot; + } + + @Override + public void exec() { + robot.ledController(); + } +} diff --git a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousBlueAudienceEngine.java b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousBlueAudienceEngine.java index 7d121a6..64e48ba 100644 --- a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousBlueAudienceEngine.java +++ b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousBlueAudienceEngine.java @@ -14,6 +14,7 @@ public class RedCrabAutonomousBlueAudienceEngine extends RedCrabEngine { public void setup() { robot = new RedCrabMinibot(true); addTask(new ClawArmTask(robot)); + addTask(new LEDControllerTask(robot)); addTask(new LocalizerTask(robot)); setupFromConfig( diff --git a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousBlueBackstageEngine.java b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousBlueBackstageEngine.java index e43523e..f915c82 100644 --- a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousBlueBackstageEngine.java +++ b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousBlueBackstageEngine.java @@ -14,6 +14,7 @@ public class RedCrabAutonomousBlueBackstageEngine extends RedCrabEngine { public void setup() { robot = new RedCrabMinibot(true); addTask(new ClawArmTask(robot)); + addTask(new LEDControllerTask(robot)); addTask(new LocalizerTask(robot)); setupFromConfig( diff --git a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousDebuggingOnlyEngine.java b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousDebuggingOnlyEngine.java index c137332..9df7adf 100644 --- a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousDebuggingOnlyEngine.java +++ b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousDebuggingOnlyEngine.java @@ -14,6 +14,7 @@ public class RedCrabAutonomousDebuggingOnlyEngine extends RedCrabEngine { public void setup() { robot = new RedCrabMinibot(true); addTask(new ClawArmTask(robot)); + addTask(new LEDControllerTask(robot)); addTask(new LocalizerTask(robot)); setupFromConfig( diff --git a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousRedAudienceEngine.java b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousRedAudienceEngine.java index 6e0b0f8..fc6c3db 100644 --- a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousRedAudienceEngine.java +++ b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousRedAudienceEngine.java @@ -14,6 +14,7 @@ public class RedCrabAutonomousRedAudienceEngine extends RedCrabEngine { public void setup() { robot = new RedCrabMinibot(true); addTask(new ClawArmTask(robot)); + addTask(new LEDControllerTask(robot)); addTask(new LocalizerTask(robot)); setupFromConfig( diff --git a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousRedBackstageEngine.java b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousRedBackstageEngine.java index ffe38b6..0099695 100644 --- a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousRedBackstageEngine.java +++ b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabAutonomousRedBackstageEngine.java @@ -14,6 +14,7 @@ public class RedCrabAutonomousRedBackstageEngine extends RedCrabEngine { public void setup() { robot = new RedCrabMinibot(true); addTask(new ClawArmTask(robot)); + addTask(new LEDControllerTask(robot)); addTask(new LocalizerTask(robot)); setupFromConfig( diff --git a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabEngine.java b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabEngine.java index a995574..046641f 100644 --- a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabEngine.java +++ b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabEngine.java @@ -14,30 +14,6 @@ public abstract class RedCrabEngine extends CyberarmEngine { super.loop(); robot.standardTelemetry(); - - if (robot.autonomous) { - if (runTime() < 20_000.0) { // KEEP CALM and CARRY ON - robot.redLED.setState(robot.LED_OFF); - robot.greenLED.setState(robot.LED_ON); - } else if (runTime() < 25_000.0) { // RUNNING LOW ON TIME - robot.redLED.setState(robot.LED_ON); - robot.greenLED.setState(robot.LED_ON); - } else { // 5 SECONDS LEFT! - robot.redLED.setState(robot.LED_ON); - robot.greenLED.setState(robot.LED_OFF); - } - } else { - if (runTime() >= 90_000.0) { // LAUNCH DRONE and DO CHIN UP - robot.redLED.setState(robot.LED_OFF); - robot.greenLED.setState(robot.LED_ON); - } else if (runTime() >= 80_000.0) { // GET READY - robot.redLED.setState(robot.LED_ON); - robot.greenLED.setState(robot.LED_ON); - } else { // KEEP CALM and CARRY ON - robot.redLED.setState(robot.LED_ON); - robot.greenLED.setState(robot.LED_OFF); - } - } } @Override diff --git a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabTeleOpDebuggingOnlyEngine.java b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabTeleOpDebuggingOnlyEngine.java index 116c726..f9c5c52 100644 --- a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabTeleOpDebuggingOnlyEngine.java +++ b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabTeleOpDebuggingOnlyEngine.java @@ -18,6 +18,7 @@ public class RedCrabTeleOpDebuggingOnlyEngine extends RedCrabEngine { robot = new RedCrabMinibot(false); + addTask(new LEDControllerTask(robot)); addTask(new LocalizerTask(robot)); addState(new CyberarmState() { diff --git a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabTeleOpEngine.java b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabTeleOpEngine.java index 05eebda..c7d3a5b 100644 --- a/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabTeleOpEngine.java +++ b/TeamCode/src/main/java/dev/cyberarm/minibots/red_crab/engines/RedCrabTeleOpEngine.java @@ -16,6 +16,7 @@ public class RedCrabTeleOpEngine extends RedCrabEngine { robot = new RedCrabMinibot(false); addTask(new ClawArmTask(robot)); + addTask(new LEDControllerTask(robot)); addTask(new LocalizerTask(robot)); addState(new Pilot(robot));