mirror of
https://github.com/TimeCrafters/FTC_2022
synced 2025-12-15 21:22:33 +00:00
Removed invalid CyberarmState#exac
This commit is contained in:
@@ -232,6 +232,4 @@ public abstract class CyberarmState implements Runnable {
|
||||
public String progressBar(int width, double percentCompleted) {
|
||||
return progressBar(width, percentCompleted, "=", " ");
|
||||
}
|
||||
|
||||
public abstract void exac();
|
||||
}
|
||||
@@ -1,117 +1,112 @@
|
||||
package org.timecrafters.minibots.cyberarm.states;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.Gamepad;
|
||||
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.minibots.cyberarm.MecanumMinibot;
|
||||
|
||||
|
||||
public class MecanumMinibotTeleOpState extends CyberarmState {
|
||||
private final MecanumMinibot robot;
|
||||
private float speed;
|
||||
|
||||
public MecanumMinibotTeleOpState(MecanumMinibot robot) {
|
||||
this.robot = robot;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void exec() {
|
||||
|
||||
/* ............................................................................ drive */
|
||||
speed = 1.0f - engine.gamepad1.left_trigger;
|
||||
|
||||
if (engine.gamepad1.y) {
|
||||
robot.driveAll(speed);
|
||||
} else if (engine.gamepad1.a) {
|
||||
robot.driveAll(-speed);
|
||||
} else if (engine.gamepad1.x) {
|
||||
robot.driveStrafe(MecanumMinibot.STRAFE_LEFT, speed);
|
||||
} else if (engine.gamepad1.b) {
|
||||
robot.driveStrafe(MecanumMinibot.STRAFE_RIGHT, speed);
|
||||
|
||||
} else if (engine.gamepad1.left_bumper) {
|
||||
robot.driveTurn(MecanumMinibot.TURN_LEFT, speed);
|
||||
|
||||
} else if (engine.gamepad1.right_bumper) {
|
||||
robot.driveTurn(MecanumMinibot.TURN_RIGHT, speed);
|
||||
} else {
|
||||
robot.driveStop();
|
||||
}
|
||||
/* ............................................................................ elevator */
|
||||
if(engine.gamepad1.dpad_up ||
|
||||
engine.gamepad2.y){
|
||||
robot.pServoElevate.setPower(1.0);
|
||||
}
|
||||
else if(engine.gamepad1.dpad_down ||
|
||||
engine.gamepad2.a){
|
||||
robot.pServoElevate.setPower(-1.0);
|
||||
}
|
||||
else{
|
||||
robot.pServoElevate.setPower((0.0));
|
||||
}
|
||||
|
||||
/* ............................................................................ arch */
|
||||
if(Math.abs(engine.gamepad1.left_stick_y)>0.1 ||
|
||||
Math.abs(engine.gamepad2.left_stick_y)>0.1){
|
||||
robot.pServoArch.setPower(engine.gamepad1.left_stick_y + engine.gamepad2.left_stick_y);
|
||||
}
|
||||
else{
|
||||
robot.pServoArch.setPower((0.0));
|
||||
}
|
||||
|
||||
/* ............................................................................ rotate */
|
||||
if(engine.gamepad1.dpad_right ||
|
||||
engine.gamepad2.dpad_right){ // up position
|
||||
robot.pServoRotate.setPosition(0.0);
|
||||
}
|
||||
if(engine.gamepad1.dpad_left ||
|
||||
engine.gamepad2.dpad_left){ // down position
|
||||
robot.pServoRotate.setPosition(0.70);
|
||||
}
|
||||
|
||||
/* ............................................................................ grab */
|
||||
if(engine.gamepad1.left_stick_x>0.5 || engine.gamepad1.right_stick_x<-0.5 ||
|
||||
engine.gamepad2.x){ // in
|
||||
robot.pServoGrab.setPosition(0.9);
|
||||
}
|
||||
if(engine.gamepad1.back ||
|
||||
engine.gamepad2.back){ // small out
|
||||
robot.pServoGrab.setPosition(0.50);
|
||||
}
|
||||
if(engine.gamepad1.right_stick_x>0.5 || engine.gamepad1.right_stick_x>0.5 ||
|
||||
engine.gamepad2.b){ // big out
|
||||
robot.pServoGrab.setPosition(0.0);
|
||||
}
|
||||
/* ............................................................................ carousel */
|
||||
if(Math.abs(engine.gamepad1.left_trigger)>0.1){
|
||||
robot.pServoCarousel.setPower(engine.gamepad1.left_trigger);
|
||||
}
|
||||
else if(Math.abs(engine.gamepad1.right_trigger)>0.1){
|
||||
robot.pServoCarousel.setPower(-engine.gamepad1.right_trigger);
|
||||
}
|
||||
else{
|
||||
robot.pServoCarousel.setPower((0.0));
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void buttonDown(Gamepad gamepad, String button) {
|
||||
super.buttonDown(gamepad, button);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void buttonUp(Gamepad gamepad, String button) {
|
||||
super.buttonUp(gamepad, button);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void exac() {
|
||||
|
||||
}
|
||||
|
||||
@Override
|
||||
public void telemetry() {
|
||||
engine.telemetry.addData("speed", speed);
|
||||
}
|
||||
}
|
||||
package org.timecrafters.minibots.cyberarm.states;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.Gamepad;
|
||||
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.minibots.cyberarm.MecanumMinibot;
|
||||
|
||||
|
||||
public class MecanumMinibotTeleOpState extends CyberarmState {
|
||||
private final MecanumMinibot robot;
|
||||
private float speed;
|
||||
|
||||
public MecanumMinibotTeleOpState(MecanumMinibot robot) {
|
||||
this.robot = robot;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void exec() {
|
||||
|
||||
/* ............................................................................ drive */
|
||||
speed = 1.0f - engine.gamepad1.left_trigger;
|
||||
|
||||
if (engine.gamepad1.y) {
|
||||
robot.driveAll(speed);
|
||||
} else if (engine.gamepad1.a) {
|
||||
robot.driveAll(-speed);
|
||||
} else if (engine.gamepad1.x) {
|
||||
robot.driveStrafe(MecanumMinibot.STRAFE_LEFT, speed);
|
||||
} else if (engine.gamepad1.b) {
|
||||
robot.driveStrafe(MecanumMinibot.STRAFE_RIGHT, speed);
|
||||
|
||||
} else if (engine.gamepad1.left_bumper) {
|
||||
robot.driveTurn(MecanumMinibot.TURN_LEFT, speed);
|
||||
|
||||
} else if (engine.gamepad1.right_bumper) {
|
||||
robot.driveTurn(MecanumMinibot.TURN_RIGHT, speed);
|
||||
} else {
|
||||
robot.driveStop();
|
||||
}
|
||||
/* ............................................................................ elevator */
|
||||
if(engine.gamepad1.dpad_up ||
|
||||
engine.gamepad2.y){
|
||||
robot.pServoElevate.setPower(1.0);
|
||||
}
|
||||
else if(engine.gamepad1.dpad_down ||
|
||||
engine.gamepad2.a){
|
||||
robot.pServoElevate.setPower(-1.0);
|
||||
}
|
||||
else{
|
||||
robot.pServoElevate.setPower((0.0));
|
||||
}
|
||||
|
||||
/* ............................................................................ arch */
|
||||
if(Math.abs(engine.gamepad1.left_stick_y)>0.1 ||
|
||||
Math.abs(engine.gamepad2.left_stick_y)>0.1){
|
||||
robot.pServoArch.setPower(engine.gamepad1.left_stick_y + engine.gamepad2.left_stick_y);
|
||||
}
|
||||
else{
|
||||
robot.pServoArch.setPower((0.0));
|
||||
}
|
||||
|
||||
/* ............................................................................ rotate */
|
||||
if(engine.gamepad1.dpad_right ||
|
||||
engine.gamepad2.dpad_right){ // up position
|
||||
robot.pServoRotate.setPosition(0.0);
|
||||
}
|
||||
if(engine.gamepad1.dpad_left ||
|
||||
engine.gamepad2.dpad_left){ // down position
|
||||
robot.pServoRotate.setPosition(0.70);
|
||||
}
|
||||
|
||||
/* ............................................................................ grab */
|
||||
if(engine.gamepad1.left_stick_x>0.5 || engine.gamepad1.right_stick_x<-0.5 ||
|
||||
engine.gamepad2.x){ // in
|
||||
robot.pServoGrab.setPosition(0.9);
|
||||
}
|
||||
if(engine.gamepad1.back ||
|
||||
engine.gamepad2.back){ // small out
|
||||
robot.pServoGrab.setPosition(0.50);
|
||||
}
|
||||
if(engine.gamepad1.right_stick_x>0.5 || engine.gamepad1.right_stick_x>0.5 ||
|
||||
engine.gamepad2.b){ // big out
|
||||
robot.pServoGrab.setPosition(0.0);
|
||||
}
|
||||
/* ............................................................................ carousel */
|
||||
if(Math.abs(engine.gamepad1.left_trigger)>0.1){
|
||||
robot.pServoCarousel.setPower(engine.gamepad1.left_trigger);
|
||||
}
|
||||
else if(Math.abs(engine.gamepad1.right_trigger)>0.1){
|
||||
robot.pServoCarousel.setPower(-engine.gamepad1.right_trigger);
|
||||
}
|
||||
else{
|
||||
robot.pServoCarousel.setPower((0.0));
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void buttonDown(Gamepad gamepad, String button) {
|
||||
super.buttonDown(gamepad, button);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void buttonUp(Gamepad gamepad, String button) {
|
||||
super.buttonUp(gamepad, button);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void telemetry() {
|
||||
engine.telemetry.addData("speed", speed);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,85 +1,79 @@
|
||||
package org.timecrafters.minibots.cyberarm.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.minibots.cyberarm.pickle_minibot_general;
|
||||
|
||||
public class pickle_teleop_state extends CyberarmState {
|
||||
private final pickle_minibot_general robot;
|
||||
public pickle_teleop_state(pickle_minibot_general robot){this.robot = robot;}
|
||||
|
||||
@Override
|
||||
public void exec() {
|
||||
double dDrivePowerY, dDrivePowerX, dRotatePowerX, dRotatePowerY;
|
||||
dDrivePowerY = engine.gamepad1.left_stick_y;
|
||||
dDrivePowerX = engine.gamepad1.left_stick_x;
|
||||
dRotatePowerY = engine.gamepad1.right_stick_y;
|
||||
dRotatePowerX = engine.gamepad1.right_stick_x;
|
||||
if (dDrivePowerY > .1 || dDrivePowerY < -.1 || dDrivePowerX > .1 || dDrivePowerX < -.1) {
|
||||
robot.pLeftFront.setPower(dDrivePowerY + dDrivePowerX);
|
||||
robot.pRightFront.setPower(dDrivePowerY - dDrivePowerX);
|
||||
robot.pRightBack.setPower(dDrivePowerY + dDrivePowerX);
|
||||
robot.pLeftBack.setPower(dDrivePowerY - dDrivePowerX);
|
||||
}
|
||||
else if ( dRotatePowerY > .1 || dRotatePowerY < -.1 || dRotatePowerX > .1 || dRotatePowerX < -.1){
|
||||
robot.pLeftFront.setPower(dRotatePowerY + dRotatePowerX);
|
||||
robot.pRightFront.setPower(-dRotatePowerY - dRotatePowerX);
|
||||
robot.pRightBack.setPower(-dRotatePowerY - dRotatePowerX);
|
||||
robot.pLeftBack.setPower(dRotatePowerY + dRotatePowerX);
|
||||
}
|
||||
else {
|
||||
robot.pLeftFront.setPower(0);
|
||||
robot.pRightFront.setPower(0);
|
||||
robot.pRightBack.setPower(0);
|
||||
robot.pLeftBack.setPower(0);
|
||||
}
|
||||
|
||||
if (engine.gamepad1.dpad_up){
|
||||
robot.pServoArch.setPower(1);
|
||||
|
||||
}
|
||||
else if (engine.gamepad1.dpad_down){
|
||||
robot.pServoArch.setPower(-1);
|
||||
|
||||
}
|
||||
else {
|
||||
robot.pServoArch.setPower(0);
|
||||
}
|
||||
if (engine.gamepad1.left_bumper){
|
||||
robot.pServoCarousel.setPower(1);
|
||||
}
|
||||
else if (engine.gamepad1.right_bumper) {
|
||||
robot.pServoCarousel.setPower(-1);
|
||||
}
|
||||
else {
|
||||
robot.pServoCarousel.setPower(0);
|
||||
}
|
||||
if (engine.gamepad1.dpad_left){
|
||||
robot.pServoElevate.setPower(1);
|
||||
|
||||
}else if (engine.gamepad1.dpad_right){
|
||||
robot.pServoElevate.setPower(-1);
|
||||
|
||||
} else {
|
||||
robot.pServoElevate.setPower(0);
|
||||
}
|
||||
if (engine.gamepad1.left_trigger>.1){
|
||||
robot.pServoRotate.setPosition(.7);// full down
|
||||
}
|
||||
else if (engine.gamepad1.right_trigger>.1){
|
||||
robot.pServoRotate.setPosition(0);//full up
|
||||
|
||||
}if (engine.gamepad1.a){
|
||||
robot.pServoGrab.setPosition(1);
|
||||
|
||||
}else if (engine.gamepad1.b){
|
||||
robot.pServoGrab.setPosition(0);
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void exac() {
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
package org.timecrafters.minibots.cyberarm.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.minibots.cyberarm.pickle_minibot_general;
|
||||
|
||||
public class pickle_teleop_state extends CyberarmState {
|
||||
private final pickle_minibot_general robot;
|
||||
public pickle_teleop_state(pickle_minibot_general robot){this.robot = robot;}
|
||||
|
||||
@Override
|
||||
public void exec() {
|
||||
double dDrivePowerY, dDrivePowerX, dRotatePowerX, dRotatePowerY;
|
||||
dDrivePowerY = engine.gamepad1.left_stick_y;
|
||||
dDrivePowerX = engine.gamepad1.left_stick_x;
|
||||
dRotatePowerY = engine.gamepad1.right_stick_y;
|
||||
dRotatePowerX = engine.gamepad1.right_stick_x;
|
||||
if (dDrivePowerY > .1 || dDrivePowerY < -.1 || dDrivePowerX > .1 || dDrivePowerX < -.1) {
|
||||
robot.pLeftFront.setPower(dDrivePowerY + dDrivePowerX);
|
||||
robot.pRightFront.setPower(dDrivePowerY - dDrivePowerX);
|
||||
robot.pRightBack.setPower(dDrivePowerY + dDrivePowerX);
|
||||
robot.pLeftBack.setPower(dDrivePowerY - dDrivePowerX);
|
||||
}
|
||||
else if ( dRotatePowerY > .1 || dRotatePowerY < -.1 || dRotatePowerX > .1 || dRotatePowerX < -.1){
|
||||
robot.pLeftFront.setPower(dRotatePowerY + dRotatePowerX);
|
||||
robot.pRightFront.setPower(-dRotatePowerY - dRotatePowerX);
|
||||
robot.pRightBack.setPower(-dRotatePowerY - dRotatePowerX);
|
||||
robot.pLeftBack.setPower(dRotatePowerY + dRotatePowerX);
|
||||
}
|
||||
else {
|
||||
robot.pLeftFront.setPower(0);
|
||||
robot.pRightFront.setPower(0);
|
||||
robot.pRightBack.setPower(0);
|
||||
robot.pLeftBack.setPower(0);
|
||||
}
|
||||
|
||||
if (engine.gamepad1.dpad_up){
|
||||
robot.pServoArch.setPower(1);
|
||||
|
||||
}
|
||||
else if (engine.gamepad1.dpad_down){
|
||||
robot.pServoArch.setPower(-1);
|
||||
|
||||
}
|
||||
else {
|
||||
robot.pServoArch.setPower(0);
|
||||
}
|
||||
if (engine.gamepad1.left_bumper){
|
||||
robot.pServoCarousel.setPower(1);
|
||||
}
|
||||
else if (engine.gamepad1.right_bumper) {
|
||||
robot.pServoCarousel.setPower(-1);
|
||||
}
|
||||
else {
|
||||
robot.pServoCarousel.setPower(0);
|
||||
}
|
||||
if (engine.gamepad1.dpad_left){
|
||||
robot.pServoElevate.setPower(1);
|
||||
|
||||
}else if (engine.gamepad1.dpad_right){
|
||||
robot.pServoElevate.setPower(-1);
|
||||
|
||||
} else {
|
||||
robot.pServoElevate.setPower(0);
|
||||
}
|
||||
if (engine.gamepad1.left_trigger>.1){
|
||||
robot.pServoRotate.setPosition(.7);// full down
|
||||
}
|
||||
else if (engine.gamepad1.right_trigger>.1){
|
||||
robot.pServoRotate.setPosition(0);//full up
|
||||
|
||||
}if (engine.gamepad1.a){
|
||||
robot.pServoGrab.setPosition(1);
|
||||
|
||||
}else if (engine.gamepad1.b){
|
||||
robot.pServoGrab.setPosition(0);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user