forked from Archive/PX4-Autopilot
Commander enums: shorten failsafe event messages
Such that the focus is on the important keywords. Signed-off-by: Silvan Fuhrer <silvan@auterion.com>
This commit is contained in:
parent
f6430a27d6
commit
da39d075ac
|
@ -364,7 +364,7 @@
|
|||
},
|
||||
"1": {
|
||||
"name": "manual_control_loss",
|
||||
"description": "manual control loss"
|
||||
"description": "Manual control loss"
|
||||
},
|
||||
"2": {
|
||||
"name": "gcs_connection_loss",
|
||||
|
@ -384,7 +384,7 @@
|
|||
},
|
||||
"6": {
|
||||
"name": "low_remaining_flight_time",
|
||||
"description": "low remaining flight time"
|
||||
"description": "Remaining flight time low"
|
||||
}
|
||||
}
|
||||
},
|
||||
|
@ -402,15 +402,15 @@
|
|||
},
|
||||
"2": {
|
||||
"name": "fallback_posctrl",
|
||||
"description": "fallback to Position mode"
|
||||
"description": "Position mode"
|
||||
},
|
||||
"3": {
|
||||
"name": "fallback_altctrl",
|
||||
"description": "fallback to Altitude mode"
|
||||
"description": "Altitude mode"
|
||||
},
|
||||
"4": {
|
||||
"name": "fallback_stabilized",
|
||||
"description": "fallback to Stabilized mode"
|
||||
"description": "Stabilized mode"
|
||||
},
|
||||
"5": {
|
||||
"name": "hold",
|
||||
|
|
|
@ -195,7 +195,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action
|
|||
events::send<uint32_t, events::px4::enums::failsafe_action_t, uint16_t>(
|
||||
events::ID("commander_failsafe_enter_generic_hold"),
|
||||
{events::Log::Critical, events::LogInternal::Warning},
|
||||
"Failsafe activated, triggering {2} in {3} seconds", mavlink_mode, failsafe_action,
|
||||
"Failsafe, triggering {2} in {3} seconds", mavlink_mode, failsafe_action,
|
||||
(uint16_t) delay_s);
|
||||
|
||||
} else {
|
||||
|
@ -204,7 +204,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action
|
|||
events::send<uint32_t, events::px4::enums::failsafe_action_t, uint16_t, events::px4::enums::failsafe_cause_t>(
|
||||
events::ID("commander_failsafe_enter_hold"),
|
||||
{events::Log::Critical, events::LogInternal::Warning},
|
||||
"Failsafe activated due to {4}, triggering {2} in {3} seconds", mavlink_mode, failsafe_action,
|
||||
"{4}, triggering {2} in {3} seconds", mavlink_mode, failsafe_action,
|
||||
(uint16_t) delay_s, failsafe_cause);
|
||||
}
|
||||
|
||||
|
@ -231,7 +231,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action
|
|||
events::send<uint32_t, events::px4::enums::failsafe_action_t>(
|
||||
events::ID("commander_failsafe_enter_generic"),
|
||||
{events::Log::Critical, events::LogInternal::Warning},
|
||||
"Failsafe activated, triggering {2}", mavlink_mode, failsafe_action);
|
||||
"Failsafe, triggering {2}", mavlink_mode, failsafe_action);
|
||||
}
|
||||
|
||||
} else {
|
||||
|
@ -272,7 +272,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action
|
|||
events::send<uint32_t, events::px4::enums::failsafe_action_t, events::px4::enums::failsafe_cause_t>(
|
||||
events::ID("commander_failsafe_enter"),
|
||||
{events::Log::Critical, events::LogInternal::Warning},
|
||||
"Failsafe activated due to {3}, triggering {2}", mavlink_mode, failsafe_action, failsafe_cause);
|
||||
"{3}, triggering {2}", mavlink_mode, failsafe_action, failsafe_cause);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue