AP_Arming: update severities

This commit is contained in:
squilter 2015-08-25 14:26:44 -07:00 committed by Andrew Tridgell
parent d4ed30a023
commit ddda407ff3
2 changed files with 22 additions and 22 deletions

View File

@ -83,7 +83,7 @@ bool AP_Arming::barometer_checks(bool report)
(checks_to_perform & ARMING_CHECK_BARO)) {
if (! barometer.healthy()) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Barometer not healthy!"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Barometer not healthy!"));
}
return false;
}
@ -103,7 +103,7 @@ bool AP_Arming::airspeed_checks(bool report)
}
if (airspeed->enabled() && airspeed->use() && !airspeed->healthy()) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: airspeed not healthy"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: airspeed not healthy"));
}
return false;
}
@ -118,7 +118,7 @@ bool AP_Arming::logging_checks(bool report)
(checks_to_perform & ARMING_CHECK_LOGGING)) {
if (!logging_available) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: logging not available"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: logging not available"));
}
return false;
}
@ -133,31 +133,31 @@ bool AP_Arming::ins_checks(bool report)
const AP_InertialSensor &ins = ahrs.get_ins();
if (! ins.get_gyro_health_all()) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: gyros not healthy!"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: gyros not healthy!"));
}
return false;
}
if (!skip_gyro_cal && ! ins.gyro_calibrated_ok_all()) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: gyros not calibrated!"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: gyros not calibrated!"));
}
return false;
}
if (! ins.get_accel_health_all()) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: accels not healthy!"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: accels not healthy!"));
}
return false;
}
if (!ahrs.healthy()) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: AHRS not healthy!"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: AHRS not healthy!"));
}
return false;
}
if (!ins.accel_calibrated_ok_all()) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: 3D accel cal needed"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: 3D accel cal needed"));
}
return false;
}
@ -185,7 +185,7 @@ bool AP_Arming::ins_checks(bool report)
}
if (hal.scheduler->millis() - last_accel_pass_ms[i] > 10000) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: inconsistent Accelerometers"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: inconsistent Accelerometers"));
}
return false;
}
@ -206,7 +206,7 @@ bool AP_Arming::ins_checks(bool report)
}
if (hal.scheduler->millis() - last_gyro_pass_ms[i] > 10000) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: inconsistent gyros"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: inconsistent gyros"));
}
return false;
}
@ -230,14 +230,14 @@ bool AP_Arming::compass_checks(bool report)
if (!_compass.healthy()) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Compass not healthy!"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Compass not healthy!"));
}
return false;
}
// check compass learning is on or offsets have been set
if (!_compass.learn_offsets_enabled() && !_compass.configured()) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Compass not calibrated"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Compass not calibrated"));
}
return false;
}
@ -246,7 +246,7 @@ bool AP_Arming::compass_checks(bool report)
Vector3f offsets = _compass.get_offsets();
if (offsets.length() > 600) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Compass offsets too high"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Compass offsets too high"));
}
return false;
}
@ -261,7 +261,7 @@ bool AP_Arming::compass_checks(bool report)
float mag_field = _compass.get_field().length();
if (mag_field > COMPASS_MAGFIELD_EXPECTED*1.65f || mag_field < COMPASS_MAGFIELD_EXPECTED*0.35f) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Check mag field"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Check mag field"));
}
return false;
}
@ -281,7 +281,7 @@ bool AP_Arming::gps_checks(bool report)
if (home_is_set == HOME_UNSET ||
gps.status() < AP_GPS::GPS_OK_FIX_3D) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Bad GPS Position"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Bad GPS Position"));
}
return false;
}
@ -297,7 +297,7 @@ bool AP_Arming::battery_checks(bool report)
if (AP_Notify::flags.failsafe_battery) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Battery failsafe on."));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Battery failsafe on."));
}
return false;
}
@ -311,7 +311,7 @@ bool AP_Arming::hardware_safety_check(bool report)
// check if safety switch has been pushed
if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Hardware Safety Switch"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Hardware Safety Switch"));
}
return false;
}
@ -326,7 +326,7 @@ bool AP_Arming::manual_transmitter_checks(bool report)
if (AP_Notify::flags.failsafe_radio) {
if (report) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Radio failsafe on"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("PreArm: Radio failsafe on"));
}
return false;
}
@ -372,7 +372,7 @@ bool AP_Arming::arm(uint8_t method)
if (checks_to_perform == ARMING_CHECK_NONE) {
armed = true;
arming_method = NONE;
gcs_send_text_P(SEVERITY_HIGH,PSTR("Throttle armed!"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Throttle armed!"));
return true;
}
@ -380,7 +380,7 @@ bool AP_Arming::arm(uint8_t method)
armed = true;
arming_method = method;
gcs_send_text_P(SEVERITY_HIGH,PSTR("Throttle armed!"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Throttle armed!"));
//TODO: Log motor arming to the dataflash
//Can't do this from this class until there is a unified logging library
@ -401,7 +401,7 @@ bool AP_Arming::disarm()
}
armed = false;
gcs_send_text_P(SEVERITY_HIGH,PSTR("Throttle disarmed!"));
gcs_send_text_P(MAV_SEVERITY_CRITICAL,PSTR("Throttle disarmed!"));
//TODO: Log motor disarming to the dataflash
//Can't do this from this class until there is a unified logging library.

View File

@ -44,7 +44,7 @@ public:
};
// for the hacky function pointer to gcs_send_text_p
FUNCTOR_TYPEDEF(gcs_send_t_p, void, gcs_severity, const prog_char_t *);
FUNCTOR_TYPEDEF(gcs_send_t_p, void, MAV_SEVERITY, const prog_char_t *);
AP_Arming(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
const enum HomeState &home_set, gcs_send_t_p);