AP_BoardConfig: rename sensor_config_error to config_error

This commit is contained in:
Mark Whitehorn 2019-11-04 15:55:39 -07:00 committed by Peter Barker
parent 7f6e89bee8
commit 9cf708b846
4 changed files with 19 additions and 10 deletions

View File

@ -335,7 +335,7 @@ void AP_BoardConfig::init_safety()
*/
bool AP_BoardConfig::_in_sensor_config_error;
void AP_BoardConfig::sensor_config_error(const char *reason)
void AP_BoardConfig::config_error(const char *fmt, ...)
{
_in_sensor_config_error = true;
/*
@ -349,9 +349,18 @@ void AP_BoardConfig::sensor_config_error(const char *reason)
uint32_t now = AP_HAL::millis();
if (now - last_print_ms >= 3000) {
last_print_ms = now;
printf("Sensor failure: %s\n", reason);
va_list arg_list;
char printfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+2];
hal.util->snprintf(printfmt, sizeof(printfmt), "Config error: %s\n", fmt);
va_start(arg_list, fmt);
vprintf(printfmt, arg_list);
va_end(arg_list);
#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && !defined(HAL_BUILD_AP_PERIPH)
gcs().send_text(MAV_SEVERITY_ERROR, "Check BRD_TYPE: %s", reason);
char taggedfmt[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
hal.util->snprintf(taggedfmt, sizeof(taggedfmt), "Config error: %s", fmt);
va_start(arg_list, fmt);
gcs().send_textv(MAV_SEVERITY_CRITICAL, taggedfmt, arg_list);
va_end(arg_list);
#endif
}
#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && !defined(HAL_BUILD_AP_PERIPH)

View File

@ -58,11 +58,11 @@ public:
static const struct AP_Param::GroupInfo var_info[];
// notify user of a fatal startup error related to available sensors.
static void sensor_config_error(const char *reason);
static void 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; }
static bool in_config_error(void) { return _in_sensor_config_error; }
// valid types for BRD_TYPE: these values need to be in sync with the
// values from the param description

View File

@ -171,7 +171,7 @@ void AP_BoardConfig_CAN::init()
_drivers[i]._driver = _drivers[i]._tcan = new AP_ToshibaCAN;
if (_drivers[i]._driver == nullptr) {
AP_BoardConfig::sensor_config_error("ToshibaCAN init failed");
AP_BoardConfig::config_error("ToshibaCAN init failed");
continue;
}
} else {

View File

@ -116,7 +116,7 @@ void AP_BoardConfig::board_setup_drivers(void)
case PX4_BOARD_MINDPXV2:
break;
default:
sensor_config_error("Unknown board type");
config_error("Unknown board type");
break;
}
}
@ -251,7 +251,7 @@ void AP_BoardConfig::validate_board_type(void)
// configured for PIXHAWK1
#if !defined(CONFIG_ARCH_BOARD_PX4FMU_V3) && !defined(HAL_CHIBIOS_ARCH_FMUV3)
// force user to load the right firmware
sensor_config_error("Pixhawk2 requires FMUv3 firmware");
config_error("Pixhawk2 requires FMUv3 firmware");
#endif
state.board_type.set(PX4_BOARD_PIXHAWK2);
hal.console->printf("Forced PIXHAWK2\n");
@ -282,7 +282,7 @@ void AP_BoardConfig::check_cubeblack(void)
if (!check_ms5611("ms5611_ext")) { success = false; }
if (!success) {
sensor_config_error("Failed to init CubeBlack - sensor mismatch");
config_error("Failed to init CubeBlack - sensor mismatch");
}
#endif
}
@ -338,7 +338,7 @@ void AP_BoardConfig::board_autodetect(void)
state.board_type.set(PX4_BOARD_PIXHAWK);
hal.console->printf("Detected Pixhawk\n");
} else {
sensor_config_error("Unable to detect board type");
config_error("Unable to detect board type");
}
#elif defined(CONFIG_ARCH_BOARD_PX4FMU_V4) || defined(HAL_CHIBIOS_ARCH_FMUV4)
// only one choice