Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Commander: complete thread cycle before emergency shutdown #9563

Merged
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
30 changes: 19 additions & 11 deletions src/modules/commander/commander.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1308,6 +1308,7 @@ Commander::run()
bool low_battery_voltage_actions_done = false;
bool critical_battery_voltage_actions_done = false;
bool emergency_battery_voltage_actions_done = false;
bool dangerous_battery_level_requests_poweroff = false;

bool status_changed = true;
bool param_init_forced = true;
Expand Down Expand Up @@ -1967,17 +1968,9 @@ Commander::run()
emergency_battery_voltage_actions_done = true;

if (!armed.armed) {
mavlink_log_critical(&mavlink_log_pub, "DANGEROUSLY LOW BATTERY, SHUT SYSTEM DOWN");
usleep(200000);
int ret_val = px4_shutdown_request(false, false);

if (ret_val) {
mavlink_log_critical(&mavlink_log_pub, "SYSTEM DOES NOT SUPPORT SHUTDOWN");

} else {
while (1) { usleep(1); }
}

// Request shutdown at the end of the cycle. This allows
// the vehicle state to be published after emergency landing
dangerous_battery_level_requests_poweroff = true;
} else {
if (low_bat_action == 2 || low_bat_action == 3) {
if (TRANSITION_CHANGED == main_state_transition(status, commander_state_s::MAIN_STATE_AUTO_LAND, status_flags, &internal_state)) {
Expand Down Expand Up @@ -2747,6 +2740,21 @@ Commander::run()

arm_auth_update(now, params_updated || param_init_forced);

// Handle shutdown request from emergency battery action
if(!armed.armed && dangerous_battery_level_requests_poweroff){
mavlink_log_critical(&mavlink_log_pub, "DANGEROUSLY LOW BATTERY, SHUT SYSTEM DOWN");
usleep(200000);
int ret_val = px4_shutdown_request(false, false);

if (ret_val) {
mavlink_log_critical(&mavlink_log_pub, "SYSTEM DOES NOT SUPPORT SHUTDOWN");
dangerous_battery_level_requests_poweroff = false;

} else {
while (1) { usleep(1); }
}
}

usleep(COMMANDER_MONITORING_INTERVAL);
}

Expand Down