Skip to content

Commit

Permalink
Fixed closed claw problem and relative speed for slides
Browse files Browse the repository at this point in the history
  • Loading branch information
Joshua-Smith-42 committed Dec 31, 2024
1 parent 67295fe commit 0e2c2c6
Show file tree
Hide file tree
Showing 2 changed files with 15 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ public class IntakeSlides extends QQMechanism {
public static final int SLIDES_EXTENSION_BOUNDARY = FULL_EXTENSION_POSITION+10;
private static final int HALF_EXTENSION_POSITION = 740;
private static final int START_POSITION = 0;
public static int MANUAL_CHANGE_AMOUNT = 30;
public static double MANUAL_CHANGE_AMOUNT = 30;

private DcMotor rightIntakeSlideMotor;
private DcMotor leftIntakeSlideMotor;
Expand Down Expand Up @@ -69,13 +69,13 @@ public void init(HardwareMap hwMap) {
public void setPosition(int desiredPos){
this.desiredPos = desiredPos;
}
public void extend(){
manualPositionChange(MANUAL_CHANGE_AMOUNT);
public void extend(double speed){
manualPositionChange(MANUAL_CHANGE_AMOUNT * speed);
}
public void retract(){
manualPositionChange(-MANUAL_CHANGE_AMOUNT);
public void retract(double speed){
manualPositionChange(-MANUAL_CHANGE_AMOUNT * speed);
}
private void manualPositionChange(int changeAmount){
private void manualPositionChange(double changeAmount){
desiredPos += changeAmount;
}
@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,10 +30,12 @@ public void loop() {
double left = gamepad1.left_stick_x;
double rotate = 0;
if (gamepad1.right_stick_button) {
if (gamepad1.right_stick_y < -0.2) {
robot.intakeSlides.extend();
} else if (gamepad1.right_stick_y > 0.2) {
robot.intakeSlides.retract();
if (gamepad1.right_stick_y < -0.1) {
double slideSpeed = (gamepad1.right_stick_y) * -5;
robot.intakeSlides.extend(slideSpeed);
} else if (gamepad1.right_stick_y > 0.1) {
double slideSpeed = (gamepad1.right_stick_y) * 5;
robot.intakeSlides.retract(slideSpeed);
}
if (robot.intakeSlides.isSafeToRotate()) {
if (gamepad1.right_stick_x > 0.3) {
Expand Down Expand Up @@ -127,9 +129,9 @@ public void loop() {
robot.scoreArm.setNotScoring();
}
if (gamepad2.dpad_up) {
robot.intakeSlides.extend();
robot.intakeSlides.extend(1);
} else if (gamepad2.dpad_down) {
robot.intakeSlides.retract();
robot.intakeSlides.retract(1);
}
if (gamepad2.right_trigger > TRIGGER_THRESHOLD) {
robot.scoringClaw.open();
Expand All @@ -141,6 +143,7 @@ public void loop() {
XWasPressed = gamepad1.x;
chamberContactWasPressed = robot.scoreArm.isChamberContacted();
clawWasClosed = robot.scoringClaw.isClawClosed();
intakeClawWasClosed = robot.intakeClaw.isClawClosed();
slidesSwitchWasPressed = robot.intakeSlides.isSwitchPressed();
manipulatorXWasPressed = gamepad2.x;

Expand Down

0 comments on commit 0e2c2c6

Please sign in to comment.