Skip to content

Commit

Permalink
Addded the Beacon-Pushing Servo
Browse files Browse the repository at this point in the history
It's in both Tele-op and Autonomous, and on the right heigh. Sometimes
it doesn't hit the button even though it's pushing up agains tthe
beacon, so we might want to think about sloping our presser... if we
have the space.
  • Loading branch information
blabel3 committed Dec 9, 2016
1 parent f65962d commit 0f5f6ae
Show file tree
Hide file tree
Showing 2 changed files with 23 additions and 13 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,9 @@ are permitted (subject to the limitations in the disclaimer below) provided that
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.util.ElapsedTime;
import com.qualcomm.robotcore.util.RobotLog;

Expand Down Expand Up @@ -83,6 +85,7 @@ public class AutonomousTest extends LinearVisionOpMode {
private DcMotor leftMotor = null;
private DcMotor rightMotor = null;
private DcMotor spinner = null;
private CRServo beaconPusher = null;

/*Declaring constant values */
final int MOTOR_PULSE_PER_REVOLUTION = 7;
Expand All @@ -107,6 +110,7 @@ public void runOpMode() throws InterruptedException {
rightMotor = hardwareMap.dcMotor.get("right motor");
spinner = hardwareMap.dcMotor.get("spinner");

beaconPusher = hardwareMap.crservo.get("beacon pusher");

// Set the drive motor directions
leftMotor.setDirection(DcMotor.Direction.REVERSE);
Expand All @@ -116,8 +120,8 @@ public void runOpMode() throws InterruptedException {
//Prepare the encoders to be used
leftMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rightMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
leftMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rightMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
leftMotor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
rightMotor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
spinner.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);

boolean blueLeft = false;
Expand Down Expand Up @@ -233,8 +237,6 @@ public void runOpMode() throws InterruptedException {
step = 2;
leftMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rightMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
leftMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rightMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
}

} else if (step == 2) {
Expand All @@ -249,8 +251,6 @@ public void runOpMode() throws InterruptedException {
step = 3;
leftMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rightMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
leftMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rightMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
}

} else if (step == 3){
Expand All @@ -265,8 +265,6 @@ public void runOpMode() throws InterruptedException {
step = 4;
leftMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rightMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
leftMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rightMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
}
} else if (step == 4) {

Expand All @@ -280,8 +278,6 @@ public void runOpMode() throws InterruptedException {
step = 5;
leftMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rightMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
leftMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rightMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
}
} else if (step == 5){

Expand All @@ -295,8 +291,6 @@ public void runOpMode() throws InterruptedException {
step = 6;
leftMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
rightMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
leftMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
rightMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
}
} else if (step == 6){

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@ are permitted (subject to the limitations in the disclaimer below) provided that
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.util.ElapsedTime;


Expand All @@ -62,6 +64,9 @@ public class driveTest extends OpMode
private DcMotor spinner = null;
//private DcMotor belt = null;

private CRServo beaconPusher = null;


private boolean testEncoders = false;


Expand All @@ -75,13 +80,18 @@ public void init() {
spinner = hardwareMap.dcMotor.get("spinner");
//belt = hardwareMap.dcMotor.get("belt");

beaconPusher = hardwareMap.crservo.get("beacon pusher");


// eg: Set the drive motor directions:
// Reverse the motor that runs backwards when connected directly to the battery
leftMotor.setDirection(DcMotor.Direction.REVERSE); // Set to REVERSE if using AndyMark motors
rightMotor.setDirection(DcMotor.Direction.FORWARD);// Set to FORWARD if using AndyMark motors
spinner.setDirection(DcMotor.Direction.FORWARD);
//belt.setDirection(DcMotor.Direction.FORWARD);

beaconPusher.setDirection(CRServo.Direction.FORWARD);

telemetry.addData("Status", "Initialized");

if(testEncoders) {
Expand Down Expand Up @@ -129,7 +139,6 @@ public void loop() {
leftMotor.setPower(-gamepad1.left_stick_y);
rightMotor.setPower(-gamepad1.right_stick_y);


if(gamepad1.left_bumper){
spinner.setPower(1);
//belt.setPower(1);
Expand All @@ -141,6 +150,13 @@ public void loop() {
//belt.setPower(0);
}

if(gamepad1.right_trigger > 0.1){
beaconPusher.setPower(gamepad1.right_trigger);
} else if (gamepad1.left_trigger > 0.1) {
beaconPusher.setPower(-gamepad1.left_trigger);
} else {
beaconPusher.setPower(0);
}

}

Expand Down

0 comments on commit 0f5f6ae

Please sign in to comment.