forked from Archive/PX4-Autopilot
commander: refactored state-machine strings
- Follow-up changes to https://github.com/PX4/Firmware/pull/11796
This commit is contained in:
parent
136962d125
commit
2deab6c607
|
@ -226,7 +226,7 @@ transition_result_t arming_state_transition(vehicle_status_s *status, const safe
|
|||
if (ret == TRANSITION_DENIED) {
|
||||
/* print to MAVLink and console if we didn't provide any feedback yet */
|
||||
if (!feedback_provided) {
|
||||
mavlink_log_critical(mavlink_log_pub, "TRANSITION_DENIED: %s to %s",
|
||||
mavlink_log_critical(mavlink_log_pub, "Transition denied: %s to %s",
|
||||
arming_state_names[status->arming_state], arming_state_names[new_arming_state]);
|
||||
}
|
||||
}
|
||||
|
@ -922,7 +922,7 @@ bool prearm_check(orb_advert_t *mavlink_log_pub, const vehicle_status_flags_s &s
|
|||
// USB not connected
|
||||
if (!status_flags.circuit_breaker_engaged_usb_check && status_flags.usb_connected) {
|
||||
if (reportFailures) {
|
||||
mavlink_log_critical(mavlink_log_pub, "ARMING DENIED: Flying with USB is not safe");
|
||||
mavlink_log_critical(mavlink_log_pub, "Arming denied! Flying with USB is not safe");
|
||||
}
|
||||
|
||||
prearm_ok = false;
|
||||
|
@ -934,7 +934,7 @@ bool prearm_check(orb_advert_t *mavlink_log_pub, const vehicle_status_flags_s &s
|
|||
// Fail transition if power is not good
|
||||
if (!status_flags.condition_power_input_valid) {
|
||||
if (reportFailures) {
|
||||
mavlink_log_critical(mavlink_log_pub, "ARMING DENIED: Connect power module");
|
||||
mavlink_log_critical(mavlink_log_pub, "Arming denied! Connect power module");
|
||||
}
|
||||
|
||||
prearm_ok = false;
|
||||
|
@ -943,7 +943,7 @@ bool prearm_check(orb_advert_t *mavlink_log_pub, const vehicle_status_flags_s &s
|
|||
// main battery level
|
||||
if (!status_flags.condition_battery_healthy) {
|
||||
if (prearm_ok && reportFailures) {
|
||||
mavlink_log_critical(mavlink_log_pub, "ARMING DENIED: CHECK BATTERY");
|
||||
mavlink_log_critical(mavlink_log_pub, "Arming denied! Check battery");
|
||||
}
|
||||
|
||||
prearm_ok = false;
|
||||
|
@ -955,7 +955,7 @@ bool prearm_check(orb_advert_t *mavlink_log_pub, const vehicle_status_flags_s &s
|
|||
|
||||
if (!status_flags.condition_auto_mission_available) {
|
||||
if (prearm_ok && reportFailures) {
|
||||
mavlink_log_critical(mavlink_log_pub, "ARMING DENIED: valid mission required");
|
||||
mavlink_log_critical(mavlink_log_pub, "Arming denied! No valid mission");
|
||||
}
|
||||
|
||||
prearm_ok = false;
|
||||
|
@ -963,7 +963,7 @@ bool prearm_check(orb_advert_t *mavlink_log_pub, const vehicle_status_flags_s &s
|
|||
|
||||
if (!status_flags.condition_global_position_valid) {
|
||||
if (prearm_ok && reportFailures) {
|
||||
mavlink_log_critical(mavlink_log_pub, "ARMING DENIED: mission requires global position");
|
||||
mavlink_log_critical(mavlink_log_pub, "Arming denied! Missions require a global position");
|
||||
}
|
||||
|
||||
prearm_ok = false;
|
||||
|
@ -975,7 +975,7 @@ bool prearm_check(orb_advert_t *mavlink_log_pub, const vehicle_status_flags_s &s
|
|||
|
||||
if (!status_flags.condition_global_position_valid) {
|
||||
if (prearm_ok && reportFailures) {
|
||||
mavlink_log_critical(mavlink_log_pub, "ARMING DENIED: global position required");
|
||||
mavlink_log_critical(mavlink_log_pub, "Arming denied! Global position required");
|
||||
}
|
||||
|
||||
prearm_ok = false;
|
||||
|
@ -986,7 +986,7 @@ bool prearm_check(orb_advert_t *mavlink_log_pub, const vehicle_status_flags_s &s
|
|||
if (safety.safety_switch_available && !safety.safety_off) {
|
||||
// Fail transition if we need safety switch press
|
||||
if (prearm_ok && reportFailures) {
|
||||
mavlink_log_critical(mavlink_log_pub, "ARMING DENIED: Press safety switch first");
|
||||
mavlink_log_critical(mavlink_log_pub, "Arming denied! Press safety switch first");
|
||||
}
|
||||
|
||||
prearm_ok = false;
|
||||
|
@ -1003,7 +1003,7 @@ bool prearm_check(orb_advert_t *mavlink_log_pub, const vehicle_status_flags_s &s
|
|||
|
||||
if (status_flags.avoidance_system_required && !status_flags.avoidance_system_valid) {
|
||||
if (prearm_ok && reportFailures) {
|
||||
mavlink_log_critical(mavlink_log_pub, "ARMING DENIED: Avoidance system not ready");
|
||||
mavlink_log_critical(mavlink_log_pub, "Arming denied! Avoidance system not ready");
|
||||
}
|
||||
|
||||
prearm_ok = false;
|
||||
|
@ -1023,16 +1023,16 @@ void battery_failsafe(orb_advert_t *mavlink_log_pub, const vehicle_status_s &sta
|
|||
break;
|
||||
|
||||
case battery_status_s::BATTERY_WARNING_LOW:
|
||||
mavlink_log_critical(mavlink_log_pub, "LOW BATTERY, RETURN ADVISED");
|
||||
mavlink_log_critical(mavlink_log_pub, "Low battery level! Return advised");
|
||||
break;
|
||||
|
||||
case battery_status_s::BATTERY_WARNING_CRITICAL:
|
||||
|
||||
static constexpr char battery_critical[] = "CRITICAL BATTERY";
|
||||
static constexpr char battery_critical[] = "Critical battery level!";
|
||||
|
||||
switch (low_battery_action) {
|
||||
case LOW_BAT_ACTION::WARNING:
|
||||
mavlink_log_critical(mavlink_log_pub, "%s, RETURN ADVISED!", battery_critical);
|
||||
mavlink_log_critical(mavlink_log_pub, "%s, Landing advised", battery_critical);
|
||||
break;
|
||||
|
||||
case LOW_BAT_ACTION::RETURN:
|
||||
|
@ -1043,10 +1043,10 @@ void battery_failsafe(orb_advert_t *mavlink_log_pub, const vehicle_status_s &sta
|
|||
// let us send the critical message even if already in RTL
|
||||
if (TRANSITION_DENIED != main_state_transition(status, commander_state_s::MAIN_STATE_AUTO_RTL, status_flags,
|
||||
internal_state)) {
|
||||
mavlink_log_critical(mavlink_log_pub, "%s, RETURNING", battery_critical);
|
||||
mavlink_log_critical(mavlink_log_pub, "%s, Executing RTL", battery_critical);
|
||||
|
||||
} else {
|
||||
mavlink_log_emergency(mavlink_log_pub, "%s, RETURN FAILED", battery_critical);
|
||||
mavlink_log_emergency(mavlink_log_pub, "%s, Can't execute RTL", battery_critical);
|
||||
}
|
||||
|
||||
break;
|
||||
|
@ -1054,10 +1054,10 @@ void battery_failsafe(orb_advert_t *mavlink_log_pub, const vehicle_status_s &sta
|
|||
case LOW_BAT_ACTION::LAND:
|
||||
if (TRANSITION_DENIED != main_state_transition(status, commander_state_s::MAIN_STATE_AUTO_LAND, status_flags,
|
||||
internal_state)) {
|
||||
mavlink_log_critical(mavlink_log_pub, "%s, LANDING AT CURRENT POSITION", battery_critical);
|
||||
mavlink_log_critical(mavlink_log_pub, "%s, Landing immediately", battery_critical);
|
||||
|
||||
} else {
|
||||
mavlink_log_emergency(mavlink_log_pub, "%s, LANDING FAILED", battery_critical);
|
||||
mavlink_log_emergency(mavlink_log_pub, "%s, Can't execute landing", battery_critical);
|
||||
}
|
||||
|
||||
break;
|
||||
|
@ -1067,20 +1067,20 @@ void battery_failsafe(orb_advert_t *mavlink_log_pub, const vehicle_status_s &sta
|
|||
|
||||
case battery_status_s::BATTERY_WARNING_EMERGENCY:
|
||||
|
||||
static constexpr char battery_dangerous[] = "DANGEROUS BATTERY LEVEL";
|
||||
static constexpr char battery_dangerous[] = "Dangerous battery level!";
|
||||
|
||||
switch (low_battery_action) {
|
||||
case LOW_BAT_ACTION::WARNING:
|
||||
mavlink_log_emergency(mavlink_log_pub, "%s, LANDING ADVISED!", battery_dangerous);
|
||||
mavlink_log_emergency(mavlink_log_pub, "%s, Please land!", battery_dangerous);
|
||||
break;
|
||||
|
||||
case LOW_BAT_ACTION::RETURN:
|
||||
if (TRANSITION_DENIED != main_state_transition(status, commander_state_s::MAIN_STATE_AUTO_RTL, status_flags,
|
||||
internal_state)) {
|
||||
mavlink_log_emergency(mavlink_log_pub, "%s, RETURNING", battery_dangerous);
|
||||
mavlink_log_emergency(mavlink_log_pub, "%s, Executing RTL", battery_dangerous);
|
||||
|
||||
} else {
|
||||
mavlink_log_emergency(mavlink_log_pub, "%s, RETURN FAILED", battery_dangerous);
|
||||
mavlink_log_emergency(mavlink_log_pub, "%s, Can't execute RTL", battery_dangerous);
|
||||
}
|
||||
|
||||
break;
|
||||
|
@ -1091,10 +1091,10 @@ void battery_failsafe(orb_advert_t *mavlink_log_pub, const vehicle_status_s &sta
|
|||
case LOW_BAT_ACTION::LAND:
|
||||
if (TRANSITION_DENIED != main_state_transition(status, commander_state_s::MAIN_STATE_AUTO_LAND, status_flags,
|
||||
internal_state)) {
|
||||
mavlink_log_emergency(mavlink_log_pub, "%s, LANDING IMMEDIATELY", battery_dangerous);
|
||||
mavlink_log_emergency(mavlink_log_pub, "%s, Landing immediately", battery_dangerous);
|
||||
|
||||
} else {
|
||||
mavlink_log_emergency(mavlink_log_pub, "%s, LANDING FAILED", battery_dangerous);
|
||||
mavlink_log_emergency(mavlink_log_pub, "%s, Can't execute landing", battery_dangerous);
|
||||
}
|
||||
|
||||
break;
|
||||
|
@ -1103,7 +1103,7 @@ void battery_failsafe(orb_advert_t *mavlink_log_pub, const vehicle_status_s &sta
|
|||
break;
|
||||
|
||||
case battery_status_s::BATTERY_WARNING_FAILED:
|
||||
mavlink_log_emergency(mavlink_log_pub, "BATTERY FAILED");
|
||||
mavlink_log_emergency(mavlink_log_pub, "Battery failure detected");
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue