mirror of
https://github.com/TimeCrafters/FTC_2022
synced 2025-12-15 21:22:33 +00:00
LeftSideAutonomous has drive backward and forward states after rotating towards both of the junctions for allignment. and it is organized
This commit is contained in:
@@ -27,6 +27,8 @@ public class LeftSideAutonomousEngine extends CyberarmEngine {
|
|||||||
addState(new DriverState(robot, "LeftSideAutonomous", "01-0"));
|
addState(new DriverState(robot, "LeftSideAutonomous", "01-0"));
|
||||||
//turn towards high pole
|
//turn towards high pole
|
||||||
addState(new RotationState(robot, "LeftSideAutonomous", "02-0"));
|
addState(new RotationState(robot, "LeftSideAutonomous", "02-0"));
|
||||||
|
//drive back
|
||||||
|
addState(new DriverState(robot, "LeftSideAutonomous", "02-1"));
|
||||||
//lift the upper arm
|
//lift the upper arm
|
||||||
addState(new TopArm(robot, "LeftSideAutonomous", "03-0"));
|
addState(new TopArm(robot, "LeftSideAutonomous", "03-0"));
|
||||||
//lift the lower arm
|
//lift the lower arm
|
||||||
|
|||||||
@@ -27,6 +27,8 @@ public class RightSideAutonomousEngine extends CyberarmEngine {
|
|||||||
addState(new DriverState(robot, "RightSideAutonomous", "01-0"));
|
addState(new DriverState(robot, "RightSideAutonomous", "01-0"));
|
||||||
//turn towards high pole
|
//turn towards high pole
|
||||||
addState(new RotationState(robot, "RightSideAutonomous", "02-0"));
|
addState(new RotationState(robot, "RightSideAutonomous", "02-0"));
|
||||||
|
// drive back
|
||||||
|
addState(new DriverState(robot, "RightSideAutonomous", "02-1"));
|
||||||
//lift the upper arm
|
//lift the upper arm
|
||||||
addState(new TopArm(robot, "RightSideAutonomous", "03-0"));
|
addState(new TopArm(robot, "RightSideAutonomous", "03-0"));
|
||||||
//lift the lower arm
|
//lift the lower arm
|
||||||
|
|||||||
@@ -20,6 +20,9 @@ public class CollectorDistanceState extends CyberarmState {
|
|||||||
private double distanceDelta;
|
private double distanceDelta;
|
||||||
private double debugRunTime;
|
private double debugRunTime;
|
||||||
private String debugStatus = "?";
|
private String debugStatus = "?";
|
||||||
|
private boolean inRange = false;
|
||||||
|
private float collectTime;
|
||||||
|
private double inRangeTime;
|
||||||
|
|
||||||
|
|
||||||
public CollectorDistanceState(PrototypeBot1 robot, String groupName, String actionName) {
|
public CollectorDistanceState(PrototypeBot1 robot, String groupName, String actionName) {
|
||||||
@@ -28,6 +31,7 @@ public class CollectorDistanceState extends CyberarmState {
|
|||||||
this.traveledDistance = robot.configuration.variable(groupName, actionName, "traveledDistance").value();
|
this.traveledDistance = robot.configuration.variable(groupName, actionName, "traveledDistance").value();
|
||||||
this.RampUpDistance = robot.configuration.variable(groupName, actionName, "RampUpDistance").value();
|
this.RampUpDistance = robot.configuration.variable(groupName, actionName, "RampUpDistance").value();
|
||||||
this.RampDownDistance = robot.configuration.variable(groupName, actionName, "RampDownDistance").value();
|
this.RampDownDistance = robot.configuration.variable(groupName, actionName, "RampDownDistance").value();
|
||||||
|
this.collectTime = robot.configuration.variable(groupName, actionName, "collectTime").value();
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -147,9 +151,18 @@ public class CollectorDistanceState extends CyberarmState {
|
|||||||
robot.frontLeftDrive.setPower(0);
|
robot.frontLeftDrive.setPower(0);
|
||||||
robot.backRightDrive.setPower(0);
|
robot.backRightDrive.setPower(0);
|
||||||
robot.backLeftDrive.setPower(0);
|
robot.backLeftDrive.setPower(0);
|
||||||
robot.collectorRight.setPower(0);
|
|
||||||
robot.collectorLeft.setPower(0);
|
if (!inRange){
|
||||||
setHasFinished(true);
|
inRange = true;
|
||||||
|
inRangeTime = runTime();
|
||||||
|
} else {
|
||||||
|
|
||||||
|
if (runTime() - inRangeTime >= collectTime){
|
||||||
|
robot.collectorRight.setPower(0);
|
||||||
|
robot.collectorLeft.setPower(0);
|
||||||
|
setHasFinished(true);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user