mirror of
https://github.com/TimeCrafters/FTC_2022
synced 2025-12-15 20:12:35 +00:00
Autonomous config
This commit is contained in:
@@ -17,7 +17,7 @@ import org.timecrafters.Autonomous.States.ServoCameraRotate;
|
|||||||
import org.timecrafters.Autonomous.States.TopArm;
|
import org.timecrafters.Autonomous.States.TopArm;
|
||||||
import org.timecrafters.Autonomous.TeleOp.states.PhoenixBot1;
|
import org.timecrafters.Autonomous.TeleOp.states.PhoenixBot1;
|
||||||
|
|
||||||
@Autonomous (name = "left 2 cone auto")
|
//@Autonomous (name = "left 2 cone auto")
|
||||||
|
|
||||||
public class LeftTwoConeAutonomousEngine extends CyberarmEngine {
|
public class LeftTwoConeAutonomousEngine extends CyberarmEngine {
|
||||||
PhoenixBot1 robot;
|
PhoenixBot1 robot;
|
||||||
|
|||||||
@@ -5,6 +5,7 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
|||||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||||
import org.timecrafters.Autonomous.States.DriverStateWithOdometer;
|
import org.timecrafters.Autonomous.States.DriverStateWithOdometer;
|
||||||
import org.timecrafters.Autonomous.States.RotationState;
|
import org.timecrafters.Autonomous.States.RotationState;
|
||||||
|
import org.timecrafters.Autonomous.States.TopArmv2;
|
||||||
import org.timecrafters.Autonomous.TeleOp.states.PhoenixBot1;
|
import org.timecrafters.Autonomous.TeleOp.states.PhoenixBot1;
|
||||||
|
|
||||||
@Autonomous(name = "Right Side")
|
@Autonomous(name = "Right Side")
|
||||||
@@ -16,15 +17,17 @@ public class RightStateAutoEngine extends CyberarmEngine {
|
|||||||
robot = new PhoenixBot1(this);
|
robot = new PhoenixBot1(this);
|
||||||
robot.imu.resetYaw();
|
robot.imu.resetYaw();
|
||||||
|
|
||||||
// setupFromConfig(
|
setupFromConfig(
|
||||||
// robot.configuration,
|
robot.configuration,
|
||||||
// "org.timecrafters.Autonomous.States",
|
"org.timecrafters.Autonomous.States",
|
||||||
// robot,
|
robot,
|
||||||
// PhoenixBot1.class,
|
PhoenixBot1.class,
|
||||||
// "Right State Auto");
|
"Right State Auto");
|
||||||
|
|
||||||
|
// addState(new TopArmv2(robot, "Right State Auto", "06-0"));
|
||||||
|
|
||||||
// // driving forward to low junction
|
// // driving forward to low junction
|
||||||
addState(new DriverStateWithOdometer(robot, "Right State Auto", "02-0"));
|
// addState(new DriverStateWithOdometer(robot, "Right State Auto", "02-0"));
|
||||||
// // rotate left towards low junction
|
// // rotate left towards low junction
|
||||||
// addState(new RotationState(robot, "Right State Auto", "02-1"));
|
// addState(new RotationState(robot, "Right State Auto", "02-1"));
|
||||||
// // driving forward/ backwards to adjust
|
// // driving forward/ backwards to adjust
|
||||||
|
|||||||
@@ -17,7 +17,7 @@ import org.timecrafters.Autonomous.States.ServoCameraRotate;
|
|||||||
import org.timecrafters.Autonomous.States.TopArm;
|
import org.timecrafters.Autonomous.States.TopArm;
|
||||||
import org.timecrafters.Autonomous.TeleOp.states.PhoenixBot1;
|
import org.timecrafters.Autonomous.TeleOp.states.PhoenixBot1;
|
||||||
|
|
||||||
@Autonomous (name = "Right 2 cone auto")
|
//@Autonomous (name = "Right 2 cone auto")
|
||||||
|
|
||||||
public class RightTwoConeAutonomousEngine extends CyberarmEngine {
|
public class RightTwoConeAutonomousEngine extends CyberarmEngine {
|
||||||
PhoenixBot1 robot;
|
PhoenixBot1 robot;
|
||||||
|
|||||||
@@ -52,8 +52,8 @@ public class CollectorState extends CyberarmState {
|
|||||||
}
|
}
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
// robot.collectorLeft.setPower(0);
|
robot.collectorLeft.setPower(0);
|
||||||
// robot.collectorRight.setPower(0);
|
robot.collectorRight.setPower(0);
|
||||||
setHasFinished(true);
|
setHasFinished(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -287,7 +287,7 @@ public class DriverStateWithOdometer extends CyberarmState {
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (driveStage == 5) {
|
if (driveStage == 5) {
|
||||||
// setHasFinished(true);
|
setHasFinished(true);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -104,7 +104,7 @@ public class RotationState extends CyberarmState {
|
|||||||
robot.backLeftDrive.setPower(0);
|
robot.backLeftDrive.setPower(0);
|
||||||
|
|
||||||
RotationStage ++;
|
RotationStage ++;
|
||||||
// setHasFinished(true);
|
setHasFinished(true);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -0,0 +1,36 @@
|
|||||||
|
package org.timecrafters.Autonomous.States;
|
||||||
|
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
|
||||||
|
import org.cyberarm.engine.V2.CyberarmState;
|
||||||
|
import org.timecrafters.Autonomous.TeleOp.states.PhoenixBot1;
|
||||||
|
|
||||||
|
public class TopArmv2 extends CyberarmState {
|
||||||
|
private final PhoenixBot1 robot;
|
||||||
|
private double targetPower;
|
||||||
|
private int targetPosition;
|
||||||
|
private int tolerance;
|
||||||
|
|
||||||
|
|
||||||
|
public TopArmv2(PhoenixBot1 robot, String groupName, String actionName) {
|
||||||
|
this.robot = robot;
|
||||||
|
this.targetPosition = robot.configuration.variable(groupName, actionName, "targetPosition").value();
|
||||||
|
this.targetPower = robot.configuration.variable(groupName, actionName, "targetPower").value();
|
||||||
|
this.tolerance = robot.configuration.variable(groupName, actionName, "tolerance").value();
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void start() {
|
||||||
|
robot.ArmMotor.setTargetPosition(targetPosition);
|
||||||
|
robot.ArmMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
|
||||||
|
robot.ArmMotor.setPower(targetPower);
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void exec() {
|
||||||
|
|
||||||
|
if (robot.ArmMotor.getTargetPosition() == targetPosition) {
|
||||||
|
setHasFinished(true);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
Reference in New Issue
Block a user