AP_Arming: status text severity to INFO

This commit is contained in:
lvale 2015-11-09 16:01:50 +09:00 committed by Randy Mackay
parent 9d88508cc3
commit b601ef2f9e
1 changed files with 3 additions and 3 deletions

View File

@ -398,7 +398,7 @@ bool AP_Arming::arm(uint8_t method)
if (checks_to_perform == ARMING_CHECK_NONE) {
armed = true;
arming_method = NONE;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Throttle armed!");
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Throttle armed!");
return true;
}
@ -406,7 +406,7 @@ bool AP_Arming::arm(uint8_t method)
armed = true;
arming_method = method;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Throttle armed!");
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Throttle armed!");
//TODO: Log motor arming to the dataflash
//Can't do this from this class until there is a unified logging library
@ -427,7 +427,7 @@ bool AP_Arming::disarm()
}
armed = false;
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Throttle disarmed!");
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Throttle disarmed!");
//TODO: Log motor disarming to the dataflash
//Can't do this from this class until there is a unified logging library.