mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-22 01:12:31 +00:00
vehicle_status: replace ARMING_STATE_REBOOT with ARMING_STATE_SHUTDOWN
Signed-off-by: Andrei Korigodski <akorigod@gmail.com>
This commit is contained in:
committed by
Julian Oes
parent
4a330c6e0a
commit
5133453822
@@ -66,13 +66,13 @@ static constexpr const char reason_no_datalink[] = "no datalink";
|
||||
// code for those checks.
|
||||
static constexpr const bool arming_transitions[vehicle_status_s::ARMING_STATE_MAX][vehicle_status_s::ARMING_STATE_MAX]
|
||||
= {
|
||||
// INIT, STANDBY, ARMED, STANDBY_ERROR, REBOOT, IN_AIR_RESTORE
|
||||
{ /* vehicle_status_s::ARMING_STATE_INIT */ true, true, false, true, false, false },
|
||||
{ /* vehicle_status_s::ARMING_STATE_STANDBY */ true, true, true, false, false, false },
|
||||
{ /* vehicle_status_s::ARMING_STATE_ARMED */ false, true, true, false, false, true },
|
||||
{ /* vehicle_status_s::ARMING_STATE_STANDBY_ERROR */ true, true, true, true, false, false },
|
||||
{ /* vehicle_status_s::ARMING_STATE_REBOOT */ true, true, false, true, true, true },
|
||||
{ /* vehicle_status_s::ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false }, // NYI
|
||||
// INIT, STANDBY, ARMED, STANDBY_ERROR, SHUTDOWN, IN_AIR_RESTORE
|
||||
{ /* vehicle_status_s::ARMING_STATE_INIT */ true, true, false, true, false, false },
|
||||
{ /* vehicle_status_s::ARMING_STATE_STANDBY */ true, true, true, false, false, false },
|
||||
{ /* vehicle_status_s::ARMING_STATE_ARMED */ false, true, true, false, false, true },
|
||||
{ /* vehicle_status_s::ARMING_STATE_STANDBY_ERROR */ true, true, true, true, false, false },
|
||||
{ /* vehicle_status_s::ARMING_STATE_SHUTDOWN */ true, true, false, true, true, true },
|
||||
{ /* vehicle_status_s::ARMING_STATE_IN_AIR_RESTORE */ false, false, false, false, false, false }, // NYI
|
||||
};
|
||||
|
||||
// You can index into the array with an arming_state_t in order to get its textual representation
|
||||
@@ -81,7 +81,7 @@ const char *const arming_state_names[vehicle_status_s::ARMING_STATE_MAX] = {
|
||||
"STANDBY",
|
||||
"ARMED",
|
||||
"STANDBY_ERROR",
|
||||
"REBOOT",
|
||||
"SHUTDOWN",
|
||||
"IN_AIR_RESTORE",
|
||||
};
|
||||
|
||||
|
||||
Reference in New Issue
Block a user