mirror of
https://github.com/TimeCrafters/FTC_2022
synced 2025-12-15 21:22:33 +00:00
New autonomous steps are listed out with a couple states filled in (I put in the states I knew we don't need to change.
I changed the name of the testing folder to TeleOp because that is what the folder is, it's not for testing anymore and it keeps confusing me.
This commit is contained in:
@@ -13,7 +13,7 @@ import org.timecrafters.Autonomous.States.PathDecision;
|
||||
import org.timecrafters.Autonomous.States.RotationState;
|
||||
import org.timecrafters.Autonomous.States.ServoCameraRotate;
|
||||
import org.timecrafters.Autonomous.States.TopArm;
|
||||
import org.timecrafters.testing.states.PhoenixBot1;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
|
||||
@Autonomous (name = "Left Side")
|
||||
|
||||
|
||||
@@ -5,7 +5,6 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.timecrafters.Autonomous.States.CollectorDistanceState;
|
||||
import org.timecrafters.Autonomous.States.CollectorState;
|
||||
import org.timecrafters.Autonomous.States.ConeIdentification;
|
||||
import org.timecrafters.Autonomous.States.DriverParkPlaceState;
|
||||
import org.timecrafters.Autonomous.States.DriverState;
|
||||
import org.timecrafters.Autonomous.States.BottomArm;
|
||||
@@ -13,7 +12,7 @@ import org.timecrafters.Autonomous.States.PathDecision;
|
||||
import org.timecrafters.Autonomous.States.RotationState;
|
||||
import org.timecrafters.Autonomous.States.ServoCameraRotate;
|
||||
import org.timecrafters.Autonomous.States.TopArm;
|
||||
import org.timecrafters.testing.states.PhoenixBot1;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
|
||||
@Autonomous (name = "Right Side")
|
||||
|
||||
|
||||
@@ -0,0 +1,107 @@
|
||||
package org.timecrafters.Autonomous.Engines;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.timecrafters.Autonomous.States.BottomArm;
|
||||
import org.timecrafters.Autonomous.States.CollectorDistanceState;
|
||||
import org.timecrafters.Autonomous.States.CollectorState;
|
||||
import org.timecrafters.Autonomous.States.ConeIdentification;
|
||||
import org.timecrafters.Autonomous.States.DriverParkPlaceState;
|
||||
import org.timecrafters.Autonomous.States.DriverState;
|
||||
import org.timecrafters.Autonomous.States.PathDecision;
|
||||
import org.timecrafters.Autonomous.States.RotationState;
|
||||
import org.timecrafters.Autonomous.States.ServoCameraRotate;
|
||||
import org.timecrafters.Autonomous.States.TopArm;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
|
||||
@Autonomous (name = "Right Side")
|
||||
|
||||
public class ThreeConeCycleAutonomousEngine extends CyberarmEngine {
|
||||
PhoenixBot1 robot;
|
||||
|
||||
@Override
|
||||
public void setup() {
|
||||
robot = new PhoenixBot1(this);
|
||||
|
||||
// 1 Rotate camera down at the signal
|
||||
addState(new ServoCameraRotate(robot, "ThreeConeCycleAutonomousRight", "01-0"));
|
||||
// 2 Scan custom image
|
||||
addState(new ConeIdentification(robot, "ThreeConeCycleAutonomousRight", "02-0"));
|
||||
// 3 Rotate Camera up, out of the way so it doesn't crash into stuff
|
||||
addState(new ServoCameraRotate(robot, "ThreeConeCycleAutonomousRight", "03-0"));
|
||||
// 4 Drive to the tall Pole (not all the way) while raising upper arm, this will be parallel
|
||||
|
||||
// 5 Turn Towards and look for junction with sensor
|
||||
|
||||
// 6 Raise lower arm while slowly driving at the junction
|
||||
|
||||
// 7 Drop top arm down on the junction to place cone
|
||||
|
||||
// 8 Drop cone as soon as arm is in position
|
||||
|
||||
// 9 Raise arm to clear junction
|
||||
|
||||
// 10 Back up and bring lower arm down (parallel state)
|
||||
|
||||
// 11 Bring upper arm to the correct position for the top cone on stack (check with distance sensor)
|
||||
|
||||
// 12 Rotate towards stack (this might be parallel with last step)
|
||||
|
||||
// 13 Drive at stack while collecting and check to see when we grab it
|
||||
|
||||
// 14 Back up and raise arm (in parallel state)
|
||||
|
||||
// 15 Drive All the way back to the medium Junction and raise upper arm (parallel state)
|
||||
|
||||
// 16 Rotate and use sensor to find junction
|
||||
|
||||
// 17 Drive Towards Junction (This is optional, idk if this is needed atm)
|
||||
|
||||
// 18 Bring upper arm down
|
||||
|
||||
// 19 Drop cone
|
||||
addState(new CollectorState(robot, "ThreeConeCycleAutonomousRight", "17-0"));
|
||||
|
||||
// 20 Bring upper arm up
|
||||
|
||||
// 21 Drive away from Junction (this is optional and only used if we use the drive forward from earlier)
|
||||
|
||||
// 22 Drop the Upper arm to the position of the new top cone / 4th cone and check with sensor and start driving fast to get to the stack (this is a parallel state)
|
||||
|
||||
// 23 Drive slower at the stack and run the collector to grab a 2nd cone off of the stack
|
||||
addState(new CollectorDistanceState(robot, "ThreeConeCycleAutonomousRight", "21-0"));
|
||||
|
||||
// 24 Drive Back and lift up all the way to position for the low junction (parallel state)
|
||||
|
||||
// 25 Drive back faster after the cone is fully off of the stack
|
||||
|
||||
// 26 Turn and look for the low junction with the distance sensor and align
|
||||
|
||||
// 27 Drive forward / backwards if you need to. (check with distance sensor)
|
||||
|
||||
// 28 Bring Upper arm down on junction
|
||||
|
||||
// 29 Let go of cone right after arm is in position
|
||||
|
||||
// 30 Raise arm as soon as the cone is dropped
|
||||
|
||||
// 31 Back up / go forward (optional, only needed if we drove forwards or backwards to align to low junction
|
||||
|
||||
// 32 Rotate towards Stack of cones
|
||||
|
||||
// 33 Decide which path after scanning image from earlier
|
||||
|
||||
// 34 Drive backwards, forwards, or stay put
|
||||
|
||||
// 35 Rotate towards alliance terminal
|
||||
|
||||
}
|
||||
|
||||
@Override
|
||||
public void loop() {
|
||||
super.loop();
|
||||
|
||||
telemetry.addData("BlackBoard Input", blackboard.get("parkPlace"));
|
||||
}
|
||||
}
|
||||
@@ -1,7 +1,7 @@
|
||||
package org.timecrafters.Autonomous.States;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.testing.states.PhoenixBot1;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
|
||||
public class BottomArm extends CyberarmState {
|
||||
|
||||
|
||||
@@ -4,7 +4,7 @@ import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.timecrafters.testing.states.PhoenixBot1;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
|
||||
public class CollectorDistanceState extends CyberarmState {
|
||||
|
||||
|
||||
@@ -2,7 +2,7 @@ package org.timecrafters.Autonomous.States;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.timecrafters.testing.states.PhoenixBot1;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
|
||||
public class CollectorState extends CyberarmState {
|
||||
|
||||
|
||||
@@ -1,10 +1,8 @@
|
||||
package org.timecrafters.Autonomous.States;
|
||||
|
||||
import static org.firstinspires.ftc.robotcore.external.BlocksOpModeCompanion.telemetry;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.firstinspires.ftc.robotcore.external.tfod.Recognition;
|
||||
import org.timecrafters.testing.states.PhoenixBot1;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
|
||||
import java.util.List;
|
||||
|
||||
|
||||
@@ -3,7 +3,7 @@ package org.timecrafters.Autonomous.States;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.testing.states.PhoenixBot1;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
|
||||
public class DriverParkPlaceState extends CyberarmState {
|
||||
private final boolean stateDisabled;
|
||||
|
||||
@@ -3,7 +3,7 @@ package org.timecrafters.Autonomous.States;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.testing.states.PhoenixBot1;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
|
||||
public class DriverState extends CyberarmState {
|
||||
private final boolean stateDisabled;
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
package org.timecrafters.Autonomous.States;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.testing.states.PhoenixBot1;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
|
||||
public class PathDecision extends CyberarmState {
|
||||
PhoenixBot1 robot;
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
package org.timecrafters.Autonomous.States;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.testing.states.PhoenixBot1;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
|
||||
public class RotationState extends CyberarmState {
|
||||
private final boolean stateDisabled;
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
package org.timecrafters.Autonomous.States;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.testing.states.PhoenixBot1;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
|
||||
public class ServoCameraRotate extends CyberarmState {
|
||||
private final boolean stateDisabled;
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
package org.timecrafters.Autonomous.States;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.testing.states.PhoenixBot1;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
|
||||
public class TopArm extends CyberarmState {
|
||||
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
package org.timecrafters.testing.engine;
|
||||
package org.timecrafters.TeleOp.engine;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.timecrafters.testing.states.AdafruitIMUState;
|
||||
import org.timecrafters.TeleOp.states.AdafruitIMUState;
|
||||
@TeleOp (name = "Adafruit IMU")
|
||||
public class AdafruitIMU extends CyberarmEngine {
|
||||
@Override
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.testing.engine;
|
||||
package org.timecrafters.TeleOp.engine;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
|
||||
@@ -1,10 +1,8 @@
|
||||
package org.timecrafters.testing.engine;
|
||||
package org.timecrafters.TeleOp.engine;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfiguration;
|
||||
|
||||
@TeleOp(name = "DynamicSetupEngine")
|
||||
@@ -1,11 +1,9 @@
|
||||
package org.timecrafters.testing.engine;
|
||||
package org.timecrafters.TeleOp.engine;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.Gamepad;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.timecrafters.testing.states.PhoenixBot1;
|
||||
import org.timecrafters.testing.states.PhoenixTeleOPState;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
|
||||
@TeleOp (name = "APhoenixTeleOP")
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.testing.engine;
|
||||
package org.timecrafters.TeleOp.engine;
|
||||
|
||||
import com.qualcomm.hardware.bosch.BNO055IMU;
|
||||
import com.qualcomm.robotcore.hardware.CRServo;
|
||||
@@ -1,11 +1,9 @@
|
||||
package org.timecrafters.testing.engine;
|
||||
package org.timecrafters.TeleOp.engine;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.timecrafters.testing.states.LaserState;
|
||||
import org.timecrafters.testing.states.SodiLEDState;
|
||||
import org.timecrafters.testing.states.SodiState;
|
||||
import org.timecrafters.TeleOp.states.LaserState;
|
||||
|
||||
@TeleOp(name = "Wheel")
|
||||
public class SodiEngine extends CyberarmEngine {
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.testing.engine;
|
||||
package org.timecrafters.TeleOp.engine;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.Gamepad;
|
||||
@@ -6,8 +6,8 @@ import com.qualcomm.robotcore.hardware.Gamepad;
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.cyberarm.engine.V2.GamepadChecker;
|
||||
import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfiguration;
|
||||
import org.timecrafters.testing.states.PhoenixBot1;
|
||||
import org.timecrafters.testing.states.TeleOPSpeedrunState;
|
||||
import org.timecrafters.TeleOp.states.PhoenixBot1;
|
||||
import org.timecrafters.TeleOp.states.TeleOPSpeedrunState;
|
||||
|
||||
@TeleOp (name = "Speedrun Engine")
|
||||
public class SpeedrunEngine extends CyberarmEngine {
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import com.qualcomm.hardware.adafruit.AdafruitBNO055IMU;
|
||||
import com.qualcomm.hardware.bosch.BNO055IMU;
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.firstinspires.ftc.robotcore.external.tfod.Recognition;
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.testing.engine.DynamicSetupEngine;
|
||||
import org.timecrafters.TeleOp.engine.DynamicSetupEngine;
|
||||
|
||||
public class DynamicSetupState extends CyberarmState {
|
||||
private long delay;
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import com.qualcomm.hardware.rev.Rev2mDistanceSensor;
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import com.qualcomm.hardware.rev.Rev2mDistanceSensor;
|
||||
import com.qualcomm.hardware.rev.RevBlinkinLedDriver;
|
||||
@@ -1,8 +1,7 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import com.qualcomm.hardware.adafruit.AdafruitI2cColorSensor;
|
||||
import com.qualcomm.hardware.bosch.BNO055IMU;
|
||||
import com.qualcomm.hardware.modernrobotics.ModernRoboticsI2cColorSensor;
|
||||
import com.qualcomm.hardware.rev.Rev2mDistanceSensor;
|
||||
import com.qualcomm.robotcore.hardware.CRServo;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
@@ -1,11 +1,10 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import android.annotation.SuppressLint;
|
||||
|
||||
import com.qualcomm.hardware.bosch.BNO055IMU;
|
||||
import com.qualcomm.robotcore.hardware.Gamepad;
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
import com.vuforia.Vuforia;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.cyberarm.engine.V2.GamepadChecker;
|
||||
@@ -89,13 +88,13 @@ public class PhoenixTeleOPState extends CyberarmState {
|
||||
}
|
||||
|
||||
if (Math.abs(engine.gamepad1.left_stick_y) > 0.05) {
|
||||
drivePower = engine.gamepad1.left_stick_y * 0.3;
|
||||
drivePower = engine.gamepad1.left_stick_y * 0.35;
|
||||
robot.backRightDrive.setPower(drivePower);
|
||||
robot.frontRightDrive.setPower(drivePower);
|
||||
}
|
||||
|
||||
if (Math.abs(engine.gamepad1.right_stick_y) > 0.05) {
|
||||
drivePower = engine.gamepad1.right_stick_y * 0.3;
|
||||
drivePower = engine.gamepad1.right_stick_y * 0.35;
|
||||
robot.backLeftDrive.setPower(drivePower);
|
||||
robot.frontLeftDrive.setPower(drivePower);
|
||||
}
|
||||
@@ -1,6 +1,5 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
|
||||
public class PhoenixTeleOPv2 extends CyberarmState {
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
|
||||
@@ -1,9 +1,8 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import com.qualcomm.hardware.rev.RevBlinkinLedDriver;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.minibots.cyberarm.engines.Common;
|
||||
|
||||
public class SodiLEDState extends CyberarmState {
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.CRServo;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
@@ -1,9 +1,6 @@
|
||||
package org.timecrafters.testing.states;
|
||||
|
||||
import com.qualcomm.hardware.rev.RevBlinkinLedDriver;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.minibots.cyberarm.states.MecanumRobot;
|
||||
|
||||
|
||||
public class SteeringDriveExperiment extends CyberarmState {
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.testing.states;
|
||||
package org.timecrafters.TeleOp.states;
|
||||
|
||||
import com.qualcomm.hardware.bosch.BNO055IMU;
|
||||
import com.qualcomm.robotcore.hardware.Gamepad;
|
||||
@@ -9,7 +9,7 @@ import org.cyberarm.engine.V2.GamepadChecker;
|
||||
public class TeleOPTankDriver extends CyberarmState {
|
||||
|
||||
private final PhoenixBot1 robot;
|
||||
private double drivePower = 1;
|
||||
private double drivePower = 0.3;
|
||||
private double RobotRotation;
|
||||
private double RotationTarget, DeltaRotation;
|
||||
private double MinimalPower = 0.2;
|
||||
Reference in New Issue
Block a user