mirror of
https://github.com/TimeCrafters/FTC_2022
synced 2025-12-15 22:22:35 +00:00
Autonomous has been wrote to acsend and descend the arms, and camera has been commented out
This commit is contained in:
@@ -1,6 +1,7 @@
|
|||||||
package org.timecrafters.Autonomous.Engines;
|
package org.timecrafters.Autonomous.Engines;
|
||||||
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
|
||||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||||
import org.timecrafters.Autonomous.States.CollectorState;
|
import org.timecrafters.Autonomous.States.CollectorState;
|
||||||
|
|||||||
@@ -11,19 +11,16 @@ public class DriverState extends CyberarmState {
|
|||||||
this.traveledDistance = robot.configuration.variable(groupName, actionName, "traveledDistance").value();
|
this.traveledDistance = robot.configuration.variable(groupName, actionName, "traveledDistance").value();
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
private float RobotRotation;
|
|
||||||
private double drivePower;
|
private double drivePower;
|
||||||
private int RobotPosition,RobotStartingPosition,traveledDistance;
|
private int traveledDistance;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void exec() {
|
public void exec() {
|
||||||
|
|
||||||
if (RobotPosition - RobotStartingPosition < traveledDistance){
|
if (robot.frontRightDrive.getCurrentPosition() < traveledDistance){
|
||||||
drivePower = 1;
|
robot.backLeftDrive.setPower(drivePower * 0.5);
|
||||||
robot.backLeftDrive.setPower(drivePower);
|
|
||||||
robot.backRightDrive.setPower(drivePower);
|
robot.backRightDrive.setPower(drivePower);
|
||||||
robot.frontLeftDrive.setPower(drivePower);
|
robot.frontLeftDrive.setPower(drivePower * 0.5);
|
||||||
robot.frontRightDrive.setPower(drivePower);
|
robot.frontRightDrive.setPower(drivePower);
|
||||||
} else {
|
} else {
|
||||||
robot.backLeftDrive.setPower(0);
|
robot.backLeftDrive.setPower(0);
|
||||||
|
|||||||
@@ -21,7 +21,7 @@ public class RotationState extends CyberarmState {
|
|||||||
|
|
||||||
|
|
||||||
RobotRotation = robot.imu.getAngularOrientation().firstAngle;
|
RobotRotation = robot.imu.getAngularOrientation().firstAngle;
|
||||||
if (RobotRotation - 3 <= targetRotation || RobotRotation + 3 <= targetRotation) {
|
if (RobotRotation <= targetRotation -3 || RobotRotation >= targetRotation + 3) {
|
||||||
robot.backLeftDrive.setPower(-drivePower);
|
robot.backLeftDrive.setPower(-drivePower);
|
||||||
robot.backRightDrive.setPower(drivePower);
|
robot.backRightDrive.setPower(drivePower);
|
||||||
robot.frontLeftDrive.setPower(-drivePower);
|
robot.frontLeftDrive.setPower(-drivePower);
|
||||||
|
|||||||
@@ -89,17 +89,22 @@ public class PrototypeBot1 {
|
|||||||
//motors direction and encoders
|
//motors direction and encoders
|
||||||
|
|
||||||
frontLeftDrive.setDirection(DcMotorSimple.Direction.REVERSE);
|
frontLeftDrive.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
frontLeftDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||||
frontLeftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
frontLeftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||||
|
|
||||||
frontRightDrive.setDirection(DcMotorSimple.Direction.FORWARD);
|
frontRightDrive.setDirection(DcMotorSimple.Direction.FORWARD);
|
||||||
|
frontRightDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||||
frontRightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
frontRightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||||
|
|
||||||
backLeftDrive.setDirection(DcMotorSimple.Direction.REVERSE);
|
backLeftDrive.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
|
backLeftDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||||
backLeftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
backLeftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||||
|
|
||||||
backRightDrive.setDirection(DcMotorSimple.Direction.FORWARD);
|
backRightDrive.setDirection(DcMotorSimple.Direction.FORWARD);
|
||||||
|
backRightDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||||
backRightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
backRightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||||
|
|
||||||
|
|
||||||
HighRiserLeft.setDirection(Servo.Direction.REVERSE);
|
HighRiserLeft.setDirection(Servo.Direction.REVERSE);
|
||||||
HighRiserRight.setDirection(Servo.Direction.FORWARD);
|
HighRiserRight.setDirection(Servo.Direction.FORWARD);
|
||||||
LowRiserLeft.setDirection(Servo.Direction.FORWARD);
|
LowRiserLeft.setDirection(Servo.Direction.FORWARD);
|
||||||
|
|||||||
Reference in New Issue
Block a user