Skip to content
This repository has been archived by the owner on Jan 19, 2025. It is now read-only.

Commit

Permalink
Update TeleOp
Browse files Browse the repository at this point in the history
  • Loading branch information
kevinthegreat1 committed Dec 13, 2023
1 parent 1841ce1 commit 7261626
Show file tree
Hide file tree
Showing 7 changed files with 97 additions and 72 deletions.
7 changes: 3 additions & 4 deletions EncoderAuto.java → Autonomous.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.Servo;
Expand All @@ -12,8 +11,8 @@
import org.firstinspires.ftc.teamcode.modules.output.MotorOutputPivot;
import org.firstinspires.ftc.teamcode.util.TelemetryWrapper;

@Autonomous(name = "EncoderAuto", group = "opmode")
public class EncoderAuto extends LinearOpMode {
@com.qualcomm.robotcore.eventloop.opmode.Autonomous(name = "Autonomous", group = "opmode")
public class Autonomous extends LinearOpMode {
protected static final boolean LEFT = false;
protected static final boolean RIGHT = true;
/**
Expand All @@ -35,7 +34,7 @@ public class EncoderAuto extends LinearOpMode {
private AprilTagWebcam aprilTagWebcam;


public EncoderAuto(boolean sideOfField) {
public Autonomous(boolean sideOfField) {
this.sideOfField = sideOfField;
}

Expand Down
8 changes: 3 additions & 5 deletions LeftAuto.java
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.eventloop.opmode.Autonomous;

@Autonomous(name = "LeftAuto", group = "opmode")
public class LeftAuto extends EncoderAuto {
@com.qualcomm.robotcore.eventloop.opmode.Autonomous(name = "LeftAuto", group = "opmode")
public class LeftAuto extends Autonomous {
public LeftAuto() {
super(EncoderAuto.LEFT);
super(Autonomous.LEFT);
}
}
8 changes: 3 additions & 5 deletions RightAuto.java
Original file line number Diff line number Diff line change
@@ -1,10 +1,8 @@
package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.eventloop.opmode.Autonomous;

@Autonomous(name = "RightAuto", group = "opmode")
public class RightAuto extends EncoderAuto {
@com.qualcomm.robotcore.eventloop.opmode.Autonomous(name = "RightAuto", group = "opmode")
public class RightAuto extends Autonomous {
public RightAuto() {
super(EncoderAuto.RIGHT);
super(Autonomous.RIGHT);
}
}
66 changes: 27 additions & 39 deletions TeleOp.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,13 +4,13 @@
import com.qualcomm.robotcore.hardware.DcMotor;

import org.firstinspires.ftc.teamcode.modules.DriveTrain;
import org.firstinspires.ftc.teamcode.modules.ServoPixel;
import org.firstinspires.ftc.teamcode.modules.output.ServoOutputPivot;
import org.firstinspires.ftc.teamcode.modules.output.LinearSlide;
import org.firstinspires.ftc.teamcode.modules.output.MotorOutputPivot;
import org.firstinspires.ftc.teamcode.util.ButtonHelper;
import org.firstinspires.ftc.teamcode.util.TelemetryWrapper;

import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.util.ElapsedTime;

@SuppressWarnings("FieldCanBeLocal")
Expand All @@ -28,8 +28,8 @@ public class TeleOp extends LinearOpMode {
private MotorOutputPivot pivot;
private ServoOutputPivot servoOutputPivot;

private Servo firstPixel;
private Servo secondPixel;
private ServoPixel firstPixel;
private ServoPixel secondPixel;

private double openPos = 0.3;

Expand All @@ -50,15 +50,17 @@ public void runOpMode() {
intakeWheel = hardwareMap.get(DcMotor.class, "intakeWheel");
outputSlide = new LinearSlide("linearSlide", 0.5);
// pivot = new OutputPivot("outputPivot");
servoOutputPivot = new ServoOutputPivot("outputClaw", runtime);
servoOutputPivot = new ServoOutputPivot("outputClaw");
driveTrain.init(hardwareMap);
outputSlide.init(hardwareMap);
// pivot.init(hardwareMap);
servoOutputPivot.init(hardwareMap);
firstPixel = hardwareMap.get(Servo.class, "firstPixel");
secondPixel = hardwareMap.get(Servo.class, "secondPixel");
firstPixel.setPosition(openPos);
secondPixel.setPosition(openPos);
firstPixel = new ServoPixel("firstPixel");
secondPixel = new ServoPixel("secondPixel");
firstPixel.init(hardwareMap);
secondPixel.init(hardwareMap);
firstPixel.setOpen(true);
secondPixel.setOpen(true);

// Wait for start
TelemetryWrapper.setLine(1, "TeleOp v" + programVer + "\t Press start to start >");
Expand All @@ -75,50 +77,36 @@ public void runOpMode() {
// DriveTrain wheels
driveTrain.move(gamepad1.left_stick_x, gamepad1.left_stick_y, gamepad1.right_stick_x, speedMultiplier);

if (gp2.pressing(ButtonHelper.a)) {
outputSlide.startRetraction();
}

if (gp2.pressing(ButtonHelper.left_bumper)) {
if (firstPixel.getPosition() - closedPos < 0.05)
firstPixel.setPosition(openPos);
} else {
firstPixel.setPosition(openPos);
}
intakeWheel.setPower((gamepad2.right_trigger - gamepad2.left_trigger) * 0.8);

if (gp2.pressing(ButtonHelper.right_bumper)) {
if (secondPixel.getPosition() - closedPos < 0.05) {
secondPixel.setPosition(openPos);
} else {
secondPixel.setPosition(openPos);
}
if (Math.abs(gamepad2.left_stick_y) > 0.001) {
outputSlide.startMoveToRelativePos((int) (-gamepad2.left_stick_y * 100));
}

if (gp2.pressing(ButtonHelper.b)) {
outputSlide.startMoveToPos(1430);
}


if (Math.abs(gamepad2.left_stick_y) > 0.001) {
outputSlide.startMoveToRelativePos((int) (gamepad2.left_stick_y * 100));
if (gp2.pressing(ButtonHelper.a)) {
outputSlide.startRetraction();
}
outputSlide.tick();

intakeWheel.setPower((gamepad2.right_trigger - gamepad2.left_trigger) * 0.8);
// pivot.moveUsingEncoder(-gamepad2.right_stick_y * 0.5);

if (gp2.pressing(ButtonHelper.dpad_left)) {
servoOutputPivot.togglePivot();
} else if (gp2.pressed(ButtonHelper.dpad_up)) {
servoOutputPivot.movePivot(1);
} else if (gp2.pressed(ButtonHelper.dpad_down)) {
servoOutputPivot.movePivot(-1);
} else if (servoOutputPivot.isFinished()) {
servoOutputPivot.movePivot(0);
}
servoOutputPivot.tick();

// if (gp2.pressed(ButtonHelper.dpad_up)) {
// servoOutputPivot.movePivot(1);
// } else if (gp2.pressed(ButtonHelper.dpad_down)) {
// servoOutputPivot.movePivot(-1);
// } else if (servoOutputPivot.isFinished()) {
// servoOutputPivot.movePivot(0);
// }
if (gp2.pressing(ButtonHelper.left_bumper)) {
firstPixel.toggle();
}
if (gp2.pressing(ButtonHelper.right_bumper)) {
secondPixel.toggle();
}
}
}
}
52 changes: 52 additions & 0 deletions modules/ServoPixel.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
package org.firstinspires.ftc.teamcode.modules;

import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.Servo;

public class ServoPixel implements Modulable {
public static final double CLOSED_POS = 0;
private static final double OPENED_POS = 0.3;
private final String name;
private Servo servo;
private boolean open;

public ServoPixel(String name) {
this.name = name;
}

public double getPosition() {
return servo.getPosition();
}

public void setPosition(double position) {
servo.setPosition(position);
}

@Override
public void init(HardwareMap map) {
servo = map.get(Servo.class, name);
}

/**
* Makes the servo start to move towards the specified position.
*
* @param open move towards open or close position
*/
public void setOpen(boolean open) {
this.open = open;
startMove();
}

/**
* Start to move the claw opposite to the current state.
*/
public void toggle() {
open = !open;
startMove();
}

private void startMove() {
servo.setPosition(open? OPENED_POS: CLOSED_POS);
}
}

26 changes: 8 additions & 18 deletions modules/output/ServoOutputPivot.java
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
package org.firstinspires.ftc.teamcode.modules.output;

import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.ServoController;

Expand All @@ -13,21 +12,17 @@
public class ServoOutputPivot implements Modulable, Tickable {
public static final double CLOSED_POS = 0;
private static final double OPENED_POS = 0.5;
private static final double TARGET_TIME = 1.4;
private final String name;
protected CRServo pivot;

private CRServo pivot;
private ServoController controller;
private final ElapsedTime runtime;
private boolean output = false;

private boolean isRunning;

private double targetTime = 1.5;

private ElapsedTime runtime;

public ServoOutputPivot(String name, ElapsedTime runtime) {
public ServoOutputPivot(String name) {
this.name = name;
this.runtime = runtime;
this.runtime = new ElapsedTime();
}

public double getPosition() {
Expand All @@ -38,7 +33,6 @@ public void setPosition(double position) {
controller.setServoPosition(0, position);
}


@Override
public void init(HardwareMap map) {
pivot = map.get(CRServo.class, name);
Expand Down Expand Up @@ -66,11 +60,7 @@ public void togglePivot() {

private void startMovePivot() {
runtime.reset();
if (output) {
pivot.setPower(1.0);
} else {
pivot.setPower(-1.0);
}
movePivot(output ? 1.0 : -1.0);
isRunning = true;
}

Expand All @@ -84,9 +74,9 @@ public boolean isFinished() {

@Override
public void tick() {
if (isRunning && runtime.seconds() >= targetTime) {
if (isRunning && runtime.seconds() >= TARGET_TIME) {
isRunning = false;
controller.setServoPosition(0, 0.5);
movePivot(0);
}
}
}
Expand Down
2 changes: 1 addition & 1 deletion util/ButtonHelper.java
Original file line number Diff line number Diff line change
Expand Up @@ -86,7 +86,7 @@ public boolean released(int idx) {

/**
* Return whether button is being pressed on
* Determined through transition from upressed to
* Determined through transition from unpressed to
* pressed button
* @param idx Gamepad button value
*/
Expand Down

0 comments on commit 7261626

Please sign in to comment.