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

mavlink receiver fix PREFLIGHT_REBOOT_SHUTDOWN #8008

Merged
merged 1 commit into from
Sep 25, 2017
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
36 changes: 2 additions & 34 deletions src/modules/mavlink/mavlink_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -405,8 +405,6 @@ MavlinkReceiver::evaluate_target_ok(int command, int target_system, int target_c
switch (command) {

case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:

/* fallthrough */
case MAV_CMD_REQUEST_PROTOCOL_VERSION:
/* broadcast and ignore component */
target_ok = (target_system == 0) || (target_system == mavlink_system.sysid);
Expand Down Expand Up @@ -461,22 +459,7 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
return;
}

//check for MAVLINK terminate command
if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN) {

int cmd_id = int(cmd_mavlink.param1);

if (cmd_id == 10) {
/* This is the link shutdown command, terminate mavlink */
PX4_WARN("terminated by remote");
fflush(stdout);
usleep(50000);

/* terminate other threads and this thread */
_mavlink->_task_should_exit = true;
}

} else if (cmd_mavlink.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) {
if (cmd_mavlink.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) {
/* send autopilot version message */
_mavlink->send_autopilot_capabilites();

Expand Down Expand Up @@ -567,22 +550,7 @@ MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg)
return;
}

//check for MAVLINK terminate command
if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN) {

int cmd_id = int(cmd_mavlink.param1);

if (cmd_id == 10) {
/* This is the link shutdown command, terminate mavlink */
PX4_WARN("terminated by remote");
fflush(stdout);
usleep(50000);

/* terminate other threads and this thread */
_mavlink->_task_should_exit = true;
}

} else if (cmd_mavlink.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) {
if (cmd_mavlink.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) {
/* send autopilot version message */
_mavlink->send_autopilot_capabilites();

Expand Down