Skip to content

Commit

Permalink
Added horizontal slide and front claw
Browse files Browse the repository at this point in the history
  • Loading branch information
luenix1 committed Nov 24, 2024
1 parent 01cb068 commit 1a07294
Show file tree
Hide file tree
Showing 2 changed files with 49 additions and 0 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,16 @@ public static class Locks {
@HardwareName("wrist")
public Servo wrist;

@HardwareName("clawFront")
public Servo clawFront;

@HardwareName("clawFlip")
public Servo clawFlip;

@HardwareName("horizontalSlide")
public Servo horizontalSlide;



@Override
public Encoder getLeftEncoder() { return encoderLeft; }
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,9 @@ public class MecanumTeleOp extends LinearOpMode {
double Wristpos = 0.28;
double Twistpos = 0.17;
double VerticalSlideSpeed = 0.75;
double fClawClose = 0.46;
double fClawPos = 0;
double horizontalSlide = 0;

@Override
public void runOpMode() {
Expand All @@ -34,6 +37,7 @@ public void runOpMode() {
hardware.verticalSlide.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
hardware.verticalSlide.setTargetPosition(0);
hardware.arm.setTargetPosition(0);
hardware.clawFlip.setPosition(0);
armTargetPosDeg = 0.0;
hardware.arm.setMode(DcMotor.RunMode.RUN_TO_POSITION);
hardware.arm.setPower(0.2);
Expand Down Expand Up @@ -106,6 +110,8 @@ public void runOpMode() {
wrist();
servoMoves();
twist();
horizontalSLide(hardware);
fClawTest(hardware);
lift(hardware);
if (gamepad2.y) {
ScoreHighBasket(hardware);
Expand Down Expand Up @@ -354,5 +360,38 @@ public void PickUpYellow(Hardware hardware){
hardware.arm.setTargetPosition(0);
sleep(500);

/////////////////////////////////////////////////////////////////////////////////////
}
public void horizontalSLide(Hardware hardware) {

if(gamepad1.x){
horizontalSlide += 0.01;
hardware.horizontalSlide.setPosition(horizontalSlide);
}
if (gamepad1.b){
horizontalSlide += -0.01;
hardware.horizontalSlide.setPosition(horizontalSlide);
}

if(gamepad1.y){
fClawPos += .01;
hardware.clawFlip.setPosition(fClawPos);
}
if(gamepad1.a){
fClawPos += -.01;
hardware.clawFlip.setPosition(fClawPos);
}
telemetry.addData("horizontal slide", horizontalSlide);
}
///////////////////////////////////////////////
public void fClawTest (Hardware hardware) {
if (gamepad1.right_bumper){
hardware.clawFront.setPosition(fClawClose);
}
if (gamepad1.left_bumper){
hardware.clawFront.setPosition(0);
}


}
}

0 comments on commit 1a07294

Please sign in to comment.