Skip to content

Commit

Permalink
Fix issue #5501. Link termination now requires param 2 = 10
Browse files Browse the repository at this point in the history
  • Loading branch information
LorenzMeier committed Sep 16, 2016
1 parent 4453e42 commit d98bbd9
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion src/modules/mavlink/mavlink_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -350,7 +350,7 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)

if (target_ok) {
//check for MAVLINK terminate command
if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 3) {
if (cmd_mavlink.command == MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN && ((int)cmd_mavlink.param1) == 10) {
/* This is the link shutdown command, terminate mavlink */
warnx("terminated by remote");
fflush(stdout);
Expand Down

0 comments on commit d98bbd9

Please sign in to comment.