AP_BoardConfig: add public method returning true if on sensor error

This commit is contained in:
Peter Barker 2017-06-06 17:18:15 +10:00 committed by Francisco Ferreira
parent 1ce2a7fcee
commit 5c15c1e4d2
2 changed files with 9 additions and 1 deletions

View File

@ -226,8 +226,11 @@ void AP_BoardConfig::init_safety()
/* /*
notify user of a fatal startup error related to available sensors. notify user of a fatal startup error related to available sensors.
*/ */
bool AP_BoardConfig::_in_sensor_config_error;
void AP_BoardConfig::sensor_config_error(const char *reason) void AP_BoardConfig::sensor_config_error(const char *reason)
{ {
_in_sensor_config_error = true;
/* /*
to give the user the opportunity to connect to USB we keep to give the user the opportunity to connect to USB we keep
repeating the error. The mavlink delay callback is initialised repeating the error. The mavlink delay callback is initialised

View File

@ -44,7 +44,10 @@ public:
// notify user of a fatal startup error related to available sensors. // notify user of a fatal startup error related to available sensors.
static void sensor_config_error(const char *reason); static void sensor_config_error(const char *reason);
// permit other libraries (in particular, GCS_MAVLink) to detect
// that we're never going to boot properly:
static bool in_sensor_config_error(void) { return _in_sensor_config_error; }
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN
// public method to start a driver // public method to start a driver
static bool px4_start_driver(main_fn_t main_function, const char *name, const char *arguments); static bool px4_start_driver(main_fn_t main_function, const char *name, const char *arguments);
@ -149,6 +152,8 @@ private:
#endif // HAL_BOARD_PX4 || HAL_BOARD_VRBRAIN #endif // HAL_BOARD_PX4 || HAL_BOARD_VRBRAIN
static bool _in_sensor_config_error;
// target temperarure for IMU in Celsius, or -1 to disable // target temperarure for IMU in Celsius, or -1 to disable
AP_Int8 _imu_target_temperature; AP_Int8 _imu_target_temperature;
}; };