mirror of https://github.com/ArduPilot/ardupilot
ArduSub: get MAV_STATE_BOOT on reboot
This commit is contained in:
parent
11ee66fc22
commit
d6ab080060
|
@ -63,6 +63,9 @@ MAV_STATE GCS_MAVLINK_Sub::vehicle_system_status() const
|
|||
if (sub.motors.armed()) {
|
||||
return MAV_STATE_ACTIVE;
|
||||
}
|
||||
if (!sub.ap.initialised) {
|
||||
return MAV_STATE_BOOT;
|
||||
}
|
||||
|
||||
return MAV_STATE_STANDBY;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue