autnomous work added

This commit is contained in:
SpencerPiha
2022-10-25 20:29:53 -05:00
parent 970071f3c1
commit 022b77fdb7
4 changed files with 25 additions and 6 deletions

View File

@@ -1,5 +1,7 @@
package org.timecrafters.Autonomous.States; package org.timecrafters.Autonomous.States;
import com.qualcomm.robotcore.hardware.DcMotor;
import org.cyberarm.engine.V2.CyberarmState; import org.cyberarm.engine.V2.CyberarmState;
import org.timecrafters.testing.states.PrototypeBot1; import org.timecrafters.testing.states.PrototypeBot1;
@@ -14,13 +16,26 @@ public class DriverState extends CyberarmState {
private double drivePower; private double drivePower;
private int traveledDistance; private int traveledDistance;
@Override
public void start() {
robot.frontRightDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
robot.frontLeftDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
robot.backRightDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
robot.backLeftDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
robot.frontRightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
robot.frontLeftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
robot.backRightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
robot.backLeftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
}
@Override @Override
public void exec() { public void exec() {
if (robot.frontRightDrive.getCurrentPosition() < traveledDistance){ if (Math.abs(robot.frontRightDrive.getCurrentPosition()) < traveledDistance){
robot.backLeftDrive.setPower(drivePower * 0.5); robot.backLeftDrive.setPower(drivePower);
robot.backRightDrive.setPower(drivePower); robot.backRightDrive.setPower(drivePower);
robot.frontLeftDrive.setPower(drivePower * 0.5); robot.frontLeftDrive.setPower(drivePower);
robot.frontRightDrive.setPower(drivePower); robot.frontRightDrive.setPower(drivePower);
} else { } else {
robot.backLeftDrive.setPower(0); robot.backLeftDrive.setPower(0);

View File

@@ -39,7 +39,8 @@ public class RotationState extends CyberarmState {
@Override @Override
public void telemetry() { public void telemetry() {
engine.telemetry.addData("Robot Rotation", RobotRotation); engine.telemetry.addData("Robot IMU Rotation", RobotRotation);
engine.telemetry.addData("Robot Target Rotation", targetRotation);
engine.telemetry.addData("Drive Power", drivePower); engine.telemetry.addData("Drive Power", drivePower);
} }

View File

@@ -80,6 +80,9 @@ public class PrototypeBot1 {
collectorLeft = engine.hardwareMap.crservo.get("Collector Left"); collectorLeft = engine.hardwareMap.crservo.get("Collector Left");
collectorRight = engine.hardwareMap.crservo.get("Collector Right"); collectorRight = engine.hardwareMap.crservo.get("Collector Right");
collectorLeft.setDirection(DcMotorSimple.Direction.REVERSE);
collectorRight.setDirection(DcMotorSimple.Direction.FORWARD);
// Arm // Arm
LowRiserLeft = engine.hardwareMap.servo.get("LowRiserLeft"); LowRiserLeft = engine.hardwareMap.servo.get("LowRiserLeft");
LowRiserRight = engine.hardwareMap.servo.get("LowRiserRight"); LowRiserRight = engine.hardwareMap.servo.get("LowRiserRight");

View File

@@ -105,7 +105,7 @@ public class PrototypeTeleOPState extends CyberarmState {
if (engine.gamepad1.right_trigger > 0) { if (engine.gamepad1.right_trigger > 0) {
drivePower = engine.gamepad1.right_trigger; drivePower = engine.gamepad1.right_trigger;
robot.backLeftDrive.setPower(0.1); robot.backLeftDrive.setPower(drivePower);
robot.backRightDrive.setPower(drivePower); robot.backRightDrive.setPower(drivePower);
robot.frontLeftDrive.setPower(drivePower); robot.frontLeftDrive.setPower(drivePower);
robot.frontRightDrive.setPower(drivePower); robot.frontRightDrive.setPower(drivePower);
@@ -113,7 +113,7 @@ public class PrototypeTeleOPState extends CyberarmState {
if (engine.gamepad1.left_trigger > 0) { if (engine.gamepad1.left_trigger > 0) {
drivePower = engine.gamepad1.left_trigger; drivePower = engine.gamepad1.left_trigger;
robot.backLeftDrive.setPower(-0.1); robot.backLeftDrive.setPower(-drivePower);
robot.backRightDrive.setPower(-drivePower); robot.backRightDrive.setPower(-drivePower);
robot.frontLeftDrive.setPower(-drivePower); robot.frontLeftDrive.setPower(-drivePower);
robot.frontRightDrive.setPower(-drivePower); robot.frontRightDrive.setPower(-drivePower);