mirror of
https://github.com/TimeCrafters/FTC_2022
synced 2025-12-15 20:12:35 +00:00
Slowing the button rotation on TeleOP, Sprint 3 TeleOP, take 5. (CAW caw caw CAWAW awcaw CAW)
This commit is contained in:
@@ -153,14 +153,14 @@ public class PrototypeTeleOPState extends CyberarmState {
|
||||
RobotRotation = robot.imu.getAngularOrientation().firstAngle;
|
||||
RotationTarget = -180;
|
||||
if (RobotRotation < 0 && RobotRotation > -177) {
|
||||
drivePower = (1 * (Math.abs(RobotRotation) - Math.abs(RotationTarget))/180) + 0.3;
|
||||
drivePower = (1 * ((RobotRotation) - (RotationTarget))/180) + 0.3;
|
||||
robot.backLeftDrive.setPower(drivePower);
|
||||
robot.backRightDrive.setPower(-drivePower);
|
||||
robot.frontLeftDrive.setPower(drivePower);
|
||||
robot.frontRightDrive.setPower(-drivePower);
|
||||
}
|
||||
if (RobotRotation > 0) {
|
||||
drivePower = (-1 * (Math.abs(RobotRotation) - Math.abs(RotationTarget))/180) - 0.3;
|
||||
drivePower = (-1 * ((RobotRotation) - (RotationTarget))/180) - 0.3;
|
||||
robot.backLeftDrive.setPower(drivePower);
|
||||
robot.backRightDrive.setPower(-drivePower);
|
||||
robot.frontLeftDrive.setPower(drivePower);
|
||||
@@ -179,14 +179,14 @@ public class PrototypeTeleOPState extends CyberarmState {
|
||||
RobotRotation = robot.imu.getAngularOrientation().firstAngle;
|
||||
RotationTarget = 0;
|
||||
if (RobotRotation < -3) {
|
||||
drivePower = (-1 * (Math.abs(RobotRotation) - Math.abs(RotationTarget))/180) - 0.3;
|
||||
drivePower = (-1 * ((RobotRotation) - (RotationTarget))/180) - 0.3;
|
||||
robot.backLeftDrive.setPower(drivePower);
|
||||
robot.backRightDrive.setPower(-drivePower);
|
||||
robot.frontLeftDrive.setPower(drivePower);
|
||||
robot.frontRightDrive.setPower(-drivePower);
|
||||
}
|
||||
if (RobotRotation > 3) {
|
||||
drivePower = (1 * (Math.abs(RobotRotation) - Math.abs(RotationTarget))/180) + 0.3;
|
||||
drivePower = (1 * ((RobotRotation) - (RotationTarget))/180) + 0.3;
|
||||
robot.backLeftDrive.setPower(drivePower);
|
||||
robot.backRightDrive.setPower(-drivePower);
|
||||
robot.frontLeftDrive.setPower(drivePower);
|
||||
@@ -204,14 +204,14 @@ public class PrototypeTeleOPState extends CyberarmState {
|
||||
RobotRotation = robot.imu.getAngularOrientation().firstAngle;
|
||||
RotationTarget = 135;
|
||||
if (RobotRotation > -45 && RobotRotation < 132) {//CCW
|
||||
drivePower = (-1 * (Math.abs(RobotRotation) - Math.abs(RotationTarget))/180) - 0.3;
|
||||
drivePower = (-1 * ((RobotRotation) - (RotationTarget))/180) - 0.3;
|
||||
robot.backLeftDrive.setPower(drivePower);
|
||||
robot.backRightDrive.setPower(-drivePower);
|
||||
robot.frontLeftDrive.setPower(drivePower);
|
||||
robot.frontRightDrive.setPower(-drivePower);
|
||||
}
|
||||
if (RobotRotation < -45 || RobotRotation > 138) {//CW
|
||||
drivePower = (1 * (Math.abs(RobotRotation) - Math.abs(RotationTarget))/180) + 0.3;
|
||||
drivePower = (1 * ((RobotRotation) - (RotationTarget))/180) + 0.3;
|
||||
robot.backLeftDrive.setPower(drivePower);
|
||||
robot.backRightDrive.setPower(-drivePower);
|
||||
robot.frontLeftDrive.setPower(drivePower);
|
||||
@@ -229,14 +229,14 @@ public class PrototypeTeleOPState extends CyberarmState {
|
||||
RobotRotation = robot.imu.getAngularOrientation().firstAngle;
|
||||
RotationTarget = -135;
|
||||
if (RobotRotation < 45 && RobotRotation > -132) {//CCW
|
||||
drivePower = (1 * (Math.abs(RobotRotation) - Math.abs(RotationTarget))/180) + 0.3;
|
||||
drivePower = (1 * ((RobotRotation) - (RotationTarget))/180) + 0.3;
|
||||
robot.backLeftDrive.setPower(drivePower);
|
||||
robot.backRightDrive.setPower(-drivePower);
|
||||
robot.frontLeftDrive.setPower(drivePower);
|
||||
robot.frontRightDrive.setPower(-drivePower);
|
||||
}
|
||||
if (RobotRotation > 45 || RobotRotation < -138) {//CW
|
||||
drivePower = (-1 * (Math.abs(RobotRotation) - Math.abs(RotationTarget))/180) - 0.3;
|
||||
drivePower = (-1 * ((RobotRotation) - (RotationTarget))/180) - 0.3;
|
||||
robot.backLeftDrive.setPower(drivePower);
|
||||
robot.backRightDrive.setPower(-drivePower);
|
||||
robot.frontLeftDrive.setPower(drivePower);
|
||||
|
||||
Reference in New Issue
Block a user