2/11 changes
This commit is contained in:
@@ -93,10 +93,10 @@ public class DriverControlsV1 extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
if (!shooting) {
|
if (!shooting) {
|
||||||
if (gamepad1.right_trigger > 0.3) {
|
if (gamepad1.right_trigger > 0.3) {
|
||||||
robot.intake.set(1);
|
robot.intake.set(0.8);
|
||||||
robot.activeTransfer.setPosition(0.7);
|
robot.activeTransfer.setPosition(0.7);
|
||||||
} else if (gamepad1.left_trigger > 0.5) {
|
} else if (gamepad1.left_trigger > 0.5) {
|
||||||
robot.intake.set(-1);
|
robot.intake.set(-0.8);
|
||||||
robot.activeTransfer.setPosition(0.7);
|
robot.activeTransfer.setPosition(0.7);
|
||||||
} else {
|
} else {
|
||||||
robot.intake.set(0);
|
robot.intake.set(0);
|
||||||
|
|||||||
Reference in New Issue
Block a user