Compare commits

...

11 Commits

Author SHA1 Message Date
f888e683ef Make FtcRobotControllerActivity startup TACNET server since the ControlHub appears to block ON_BOOT_COMPLETED receivers... 2021-12-08 17:39:37 -06:00
Spencer
05376d01d5 Updated configuration 2021-12-07 20:38:41 -06:00
Spencer
7d3649cb1d more auto work started configuring camera 2021-12-07 20:37:10 -06:00
Spencer
9532b9e8af added configuration 2021-12-05 16:04:35 -06:00
Spencer
1944e3c57b added configuration 2021-12-04 16:32:28 -06:00
Spencer
ee4e05f28d added configuration 2021-12-02 20:32:39 -06:00
Spencer
7332fe8a72 started working on configuration 2021-12-02 20:29:11 -06:00
Spencer
6136b0a3b5 made auto draft, and started on vuforia/tensorflow state
(:
2021-12-02 19:28:03 -06:00
Spencer
8f2f471667 created auto. states and made toggle for teleop (not tested yet) 2021-11-30 20:26:31 -06:00
Spencer
166b8091b8 Merge remote-tracking branch 'origin/master' 2021-11-28 15:25:39 -06:00
Spencer
9efd0ffcad need to add a toggle so that we can switch or invert the direction that the arm orbits. 2021-11-27 14:40:04 -06:00
16 changed files with 647 additions and 100 deletions

View File

@@ -49,6 +49,8 @@ import android.preference.PreferenceManager;
import androidx.annotation.NonNull;
import androidx.annotation.Nullable;
import androidx.annotation.StringRes;
import androidx.core.content.ContextCompat;
import android.view.Menu;
import android.view.MenuItem;
import android.view.MotionEvent;
@@ -410,6 +412,12 @@ public class FtcRobotControllerActivity extends Activity
checkPreferredChannel();
AnnotatedHooksClassFilter.getInstance().callOnCreateMethods(this);
/* REV CONTROL HUB APPEARS TO PREVENT ANY APP NOT ON ITS WHITELIST FROM USING ON_BOOT_COMPLETED RECEIVERS */
/* USING THIS HACK DUE TO THAT... */
Intent tacnetIntent = new Intent("org.timecrafters.TimeCraftersConfigurationTool.tacnet.ACTION_START_SERVER");
tacnetIntent.setPackage("org.timecrafters.TimeCraftersConfigurationTool");
ContextCompat.startForegroundService(context, tacnetIntent);
}
protected UpdateUI createUpdateUI() {

File diff suppressed because one or more lines are too long

View File

@@ -0,0 +1,58 @@
package org.timecrafters.FreightFrenzy.Competition.Autonomous.Engines;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import org.cyberarm.engine.V2.CyberarmEngine;
import org.timecrafters.FreightFrenzy.Competition.Autonomous.States.CollectorToggle;
import org.timecrafters.FreightFrenzy.Competition.Autonomous.States.DriveState;
import org.timecrafters.FreightFrenzy.Competition.Autonomous.States.TensorFlowState;
import org.timecrafters.FreightFrenzy.Competition.Autonomous.States.TurretArmExtension;
import org.timecrafters.FreightFrenzy.Competition.Autonomous.States.TurretArmRiser;
import org.timecrafters.FreightFrenzy.Competition.Autonomous.States.TurretOrbit;
import org.timecrafters.FreightFrenzy.Competition.Common.Robot;
@Autonomous (name = "Blue WareHouse", group = "blue")
public class BlueWarehouseEngine extends CyberarmEngine {
Robot robot;
@Override
public void setup() {
this.robot = new Robot(this);
addState(new TurretOrbit(robot, robot.turretServoWhite, robot.whiteMag, "BlueWarehouseAutonomous", "01_0"));
addState(new TensorFlowState(robot, robot.whiteArmRiser, robot.whiteArmBobbin, "BlueWarehouseAutonomous", "01_1"));
// addState(new TurretArmExtension(robot, robot.whiteArmBobbin, "BlueWarehouseAutonomous", "02_0"));
// addState(new TurretArmRiser(robot, robot.whiteArmRiser, "BlueWarehouseAutonomous", "03_0_middle"));
// addState(new TurretArmExtension(robot, robot.whiteArmBobbin, "BlueWarehouseAutonomous", "04_0_middle"));
addState(new CollectorToggle(robot, robot.collectorWhite, "BlueWarehouseAutonomous", "05_0"));
addState(new CollectorToggle(robot, robot.collectorWhite, "BlueWarehouseAutonomous", "06_0"));
addState(new TurretArmExtension(robot, robot.whiteArmBobbin, "BlueWarehouseAutonomous", "07_0"));
addState(new DriveState(robot,"BlueWarehouseAutonomous", "08_0"));
addState(new DriveState(robot, "BlueWarehouseAutonomous", "09_0"));
addState(new DriveState(robot, "BlueWarehouseAutonomous", "10_0"));
}
public void loop() {
super.loop();
telemetry.addData("white arm extension", robot.whiteArmBobbin.getCurrentPosition());
telemetry.addData("White Riser Arm", robot.whiteArmRiser.getCurrentPosition());
telemetry.addData("white Turret Switch", robot.whiteMag.isPressed());
telemetry.addData("white Turret orbit Power", robot.turretServoWhite.getPower());
telemetry.addData("White Door Position", robot.whiteDispenser.getPosition());
telemetry.addLine();
telemetry.addData("Orange Riser Arm", robot.orangeArmRiser.getCurrentPosition());
telemetry.addData("orange arm extension", robot.orangeArmBobbin.getCurrentPosition());
telemetry.addData("orange Turret Switch", robot.orangeMag.isPressed());
telemetry.addData("orange Turret Orbit Power", robot.turretServoOrange.getPower());
telemetry.addData("Orange Door Position", robot.orangeDispenser.getPosition());
telemetry.addLine();
telemetry.addData("driveWarehouseLeft", robot.driveWarehouseLeft.getCurrentPosition());
telemetry.addData("driveWarehouseRight", robot.driveWarehouseRight.getCurrentPosition());
telemetry.addData("driveGoalLeft", robot.driveGoalLeft.getCurrentPosition());
telemetry.addData("driveGoalRight", robot.driveGoalRight.getCurrentPosition());
}
}

View File

@@ -1,14 +1,59 @@
package org.timecrafters.FreightFrenzy.Competition.Autonomous.Engines;
import org.cyberarm.engine.V2.CyberarmEngine;
import org.timecrafters.FreightFrenzy.Competition.Autonomous.States.DriveState;
import org.timecrafters.FreightFrenzy.Competition.Common.Robot;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import org.cyberarm.engine.V2.CyberarmEngine;
import org.timecrafters.FreightFrenzy.Competition.Autonomous.States.CollectorToggle;
import org.timecrafters.FreightFrenzy.Competition.Autonomous.States.DepositorDoor;
import org.timecrafters.FreightFrenzy.Competition.Autonomous.States.DriveState;
import org.timecrafters.FreightFrenzy.Competition.Autonomous.States.TensorFlowState;
import org.timecrafters.FreightFrenzy.Competition.Autonomous.States.TurretArmExtension;
import org.timecrafters.FreightFrenzy.Competition.Autonomous.States.TurretArmRiser;
import org.timecrafters.FreightFrenzy.Competition.Autonomous.States.TurretOrbit;
import org.timecrafters.FreightFrenzy.Competition.Common.Robot;
@Autonomous (name = "Red WareHouse", group = "red")
public class RedWarehouseEngine extends CyberarmEngine {
Robot robot;
@Override
public void setup() {
Robot robot = new Robot(this);
this.robot = new Robot(this);
addState(new DriveState(robot, 2000, 2000,.25,.25));
addState(new TurretOrbit(robot, robot.turretServoWhite, robot.whiteMag, "RedWarehouseAutonomous", "01_0"));
addState(new TensorFlowState(robot, robot.whiteArmRiser, robot.whiteArmBobbin, "RedWarehouseAutonomous", "01_1"));
// addState(new TurretArmExtension(robot, robot.whiteArmBobbin, "RedWarehouseAutonomous", "02_0"));
// addState(new TurretArmRiser(robot, robot.whiteArmRiser, "RedWarehouseAutonomous", "03_0_middle"));
// addState(new TurretArmExtension(robot, robot.whiteArmBobbin, "RedWarehouseAutonomous", "04_0"));
addState(new CollectorToggle(robot, robot.collectorWhite, "RedWarehouseAutonomous", "05_0"));
addState(new CollectorToggle(robot, robot.collectorWhite, "RedWarehouseAutonomous", "06_0"));
addState(new TurretArmExtension(robot, robot.whiteArmBobbin, "RedWarehouseAutonomous", "07_0"));
addState(new DriveState(robot,"RedWarehouseAutonomous", "08_0"));
addState(new DriveState(robot, "RedWarehouseAutonomous", "09_0"));
addState(new TurretOrbit(robot, robot.turretServoWhite, null, "RedWarehouseAutonomous", "10_0"));
addState(new DriveState(robot, "RedWarehouseAutonomous", "10_1"));
}
public void loop() {
super.loop();
telemetry.addData("white arm extension", robot.whiteArmBobbin.getCurrentPosition());
telemetry.addData("White Riser Arm", robot.whiteArmRiser.getCurrentPosition());
telemetry.addData("white Turret Switch", robot.whiteMag.isPressed());
telemetry.addData("white Turret orbit Power", robot.turretServoWhite.getPower());
telemetry.addData("White Door Position", robot.whiteDispenser.getPosition());
telemetry.addLine();
telemetry.addData("Orange Riser Arm", robot.orangeArmRiser.getCurrentPosition());
telemetry.addData("orange arm extension", robot.orangeArmBobbin.getCurrentPosition());
telemetry.addData("orange Turret Switch", robot.orangeMag.isPressed());
telemetry.addData("orange Turret Orbit Power", robot.turretServoOrange.getPower());
telemetry.addData("Orange Door Position", robot.orangeDispenser.getPosition());
telemetry.addLine();
telemetry.addData("driveWarehouseLeft", robot.driveWarehouseLeft.getCurrentPosition());
telemetry.addData("driveWarehouseRight", robot.driveWarehouseRight.getCurrentPosition());
telemetry.addData("driveGoalLeft", robot.driveGoalLeft.getCurrentPosition());
telemetry.addData("driveGoalRight", robot.driveGoalRight.getCurrentPosition());
}
}

View File

@@ -0,0 +1,41 @@
package org.timecrafters.FreightFrenzy.Competition.Autonomous.States;
import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.hardware.Servo;
import org.cyberarm.engine.V2.CyberarmState;
import org.timecrafters.FreightFrenzy.Competition.Common.Robot;
public class CollectorToggle extends CyberarmState {
final static public int MODE_REVERSE = -1;
final static public int MODE_COLLECT = 1;
final static public int MODE_STOPPED = 0;
double time;
CRServo servo;
int power;
public CollectorToggle(Robot robot, CRServo servo, String groupName, String actionName) {
this.servo = servo;
this.power = robot.configuration.variable(groupName, actionName, "power").value();
this.time = robot.configuration.variable(groupName, actionName, "time").value();
}
@Override
public void exec() {
servo.setPower(power);
if (runTime() >= time){
servo.setPower(0);
setHasFinished(true);
}
}
@Override
public void telemetry() {
engine.telemetry.addData("runtime", runTime());
engine.telemetry.addData("time", time);
}
}

View File

@@ -0,0 +1,30 @@
package org.timecrafters.FreightFrenzy.Competition.Autonomous.States;
import com.qualcomm.robotcore.hardware.Servo;
import org.cyberarm.engine.V2.CyberarmState;
import org.timecrafters.FreightFrenzy.Competition.Common.Robot;
public class DepositorDoor extends CyberarmState {
Servo servo;
double targetPosition;
long time;
public DepositorDoor(Robot robot, Servo servo, String groupName, String actionName) {
this.servo = servo;
this.targetPosition = robot.configuration.variable(groupName, actionName, "targetPosition").value();
this.time = robot.configuration.variable(groupName, actionName, "time").value();
}
@Override
public void exec() {
if (runTime() < time) {
servo.setPosition(targetPosition);
}
else {
setHasFinished(true);
}
}
}

View File

@@ -7,14 +7,15 @@ import org.timecrafters.FreightFrenzy.Competition.Common.Robot;
public class DriveState extends CyberarmState {
Robot robot;
double distanceLeft, distanceRight, powerLeft, powerRight;
int distanceLeft, distanceRight;
double powerLeft, powerRight;
public DriveState(Robot robot, double distanceLeft, double distanceRight, double powerLeft, double powerRight) {
public DriveState(Robot robot, String groupName, String actionName) {
this.robot = robot;
this.distanceLeft = distanceLeft;
this.distanceRight = distanceRight;
this.powerLeft = powerLeft;
this.powerRight = powerRight;
this.distanceLeft = robot.configuration.variable(groupName, actionName, "distanceLeft").value();
this.distanceRight = robot.configuration.variable(groupName, actionName, "distanceRight").value();
this.powerLeft = robot.configuration.variable(groupName, actionName, "powerLeft").value();
this.powerRight = robot.configuration.variable(groupName, actionName, "powerRight").value();
}
@Override
@@ -32,7 +33,8 @@ public class DriveState extends CyberarmState {
@Override
public void exec() {
if (Math.abs(robot.driveGoalLeft.getCurrentPosition()) >= distanceLeft && Math.abs(robot.driveGoalRight.getCurrentPosition()) >= distanceRight) {
if (Math.abs(robot.driveGoalLeft.getCurrentPosition()) >= distanceLeft &&
Math.abs(robot.driveGoalRight.getCurrentPosition()) >= distanceRight) {
robot.driveGoalLeft.setPower(0);
robot.driveGoalRight.setPower(0);
robot.driveWarehouseRight.setPower(0);
@@ -45,6 +47,15 @@ public class DriveState extends CyberarmState {
robot.driveWarehouseLeft.setPower(powerLeft);
}
}
@Override
public void telemetry() {
engine.telemetry.addData("distance left", distanceLeft);
engine.telemetry.addData("distance right", distanceRight);
engine.telemetry.addData("power left", powerLeft);
engine.telemetry.addData("power Right", powerRight);
}
}

View File

@@ -0,0 +1,57 @@
package org.timecrafters.FreightFrenzy.Competition.Autonomous.States;
import com.qualcomm.robotcore.hardware.DcMotor;
import org.cyberarm.engine.V2.CyberarmState;
import org.timecrafters.FreightFrenzy.Competition.Common.Robot;
public class FaceState extends CyberarmState {
private double faceDirection, tolerance, power;
private Robot robot;
public FaceState(Robot robot, double faceDirection, double tolerance, double power) {
this.robot = robot;
this.faceDirection = faceDirection;
this.tolerance = tolerance;
this.power = power;
}
@Override
public void start() {
robot.driveGoalLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
robot.driveGoalRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
robot.driveWarehouseLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
robot.driveWarehouseRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
robot.driveGoalLeft.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
robot.driveGoalRight.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
robot.driveWarehouseLeft.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
robot.driveWarehouseRight.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
}
@Override
public void exec() {
robot.updateRobotOrientation();
if (robot.heading() - tolerance > faceDirection) {
robot.driveGoalLeft.setPower(power);
robot.driveWarehouseLeft.setPower(power);
robot.driveGoalRight.setPower(0);
robot.driveWarehouseRight.setPower(0);
}
else if (robot.heading() + tolerance < faceDirection){
robot.driveGoalLeft.setPower(0);
robot.driveWarehouseLeft.setPower(0);
robot.driveGoalRight.setPower(power);
robot.driveWarehouseRight.setPower(power);
}
else {
robot.driveGoalLeft.setPower(0);
robot.driveWarehouseLeft.setPower(0);
robot.driveGoalRight.setPower(0);
robot.driveWarehouseRight.setPower(0);
setHasFinished(true);
}
}
}

View File

@@ -0,0 +1,86 @@
package org.timecrafters.FreightFrenzy.Competition.Autonomous.States;
import com.qualcomm.robotcore.hardware.DcMotor;
import org.cyberarm.engine.V2.CyberarmState;
import org.firstinspires.ftc.robotcore.external.tfod.Recognition;
import org.timecrafters.FreightFrenzy.Competition.Common.Robot;
import java.util.List;
public class TensorFlowState extends CyberarmState {
Robot robot;
private List<Recognition> recognitions;
private double checkTime;
private int manualPath;
private int path = 0;
private String groupName;
private DcMotor armRiser, armExtension;
public TensorFlowState(Robot robot, DcMotor armRiser, DcMotor armExtension, String groupName, String actionName) {
this.robot = robot;
this.groupName = groupName;
this.armRiser = armRiser;
this.armExtension = armExtension;
}
@Override
public void start() {
robot.activateVuforia();
robot.activateTensorflow();
}
@Override
public void exec() {
recognitions = robot.tensorflowDetections();
//
if (runTime() < checkTime) {
if (manualPath != -1) {
if (recognitions != null) {
if (recognitions.size() == 1) {
Recognition recognition = recognitions.get(0);
if (recognition.getLabel().equals("duck")){
if (recognition.getLeft() < 320) {
path = 0;
} else {
path = 1;
}
}
} else {
path = 2;
}
}
}
} else {
if (path == 0){
addState(new TurretArmExtension(robot, armExtension, groupName, "02_0"));
addState(new TurretArmRiser(robot, armRiser, groupName, "03_0_bottom"));
addState(new TurretArmExtension(robot, armExtension, groupName, "04_0_bottom"));
} else if (path == 1){
addState(new TurretArmExtension(robot, armExtension, groupName, "02_0"));
addState(new TurretArmRiser(robot, armRiser, groupName, "03_0_middle"));
addState(new TurretArmExtension(robot, armExtension, groupName, "04_0_middle"));
} else {
addState(new TurretArmExtension(robot, armExtension, groupName, "02_0"));
addState(new TurretArmRiser(robot, armRiser, groupName, "03_0_top"));
addState(new TurretArmExtension(robot, armExtension, groupName, "04_0_top"));
}
setHasFinished(true);
}
}
@Override
public void telemetry() {
for (Recognition recognition : robot.tensorflowDetections()) {
engine.telemetry.addData("Label", recognition.getLabel());
engine.telemetry.addData("Left", recognition.getLeft());
engine.telemetry.addData("Top", recognition.getTop());
engine.telemetry.addData("Confidence", recognition.getConfidence());
}
}
}

View File

@@ -0,0 +1,43 @@
package org.timecrafters.FreightFrenzy.Competition.Autonomous.States;
import com.qualcomm.robotcore.hardware.DcMotor;
import org.cyberarm.engine.V2.CyberarmState;
import org.timecrafters.FreightFrenzy.Competition.Common.Robot;
public class TurretArmExtension extends CyberarmState {
private Robot robot;
private DcMotor motor;
private int targetPosition, tolerance;
private double power;
public TurretArmExtension(Robot robot, DcMotor motor, String groupName, String actionName) {
this.robot = robot;
this.motor = motor;
this.targetPosition = robot.configuration.variable(groupName, actionName, "targetPosition").value();
this.power = robot.configuration.variable(groupName, actionName, "power").value();
this.tolerance = robot.configuration.variable(groupName, actionName, "tolerance").value();
}
@Override
public void start() {
motor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
motor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
}
@Override
public void exec() {
if (motor.getCurrentPosition() < targetPosition - tolerance){
motor.setPower(power);
}
else if (motor.getCurrentPosition() > targetPosition + tolerance){
motor.setPower(-power);
}
else {
setHasFinished(true);
motor.setPower(0);
}
}
}

View File

@@ -0,0 +1,43 @@
package org.timecrafters.FreightFrenzy.Competition.Autonomous.States;
import com.qualcomm.robotcore.hardware.DcMotor;
import org.cyberarm.engine.V2.CyberarmState;
import org.timecrafters.FreightFrenzy.Competition.Common.Robot;
public class TurretArmRiser extends CyberarmState {
private Robot robot;
private DcMotor motor;
private int targetPosition, tolerance;
private double power;
public TurretArmRiser(Robot robot, DcMotor motor, String groupName, String actionName) {
this.robot = robot;
this.motor = motor;
this.targetPosition = robot.configuration.variable(groupName, actionName, "targetPosition").value();
this.power = robot.configuration.variable(groupName, actionName, "power").value();
this.tolerance = robot.configuration.variable(groupName, actionName, "tolerance").value();
}
@Override
public void start() {
motor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
motor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
}
@Override
public void exec() {
if (motor.getCurrentPosition() < targetPosition - tolerance){
motor.setPower(power);
}
else if (motor.getCurrentPosition() > targetPosition + tolerance){
motor.setPower(-power);
}
else {
setHasFinished(true);
motor.setPower(0);
}
}
}

View File

@@ -0,0 +1,35 @@
package org.timecrafters.FreightFrenzy.Competition.Autonomous.States;
import com.qualcomm.hardware.rev.RevTouchSensor;
import com.qualcomm.robotcore.hardware.CRServo;
import org.cyberarm.engine.V2.CyberarmState;
import org.timecrafters.FreightFrenzy.Competition.Common.Robot;
import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfiguration;
import org.timecrafters.TimeCraftersConfigurationTool.library.backend.config.Action;
public class TurretOrbit extends CyberarmState {
private Robot robot;
private CRServo servo;
private double time;
private double power;
private RevTouchSensor magnetSwitch;
public TurretOrbit(Robot robot, CRServo servo, RevTouchSensor magnetSwitch, String groupName, String actionName) {
this.robot = robot;
this.servo = servo;
this.time = robot.configuration.variable(groupName, actionName, "time").value();
this. power = robot.configuration.variable(groupName, actionName, "power").value();
this. magnetSwitch = magnetSwitch;
}
@Override
public void exec() {
if (magnetSwitch.isPressed() || runTime() < time ){
servo.setPower(0);
setHasFinished(true);
}
else {
servo.setPower(power);
}
}
}

View File

@@ -6,6 +6,7 @@ import static org.firstinspires.ftc.robotcore.external.navigation.AxesReference.
import com.qualcomm.hardware.bosch.BNO055IMU;
import com.qualcomm.hardware.rev.RevBlinkinLedDriver;
import com.qualcomm.hardware.rev.RevTouchSensor;
import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
@@ -65,9 +66,12 @@ public class Robot {
.translation(VUFORIA_CAMERA_FORWARD_DISPLACEMENT, VUFORIA_CAMERA_LEFT_DISPLACEMENT, VUFORIA_CAMERA_VERTICAL_DISPLACEMENT)
.multiplied(Orientation.getRotationMatrix(AxesReference.EXTRINSIC, AxesOrder.XZY, AngleUnit.DEGREES, 90, 90, 0));
private RobotLocation vuforiaLastLocation;
private Orientation orientation;
// Sensors
public BNO055IMU imu;
public RevTouchSensor whiteMag;
public RevTouchSensor orangeMag;
// Drivetrain
public static final double WHEEL_CIRCUMFERENCE = Math.PI * 8;
@@ -89,7 +93,7 @@ public class Robot {
public Robot(CyberarmEngine engine) {
this.engine = engine;
initMagnetSwitches();
initConfiguration();
initBlinkin();
initIMU();
@@ -97,20 +101,29 @@ public class Robot {
initCollector();
initDepositor();
initCarousel();
// initVuforia();
// initTensorflow();
initVuforia();
initTensorflow();
}
private void initMagnetSwitches() {
whiteMag = engine.hardwareMap.get(RevTouchSensor.class, "whiteMag");
orangeMag = engine.hardwareMap.get(RevTouchSensor.class, "orangeMag");
}
public double heading() {
return imu.getAngularOrientation().firstAngle;
return orientation.firstAngle;
}
public double roll() {
return imu.getAngularOrientation().secondAngle;
return orientation.secondAngle;
}
public double pitch() {
return imu.getAngularOrientation().thirdAngle;
return orientation.thirdAngle;
}
public void updateRobotOrientation(){
orientation = imu.getAngularOrientation();
}
public void activateTensorflow() {
@@ -209,12 +222,14 @@ public class Robot {
private void initCollector() {
orangeArmBobbin = engine.hardwareMap.dcMotor.get("orangeArmBobbin");
orangeDispenser = engine.hardwareMap.servo.get("orangeDispenser");
orangeArmBobbin.setDirection(DcMotorSimple.Direction.FORWARD);
orangeArmBobbin.setDirection(DcMotorSimple.Direction.REVERSE);
turretServoOrange = engine.hardwareMap.crservo.get("turretServoOrange");
orangeArmRiser = engine.hardwareMap.dcMotor.get("orangeArmRiser");
orangeArmRiser.setDirection(DcMotorSimple.Direction.FORWARD);
orangeArmRiser.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
collectorOrange = engine.hardwareMap.crservo.get("collectorOrange");
orangeDispenser.setPosition(0.5);
}
private void initDepositor(){

View File

@@ -1,5 +1,5 @@
package org.timecrafters.FreightFrenzy.Competition.TeleOp.Engines;
//adb connect 192.168.43.1
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.cyberarm.engine.V2.CyberarmEngine;

View File

@@ -1,6 +1,8 @@
package org.timecrafters.FreightFrenzy.Competition.TeleOp.States;
import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.Gamepad;
import org.cyberarm.engine.V2.CyberarmState;
import org.timecrafters.FreightFrenzy.Competition.Common.Robot;
@@ -8,22 +10,25 @@ import org.timecrafters.FreightFrenzy.Competition.Common.Robot;
public class TeleOpState extends CyberarmState {
Robot robot;
double maxDriveSpeed, maxCollectorArmSpeed, maxDepositorArmSpeed;
int maxArmTravelDistance;
int maxArmTravelDistance, minArmTravelDistance;
boolean armLimitToggle = false, orangeCollectorToggle = false, whiteCollectorToggle = false;
boolean allianceRedDriver1 = true, allianceRedDriver2 = true;
public TeleOpState(Robot robot) {
this.robot = robot;
maxDriveSpeed = 1;
maxCollectorArmSpeed = 1;
maxDepositorArmSpeed = 1;
minArmTravelDistance = 0;
maxArmTravelDistance = 4000;
}
@Override
public void start() {
super.start();
// FIXME: Don't reset when doing autonomous stuff
// FIXME: Fix unable to retract if reset mid-match
robot.whiteArmBobbin.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
robot.whiteArmBobbin.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
robot.orangeArmBobbin.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
@@ -43,19 +48,19 @@ public class TeleOpState extends CyberarmState {
// dispenser powered
if (engine.gamepad1.b){
robot.orangeDispenser.setPosition(.5);
}
// if not pressed dispenser off
else {
robot.orangeDispenser.setPosition(0);
}
// if not pressed dispenser off
else {
robot.orangeDispenser.setPosition(0.5);
}
// if one of triggers pressed arm extends or unextends, there is also a limit on how far arm can extend
if (robot.orangeArmBobbin.getCurrentPosition() <= maxArmTravelDistance && engine.gamepad1.left_trigger > 0) {
robot.orangeArmBobbin.setPower(engine.gamepad1.left_trigger * maxDepositorArmSpeed);
} else {
if (engine.gamepad1.left_trigger <= 0 && robot.orangeArmBobbin.getCurrentPosition() >= 0) {
if (engine.gamepad1.left_trigger <= 0 && robot.orangeArmBobbin.getCurrentPosition() >= minArmTravelDistance) {
robot.orangeArmBobbin.setPower(-engine.gamepad1.right_trigger * maxDepositorArmSpeed);
} else {
robot.orangeArmBobbin.setPower(0);
@@ -63,33 +68,17 @@ public class TeleOpState extends CyberarmState {
}
// if either of these buttons... move the servo
// turretServo1 = orange
if (engine.gamepad1.dpad_right || engine.gamepad1.dpad_left) {
if (engine.gamepad1.dpad_right) {
robot.turretServoOrange.setPower(-1);
}
if (engine.gamepad1.dpad_left) {
robot.turretServoOrange.setPower(1);
}
}
// if neither of these buttons... power off
else {
robot.turretServoOrange.setPower(0);
}
turretOrbitControl(engine.gamepad1, robot.turretServoOrange, allianceRedDriver1);
// if dpad verticles pressed arm rises or lowers...
if (engine.gamepad1.dpad_up || engine.gamepad1.dpad_down) {
if (engine.gamepad1.dpad_up) {
robot.orangeArmRiser.setPower(1);
robot.orangeArmRiser.setPower(0.8);
}
if (engine.gamepad1.dpad_down) {
robot.orangeArmRiser.setPower(-1);
robot.orangeArmRiser.setPower(-0.5);
}
}
// nothing pressed nothing move...
@@ -97,22 +86,6 @@ public class TeleOpState extends CyberarmState {
robot.orangeArmRiser.setPower(0);
}
// if bumpers pressed intake wheel move...
if (engine.gamepad1.right_bumper || engine.gamepad1.left_bumper) {
if (engine.gamepad1.right_bumper) {
robot.collectorOrange.setPower(1);
}
if (engine.gamepad1.left_bumper) {
robot.collectorOrange.setPower(-1);
}
}
// no bumpers pressed no wheel move...
else {
robot.collectorOrange.setPower(0);
}
// button x pressed carousel wheel move.
if (engine.gamepad1.x){
@@ -130,7 +103,7 @@ public class TeleOpState extends CyberarmState {
robot.whiteArmBobbin.setPower(engine.gamepad2.left_trigger * maxDepositorArmSpeed);
} else {
if (engine.gamepad2.left_trigger <= 0 && robot.whiteArmBobbin.getCurrentPosition() >= 0) {
if (engine.gamepad2.left_trigger <= 0 && robot.whiteArmBobbin.getCurrentPosition() >= minArmTravelDistance) {
robot.whiteArmBobbin.setPower(-engine.gamepad2.right_trigger * maxDepositorArmSpeed);
} else {
robot.whiteArmBobbin.setPower(0);
@@ -149,59 +122,160 @@ public class TeleOpState extends CyberarmState {
robot.whiteDispenser.setPosition(0);
}
// if either of these buttons move the servo
// turretServo2 = white
if (engine.gamepad2.dpad_right || engine.gamepad2.dpad_left) {
if (engine.gamepad2.dpad_right) {
robot.turretServoWhite.setPower(-1);
}
if (engine.gamepad2.dpad_left) {
robot.turretServoWhite.setPower(1);
}
}
// if neither of these buttons power off
else {
robot.turretServoWhite.setPower(0);
}
turretOrbitControl(engine.gamepad2, robot.turretServoWhite, allianceRedDriver2);
// if dpad verticles pressed arm rises or lowers
if (engine.gamepad2.dpad_down || engine.gamepad2.dpad_up) {
if (engine.gamepad2.dpad_up) {
robot.whiteArmRiser.setPower(-1);
robot.whiteArmRiser.setPower(8);
}
if (engine.gamepad2.dpad_down) {
robot.whiteArmRiser.setPower(1);
robot.whiteArmRiser.setPower(-0.5);
}
}
// nothing pressed nothing move...
else {
robot.whiteArmRiser.setPower(0);
}
if (engine.gamepad2.left_bumper || engine.gamepad2.right_bumper) {
if (engine.gamepad2.left_bumper) {
robot.collectorWhite.setPower(-1);
}
if (engine.gamepad2.right_bumper) {
robot.collectorWhite.setPower(1);
}
}
else {
robot.collectorWhite.setPower(0);
}
}
@Override
public void telemetry() {
engine.telemetry.addData("arm limit toggle", armLimitToggle);
engine.telemetry.addData("driver A turret inverted", allianceRedDriver1);
engine.telemetry.addData("driver B turret inverted", allianceRedDriver2);
engine.telemetry.addLine();
engine.telemetry.addData("white arm extension", robot.whiteArmBobbin.getCurrentPosition());
engine.telemetry.addData("White Riser Arm", robot.whiteArmRiser.getCurrentPosition());
engine.telemetry.addData("white collector toggle ", whiteCollectorToggle);
engine.telemetry.addData("white Turret Switch", robot.whiteMag.isPressed());
engine.telemetry.addData("white Turret orbit Power", robot.turretServoWhite.getPower());
engine.telemetry.addData("White Door Position", robot.whiteDispenser.getPosition());
engine.telemetry.addLine();
engine.telemetry.addData("Orange Riser Arm", robot.orangeArmRiser.getCurrentPosition());
engine.telemetry.addData("orange arm extension", robot.orangeArmBobbin.getCurrentPosition());
engine.telemetry.addData("orange collector toggle ", orangeCollectorToggle);
engine.telemetry.addData("orange Turret Switch", robot.orangeMag.isPressed());
engine.telemetry.addData("orange Turret Orbit Power", robot.turretServoOrange.getPower());
engine.telemetry.addData("Orange Door Position", robot.orangeDispenser.getPosition());
engine.telemetry.addLine();
engine.telemetry.addData("driveWarehouseLeft", robot.driveWarehouseLeft.getCurrentPosition());
engine.telemetry.addData("driveWarehouseRight", robot.driveWarehouseRight.getCurrentPosition());
engine.telemetry.addData("driveGoalLeft", robot.driveGoalLeft.getCurrentPosition());
engine.telemetry.addData("driveGoalRight", robot.driveGoalRight.getCurrentPosition());
}
@Override
public void buttonUp(Gamepad gamepad, String button) {
// this is a toggle of a limit for arm extension in the case of the robot crashes
// in the middle of the game we can bring the arm back in and extend and reset its position.
System.out.println("GamePad: " + gamepad.getGamepadId() + " Button: " + button);
if (button.equals("y")) {
System.out.println("Y has been pressed! (" + armLimitToggle + ")");
if (!armLimitToggle) {
armLimitToggle = true;
minArmTravelDistance = -8500;
maxArmTravelDistance = 8500;
} else {
armLimitToggle = false;
minArmTravelDistance = 0;
maxArmTravelDistance = 4000;
robot.orangeArmBobbin.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
robot.whiteArmBobbin.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
robot.orangeArmBobbin.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
robot.whiteArmBobbin.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
}
}
if (gamepad == engine.gamepad1) {
switch (button) {
case "left_bumper":
if (orangeCollectorToggle) {
orangeCollectorToggle = false;
robot.collectorOrange.setPower(0);
} else {
orangeCollectorToggle = true;
robot.collectorOrange.setPower(1);
}
break;
case "right_bumper":
if (orangeCollectorToggle) {
orangeCollectorToggle = false;
robot.collectorOrange.setPower(0);
} else {
orangeCollectorToggle = true;
robot.collectorOrange.setPower(-1);
}
break;
case "guide":
allianceRedDriver1 = !allianceRedDriver1;
break;
}
}
if (gamepad == engine.gamepad2) {
switch (button) {
case "left_bumper":
if (whiteCollectorToggle) {
whiteCollectorToggle = false;
robot.collectorWhite.setPower(0);
} else {
whiteCollectorToggle = true;
robot.collectorWhite.setPower(-1);
}
break;
case "right_bumper":
if (whiteCollectorToggle) {
whiteCollectorToggle = false;
robot.collectorWhite.setPower(0);
} else {
whiteCollectorToggle = true;
robot.collectorWhite.setPower(1);
}
break;
case "guide":
allianceRedDriver2 = !allianceRedDriver2;
break;
}
}
}
private void turretOrbitControl (Gamepad gamepad, CRServo turretServo, boolean bias){
// if either of these buttons... move the servo
// turretServo1 = orange
if (gamepad.dpad_right || gamepad.dpad_left) {
if (bias) {
if (gamepad.dpad_right) {
turretServo.setPower(-1);
}
if (gamepad.dpad_left) {
turretServo.setPower(1);
}
} else {
if (gamepad.dpad_right) {
turretServo.setPower(1);
}
if (gamepad.dpad_left) {
turretServo.setPower(-1);
}
}
} else {
turretServo.setPower(0);
}
}
}

View File

@@ -85,8 +85,8 @@ public class TensorFlowCheck extends CyberarmState {
setHasFinished(true);
}
}
}
@Override
public void telemetry() {
engine.telemetry.addData("Chosen Path", path);