|
|
|
@ -197,6 +197,8 @@ void print_reject_arm(const char *msg);
@@ -197,6 +197,8 @@ void print_reject_arm(const char *msg);
|
|
|
|
|
|
|
|
|
|
void print_status(); |
|
|
|
|
|
|
|
|
|
bool shutdown_if_allowed(); |
|
|
|
|
|
|
|
|
|
transition_result_t arm_disarm(bool arm, orb_advert_t *mavlink_log_pub, const char *armedBy); |
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
@ -521,6 +523,13 @@ void print_status()
@@ -521,6 +523,13 @@ void print_status()
|
|
|
|
|
PX4_INFO("arming: %s", arming_state_names[status.arming_state]); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
bool shutdown_if_allowed() |
|
|
|
|
{ |
|
|
|
|
return TRANSITION_DENIED != arming_state_transition(&status, safety, vehicle_status_s::ARMING_STATE_REBOOT, |
|
|
|
|
&armed, false /* fRunPreArmChecks */, &mavlink_log_pub, &status_flags, arm_requirements, |
|
|
|
|
hrt_elapsed_time(&commander_boot_timestamp)); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
transition_result_t arm_disarm(bool arm, orb_advert_t *mavlink_log_pub_local, const char *armedBy) |
|
|
|
|
{ |
|
|
|
|
transition_result_t arming_res = TRANSITION_NOT_CHANGED; |
|
|
|
@ -1511,7 +1520,7 @@ Commander::run()
@@ -1511,7 +1520,7 @@ Commander::run()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/* if the USB hardware connection went away, reboot */ |
|
|
|
|
if (status_flags.usb_connected && !system_power.usb_connected) { |
|
|
|
|
if (status_flags.usb_connected && !system_power.usb_connected && shutdown_if_allowed()) { |
|
|
|
|
/*
|
|
|
|
|
* apparently the USB cable went away but we are still powered, |
|
|
|
|
* so lets reset to a classic non-usb state. |
|
|
|
|