Great job describing this issue!
TLDR: For a quick workaround, move RUN_USING_ENCODER
before while opModeIsActive()
. This worked in my version of your code, as described below.
============
Background
I was able to replicate the “rogue state” where Telemetry reports STOP_AND_RESET
but the motor is still running. This was possible with a simpler version of your code, using gamepad button B instead of a digital limit switch (thus eliminating that potential source of sensor delay).
The rogue state arose only when the stop event happened very soon after the start event, which is true for your robot mechanism.
Your code also has another characteristic, that pressing the A button allows retraction to resume, after the limit switch was triggered. The code logic seems to preclude that, but it does happen.
In fact, a way to recover from the rogue state, is to press the A button again, which resets retracting
to True, which allows the limit switch (my button B) to again call STOP_AND_RESET
, with success.
I think there are three considerations here:
-
Do you want retracting and limit-stopping to be mutually exclusive? Namely start just once, then stop when limited? If so, there’s no need to catch the rising edge of Button A.
-
There is indeed a tricky timing issue with the RunModes, possibly related to loop cycle times or the state of logic variables. More on that below.
-
Further obscurity is provided by the FTC Javadocs which you mentioned. Far from being “clear”, here’s the full blurb (emphasis added):
STOP_AND_RESET_ENCODER
.
public static final DcMotor.RunMode STOP_AND_RESET_ENCODER
.
The motor is to set the current encoder position to zero. In contrast to RUN_TO_POSITION, the motor is not rotated in order to achieve this; rather, the current rotational position of the motor is simply reinterpreted as the new zero value. However, as a side effect of placing a motor in this mode, power is removed from the motor, causing it to stop, though it is unspecified whether the motor enters brake or float mode. Further, it should be noted that setting a motor to STOP_AND_RESET_ENCODER may or may not be a transient state: motors connected to some motor controllers will remain in this mode until explicitly transitioned to a different one, while motors connected to other motor controllers will automatically transition to a different mode after the reset of the encoder is complete.
==========
Testing
Here was my first version, replacing your limit switch with Button B. Allows testing with just a DC motor, not a full robot.
v01
if (retracting && gamepad1.b) {
motor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
retracting = false;
}
boolean aThis = gamepad1.a;
if (aThis && !aLast) {
motor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
motor.setVelocity(-1000);
retracting = true;
}
aLast = aThis;
I then tried other versions to address possible underlying issues of:
- code logic
- loop timing
- human response (button release)
The following versions did not eliminate the problem. For all of these, a fast sequence of A, then B, could generate the rogue state. This was true whether or not A was physically released before pressing B.
v02
boolean limitReached = false;
while (opModeIsActive()) {
if (!limitReached) {
if (gamepad1.b) {
motor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
limitReached = true;
}
else if (gamepad1.a) {
motor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
motor.setVelocity(-1000);
}
} // end if !limitReached
// telemetry
} // end while
v03
boolean limitReached = false;
while (opModeIsActive()) {
if (!limitReached && gamepad1.b) {
limitReached = true;
motor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
}
else if (!limitReached && gamepad1.a) {
motor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
motor.setVelocity(-1000);
}
// telemetry
} // end while
=========
Separation
I ending up suspecting the culprit was a fast succession of initiating RUN_USING_ENCODER
and STOP_AND_RESET
. Sure enough, this always works as intended:
v04
boolean limitReached = false;
motor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
while (opModeIsActive()) {
if (!limitReached) {
if (gamepad1.b) {
limitReached = true;
motor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
}
else if (gamepad1.a) {
motor.setVelocity(-1000);
}
} // end if !limitReached
// telemetry
} // end while
No sequence of fast or overlapping inputs could generate the rogue state.
Lastly, I applied this to the first version that replicates your code, and it also works:
v05
boolean aLast = false;
boolean retracting = false;
motor.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
while (opModeIsActive()) {
if (retracting && gamepad1.b) {
motor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
retracting = false;
}
boolean aThis = gamepad1.a;
if (aThis && !aLast) {
motor.setVelocity(-1000);
retracting = true;
}
aLast = aThis;
// telemetry
} // end while
===============
Conclusion
Perhaps there’s no “bug” per se with a single RunMode, but instead there are rare interactions to document and avoid, eventually to improve if deemed essential.