Browse Source

AP_BoardConfig: add public method returning true if on sensor error

master
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
5c15c1e4d2
  1. 3
      libraries/AP_BoardConfig/AP_BoardConfig.cpp
  2. 5
      libraries/AP_BoardConfig/AP_BoardConfig.h

3
libraries/AP_BoardConfig/AP_BoardConfig.cpp

@ -226,8 +226,11 @@ void AP_BoardConfig::init_safety() @@ -226,8 +226,11 @@ void AP_BoardConfig::init_safety()
/*
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)
{
_in_sensor_config_error = true;
/*
to give the user the opportunity to connect to USB we keep
repeating the error. The mavlink delay callback is initialised

5
libraries/AP_BoardConfig/AP_BoardConfig.h

@ -44,6 +44,9 @@ public: @@ -44,6 +44,9 @@ public:
// notify user of a fatal startup error related to available sensors.
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
// public method to start a driver
@ -149,6 +152,8 @@ private: @@ -149,6 +152,8 @@ private:
#endif // HAL_BOARD_PX4 || HAL_BOARD_VRBRAIN
static bool _in_sensor_config_error;
// target temperarure for IMU in Celsius, or -1 to disable
AP_Int8 _imu_target_temperature;
};

Loading…
Cancel
Save