Skip to content

Commit

Permalink
Added the claw in during the meet.
Browse files Browse the repository at this point in the history
  • Loading branch information
Migala committed Jan 22, 2017
1 parent 48f7571 commit dac8275
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 38 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -68,12 +68,10 @@ public class DadDriver extends OpMode
private CRServo leftClaw = null;
private CRServo rightClaw = null;

private DcMotor verticalClawMotor = null;
private DcMotor horizontalClawMotor = null;

// shooter variables
private double endTime = 0;
private final double revolutionTime = 0.5;
private final double revolutionTime = 0.349;



/* Code to run ONCE when the driver hits INIT */
Expand All @@ -88,26 +86,15 @@ public void init() {
shooter = hardwareMap.dcMotor.get("shooter");
spinner = hardwareMap.dcMotor.get("spinner");

/* unimplemented claw objects
leftClaw = hardwareMap.crservo.get("left claw");
rightClaw = hardwareMap.crservo.get("right claw");

verticalClawMotor = hardwareMap.dcMotor.get("vertical claw");
horizontalClawMotor = hardwareMap.dcMotor.get("horizontal claw");
*/


rightMotor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
leftMotor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);

spinner.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
shooter.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);

/* unimplemented claw objects
verticalClawMotor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
horizontalClawMotor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
*/


// Reverse the motor that runs backwards when connected directly to the battery
leftMotor.setDirection(DcMotor.Direction.REVERSE); // Set to REVERSE if using AndyMark motors
Expand All @@ -116,14 +103,9 @@ public void init() {
spinner.setDirection(DcMotor.Direction.FORWARD);
shooter.setDirection(DcMotor.Direction.FORWARD);

/* unimplemented claw objects
leftClaw.setDirection(CRServo.Direction.FORWARD);
rightClaw.setDirection(CRServo.Direction.REVERSE);

verticalClawMotor.setDirection(DcMotor.Direction.FORWARD);
horizontalClawMotor.setDirection(DcMotor.Direction.FORWARD);
*/

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

Expand All @@ -148,8 +130,8 @@ public void loop() {
telemetry.addData("Right Motor", rightMotor.getPower());
telemetry.addData("Left Motor", leftMotor.getPower());
telemetry.addData("Spinner", spinner.getPower());
//telemetry.addData("Left Claw", leftClaw.getPower());
//telemetry.addData("Right Claw", rightClaw.getPower());
telemetry.addData("Left Claw", leftClaw.getPower());
telemetry.addData("Right Claw", rightClaw.getPower());


// Drivetrain code (note: The joystick goes negative when pushed forwards)
Expand Down Expand Up @@ -199,25 +181,20 @@ public void loop() {
leftClaw.setPower(-gamepad2.left_trigger);
rightClaw.setPower(-gamepad2.left_trigger);
}
*/

if (gamepad2.dpad_up){
verticalClawMotor.setPower(0.89);
}
if (gamepad2.dpad_down){
verticalClawMotor.setPower(-0.89);
leftClaw.setPower(1);
rightClaw.setPower(1);
}
if (gamepad2.dpad_right){
horizontalClawMotor.setPower(0.90);
if (gamepad2.dpad_down) {
leftClaw.setPower(1);
rightClaw.setPower(1);
}
if (gamepad2.dpad_left){
horizontalClawMotor.setPower(-0.90);
if (gamepad2.x) {
leftClaw.setPower(0);
rightClaw.setPower(0);
}
if (gamepad2.back){
verticalClawMotor.setPower(0);
horizontalClawMotor.setPower(0);
}
*/
}


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@ are permitted (subject to the limitations in the disclaimer below) provided that
package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.util.ElapsedTime;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
Expand Down Expand Up @@ -63,6 +64,9 @@ public class Unbeacon extends LinearOpMode {
private DcMotor spinner = null;
private DcMotor shooter = null;

private CRServo leftClaw = null;
private CRServo rightClaw = null;

/*Declaring constant values */
final int MOTOR_PULSE_PER_REVOLUTION = 7;
final int MOTOR_GEAR_RATIO = 80;
Expand All @@ -82,6 +86,9 @@ public void runOpMode() throws InterruptedException {
shooter = hardwareMap.dcMotor.get("shooter");
spinner = hardwareMap.dcMotor.get("spinner");

leftClaw = hardwareMap.crservo.get("left claw");
rightClaw = hardwareMap.crservo.get("right claw");

// Set the drive motor directions
leftMotor.setDirection(DcMotor.Direction.REVERSE);
rightMotor.setDirection(DcMotor.Direction.FORWARD);
Expand Down Expand Up @@ -113,8 +120,8 @@ public void runOpMode() throws InterruptedException {
telemetry.addData("Status", "Run Time: " + runtime.toString());

//Set the target distance to travel (to the ball)
leftMotor.setTargetPosition((int)(2.5 * FLOOR_BLOCK));
rightMotor.setTargetPosition((int)(2.5 * FLOOR_BLOCK));
leftMotor.setTargetPosition((int)(5 * FLOOR_BLOCK));
rightMotor.setTargetPosition((int)(5 * FLOOR_BLOCK));

//Run to the ball until it gets to the target distance.
while (!(leftMotor.getCurrentPosition() >= leftMotor.getTargetPosition() - 10 && leftMotor.getCurrentPosition() <= leftMotor.getTargetPosition() + 10)) {
Expand Down

0 comments on commit dac8275

Please sign in to comment.