RedCrab: Fixed Move state erroneous instantly finishing- sometimes; due to caching, fix CyberarmEngine not throwing errors when expected, mostly functional Red Audience path (with center deposit branch added)

This commit is contained in:
2024-01-07 21:12:23 -06:00
parent dffb883427
commit 8c103aeec0
4 changed files with 27 additions and 8 deletions

View File

@@ -514,11 +514,15 @@ public abstract class CyberarmEngine extends OpMode {
RuntimeException exception = new RuntimeException(cause.getMessage(), cause.getCause());
exception.setStackTrace(cause.getStackTrace());
throw(exception);
} else {
e.printStackTrace();
RuntimeException exception = new RuntimeException(e.getMessage(), e.getCause());
exception.setStackTrace(e.getStackTrace());
throw(exception);
}
}
}

File diff suppressed because one or more lines are too long

View File

@@ -11,9 +11,9 @@ public abstract class RedCrabAutonomousEngine extends CyberarmEngine {
public void loop() {
Utilities.hubsClearBulkReadCache(hardwareMap);
super.loop();
if (robot != null)
robot.standardTelemetry();
super.loop();
}
}

View File

@@ -1,5 +1,7 @@
package dev.cyberarm.minibots.red_crab.states;
import android.util.Log;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.util.Range;
@@ -27,13 +29,21 @@ public class Move extends CyberarmState {
this.lerpMM_DOWN = robot.config.variable(groupName, actionName, "lerpMM_DOWN").value();
this.toleranceMM = robot.config.variable(groupName, actionName, "toleranceMM").value();
this.maxVelocityMM = robot.config.variable(groupName, actionName, "maxVelocityMM").value();
this.minVelocityMM = robot.config.variable(groupName, actionName, "minVelocityMM").value();
double maxVelocityMM = robot.config.variable(groupName, actionName, "maxVelocityMM").value();
double minVelocityMM = robot.config.variable(groupName, actionName, "minVelocityMM").value();
this.strafe = robot.config.variable(groupName, actionName, "strafe").value();
this.timeoutMS = robot.config.variable(groupName, actionName, "timeoutMS").value();
if (distanceMM < 0) {
this.maxVelocityMM = Math.abs(maxVelocityMM) * -1;
this.minVelocityMM = Math.abs(minVelocityMM) * -1;
} else {
this.maxVelocityMM = Math.abs(maxVelocityMM);
this.minVelocityMM = Math.abs(minVelocityMM);
}
// Validate distance and lerp distances
if (lerpMM_UP == 0 && lerpMM_DOWN == 0) { return; }
@@ -94,6 +104,9 @@ public class Move extends CyberarmState {
robot.backLeft.setTargetPosition(distanceTicks);
robot.backRight.setTargetPosition(distanceTicks);
}
// Explicitly reset cached hub data, fixes Move state erroneous instantly finishing- sometimes.
Utilities.hubsClearBulkReadCache(engine.hardwareMap);
}
@Override
@@ -122,14 +135,17 @@ public class Move extends CyberarmState {
double velocity = lerpVelocity(travelledDistance);
double angleDiff = Utilities.angleDiff(initialHeadingDegrees, Utilities.facing(robot.imu));
if (maxVelocityMM < 0)
angleDiff = -1 * angleDiff;
double leftVelocity = velocity;
double rightVelocity = velocity;
// use +10% of power at 7 degrees of error to correct angle
double correctiveVelocity = Utilities.lerp(0.0, 1.0, angleDiff / 7.0) * (velocity * 0.1);
if (angleDiff > -0.5) {
if (angleDiff < -0.5) {
leftVelocity += correctiveVelocity;
} else if (angleDiff < 0.5) {
} else if (angleDiff > 0.5) {
rightVelocity += correctiveVelocity;
}
@@ -155,7 +171,6 @@ public class Move extends CyberarmState {
double velocity = lerpVelocity(travelledDistance);
double angleDiff = Utilities.angleDiff(initialHeadingDegrees, Utilities.facing(robot.imu));
double frontVelocity = velocity;
double backVelocity = velocity;
// use +40% of power at 7 degrees of error to correct angle