Skip to content

Commit

Permalink
notes
Browse files Browse the repository at this point in the history
  • Loading branch information
fulton committed Jan 11, 2020
1 parent 1dcdddf commit d1da453
Show file tree
Hide file tree
Showing 3 changed files with 44 additions and 31 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -87,37 +87,27 @@ public void init() {
@SuppressLint("DefaultLocale")
@Override
public void loop() {


// left stick controls direction
// right stick X controls rotation

// formula for motor values
float gamepad1LeftY = -gamepad1.left_stick_y;
float gamepad1LeftX = gamepad1.left_stick_x;
float gamepad1RightX = gamepad1.right_stick_x;


float FrontLeft = -gamepad1LeftY - gamepad1LeftX - gamepad1RightX;
float FrontRight = gamepad1LeftY - gamepad1LeftX - gamepad1RightX;
float BackRight = gamepad1LeftY + gamepad1LeftX - gamepad1RightX;
float BackLeft = -gamepad1LeftY + gamepad1LeftX - gamepad1RightX;
//if (gamepad2.x) new Move().arm(1.0, crServo0);
//if(gamepad2.y) new Move().arm(0.0, crServo0);
// move the claw in and out
if ((gamepad2.left_bumper)) new Move().arm(1.0, claw);
else if (gamepad2.right_bumper) new Move().arm(0.0, claw);
if ((gamepad2.dpad_up)) arm.setPower(0.4);
else if (gamepad2.dpad_down && !touch1.isPressed()) arm.setPower(-0.4);
//move the arm up and down
if ((gamepad2.dpad_up)) arm.setPower(0.8);
else if (gamepad2.dpad_down && !touch1.isPressed()) arm.setPower(-0.8);
else arm.setPower(0.0);

//set powers
motorFrontRight.setPower(FrontRight);
motorFrontLeft.setPower(FrontLeft);
motorBackLeft.setPower(BackLeft);
motorBackRight.setPower(BackRight);





/*
* Telemetry for debugging
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ public void runOpMode() {
DcMotor motor0 = hardwareMap.dcMotor.get("motor0");
DcMotor motor1 = hardwareMap.dcMotor.get("motor1");
DcMotor motor2 = hardwareMap.dcMotor.get("motor2");
DcMotor arm = hardwareMap.dcMotor.get("motor4");
DcMotor motor3 = hardwareMap.dcMotor.get("motor3");
//set break
motor0.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
Expand All @@ -40,7 +41,7 @@ public void runOpMode() {
waitForStart();
//ensure position is correct
servo1.setPosition(1.0);
//move for the first time
//move to blocks
new Move().left(motor0, motor1, motor2, motor3);
sleep(2900);
//start looking for block
Expand All @@ -56,7 +57,7 @@ public void runOpMode() {
}
new Move().stop(motor0, motor1, motor2, motor3);
sleep(2000);
//get the block, place it
// find yellow
new Move().back(motor0, motor1, motor2, motor3);
telemetry.addData("while is running", "");
while (true) {
Expand All @@ -66,21 +67,26 @@ public void runOpMode() {
break;
}
}
sleep(520);
//move in and get the block
sleep(400);
new Move().spinOtherWay(motor0, motor1, motor2, motor3);
sleep(25);
new Move().left(motor0, motor1, motor2, motor3);
sleep(1000);
sleep(1300);
new Move().forward(motor0, motor1, motor2, motor3);
sleep(700);
new Move().stop(motor0, motor1, motor2, motor3);
new Move().arm(0.0, servo1);
sleep(2000);
arm.setPower(1.0);
sleep(450);
arm.setPower(0.0);
//move out with block
new Move().right(motor0, motor1, motor2, motor3);
sleep(1800);
sleep(2100);
new Move().stop(motor0, motor1, motor2, motor3);
new Move().forward(motor0, motor1, motor2, motor3);
//park under the bridge
//look for over hang
telemetry.addData("while is running", "");
while (true) {
boolean scan = range0.rawUltrasonic() < 40;
Expand All @@ -89,10 +95,11 @@ public void runOpMode() {
break;
}
}
sleep(2000);
// place on the platform
sleep(3000);
new Move().back(motor0, motor1, motor2, motor3);
new Move().arm(1.0, servo1);
sleep(2000);
sleep(3000);
new Move().stop(motor0, motor1, motor2, motor3);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
import org.firstinspires.ftc.teamcode.framework.Color;
import org.firstinspires.ftc.teamcode.framework.Move;

@Autonomous(name = "red")
@Autonomous(name = "blue")

public class LinearAutoRight extends LinearOpMode{
private ElapsedTime runtime = new ElapsedTime();
Expand All @@ -24,25 +24,33 @@ public class LinearAutoRight extends LinearOpMode{

@Override
public void runOpMode() throws InterruptedException {
//get the motors
DcMotor motor0 = hardwareMap.dcMotor.get("motor0");
DcMotor motor1 = hardwareMap.dcMotor.get("motor1");
DcMotor motor2 = hardwareMap.dcMotor.get("motor2");
DcMotor motor3 = hardwareMap.dcMotor.get("motor3");
DcMotor arm = hardwareMap.dcMotor.get("motor4");
//set the breaks
motor0.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
motor1.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
motor2.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
motor3.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
//servos
servo1 = hardwareMap.servo.get("servo1");
//sensors
range0 = hardwareMap.get( ModernRoboticsI2cRangeSensor.class,"range0");
ColorSensor colorSensor = hardwareMap.colorSensor.get("color0");
motor0.setDirection(DcMotorSimple.Direction.REVERSE);
motor1.setDirection(DcMotorSimple.Direction.REVERSE);
motor2.setDirection(DcMotorSimple.Direction.REVERSE);
motor3.setDirection(DcMotorSimple.Direction.REVERSE);
waitForStart();
//move claw in correct position
servo1.setPosition(1.0);
//move to blocks
new Move().right(motor0, motor1, motor2, motor3);
sleep(2700);
sleep(2900);
//scan for black
new Move().back(motor0, motor1, motor2, motor3);
telemetry.addData("while is running", "");
while (true) {
Expand All @@ -54,6 +62,7 @@ public void runOpMode() throws InterruptedException {
}
new Move().stop(motor0, motor1, motor2, motor3);
sleep(2000);
//find the yellow
new Move().back(motor0, motor1, motor2, motor3);
telemetry.addData("while is running", "");
while (true) {
Expand All @@ -63,19 +72,25 @@ public void runOpMode() throws InterruptedException {
break;
}
}
sleep(540);
//move in and get the block
sleep(400);
new Move().spinOtherWay(motor0, motor1, motor2, motor3);
sleep(25);
new Move().right(motor0, motor1, motor2, motor3);
sleep(1000);
sleep(1300);
new Move().forward(motor0, motor1, motor2, motor3);
sleep(700);
new Move().stop(motor0, motor1, motor2, motor3);
new Move().arm(0.0, servo1);
sleep(2000);
arm.setPower(1.0);
sleep(250);
arm.setPower(0.0);
// pull out
new Move().left(motor0, motor1, motor2, motor3);
sleep(1800);
sleep(2100);
new Move().stop(motor0, motor1, motor2, motor3);
//find the over hang
new Move().forward(motor0, motor1, motor2, motor3);
telemetry.addData("while is running", "");
while (true) {
Expand All @@ -85,10 +100,11 @@ public void runOpMode() throws InterruptedException {
break;
}
}
sleep(2000);
// move ot drop the block and come back
sleep(3000);
new Move().back(motor0, motor1, motor2, motor3);
new Move().arm(1.0, servo1);
sleep(2000);
sleep(3000);
new Move().stop(motor0, motor1, motor2, motor3);


Expand Down

0 comments on commit d1da453

Please sign in to comment.