feat:ftc2024-carlike.java

This commit is contained in:
GZod01 2024-01-07 16:37:00 +01:00
parent 4d9fb91769
commit 0064a62555

View file

@ -57,18 +57,18 @@ public class Werobot_FTC2024_carlike extends LinearOpMode {
) )
); );
rm.setDirection(DcMotorSimple.Direction.REVERSE); rm.setDirection(DcMotorSimple.Direction.REVERSE);
telemetry.addData("Mode", "calibrating..."); //telemetry.addData("Mode", "calibrating...");
telemetry.update(); //telemetry.update();
// make sure the imu gyro is calibrated before continuing. // make sure the imu gyro is calibrated before continuing.
while (!isStopRequested() && !imu.isGyroCalibrated()) //while (!isStopRequested() && !imu.isGyroCalibrated())
{ //{
sleep(50); // sleep(50);
idle(); // idle();
} //}
telemetry.addData("Mode", "waiting for start"); telemetry.addData("Mode", "waiting for start");
telemetry.addData("imu calib status", imu.getCalibrationStatus().toString()); //telemetry.addData("imu calib status", imu.getCalibrationStatus().toString());
telemetry.update(); telemetry.update();
waitForStart(); waitForStart();
@ -146,7 +146,7 @@ public class Werobot_FTC2024_carlike extends LinearOpMode {
} }
private void resetAngle() private void resetAngle()
{ {
lastAngles = imu.getAngularOrientation(AxesReference.INTRINSIC, AxesOrder.ZYX, AngleUnit.DEGREES); lastAngles = imu.getRobotOrientation(AxesReference.INTRINSIC, AxesOrder.ZYX, AngleUnit.DEGREES);
globalAngle = 0; globalAngle = 0;
} }
@ -162,7 +162,7 @@ public class Werobot_FTC2024_carlike extends LinearOpMode {
// returned as 0 to +180 or 0 to -180 rolling back to -179 or +179 when rotation passes // returned as 0 to +180 or 0 to -180 rolling back to -179 or +179 when rotation passes
// 180 degrees. We detect this transition and track the total cumulative angle of rotation. // 180 degrees. We detect this transition and track the total cumulative angle of rotation.
Orientation angles = imu.getAngularOrientation(AxesReference.INTRINSIC, AxesOrder.ZYX, AngleUnit.DEGREES); Orientation angles = imu.getRobotOrientation(AxesReference.INTRINSIC, AxesOrder.ZYX, AngleUnit.DEGREES);
double deltaAngle = angles.firstAngle - lastAngles.firstAngle; double deltaAngle = angles.firstAngle - lastAngles.firstAngle;