diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index aa9591f0e3..163af7e6a2 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -419,7 +419,10 @@ bool AP_InertialSensor::calibrate_accel(AP_InertialSensor_UserInteract* interact PSTR("Place vehicle %S and press any key.\n"), msg); // wait for user input - interact->blocking_read(); + if (interact->blocking_read()) { + //No need to use interact->printf_P for an error, blocking_read does this when it fails + goto failed; + } // clear out any existing samples from ins update(); diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp index 58f2c6b948..06e3c2ea36 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp @@ -25,7 +25,7 @@ uint8_t AP_InertialSensor_UserInteract_MAVLink::blocking_read(void) } } hal.console->println_P(PSTR("Timed out waiting for user response")); - return 0; + return 1; } void AP_InertialSensor_UserInteract_MAVLink::_printf_P(const prog_char* fmt, ...)