From 4e3e6c35033f538e8a45e6d97c9ecf9bc15917d0 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Wed, 3 May 2017 10:07:51 -0700 Subject: [PATCH] Mavlink update --- libs/mavlink/include/mavlink/v2.0 | 2 +- src/AutoPilotPlugins/APM/APMSensorsComponentController.cc | 7 ++++--- src/comm/MockLink.cc | 3 ++- 3 files changed, 7 insertions(+), 5 deletions(-) diff --git a/libs/mavlink/include/mavlink/v2.0 b/libs/mavlink/include/mavlink/v2.0 index fb411385d..9bc6f7d5e 160000 --- a/libs/mavlink/include/mavlink/v2.0 +++ b/libs/mavlink/include/mavlink/v2.0 @@ -1 +1 @@ -Subproject commit fb411385d5f00300ab5d04c5adb08e7e17670d58 +Subproject commit 9bc6f7d5ecb8c081b554cbd934a20290a5efa529 diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc index 9c0837d26..e3e6ca5e3 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc @@ -607,7 +607,8 @@ void APMSensorsComponentController::nextClicked(void) _vehicle->priorityLink()->mavlinkChannel(), &msg, 0, // command - 1); // result + 1, // result + 0); // progress _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); @@ -677,7 +678,7 @@ void APMSensorsComponentController::_handleMagCalProgress(mavlink_message_t& mes mavlink_msg_mag_cal_progress_decode(&message, &magCalProgress); qCDebug(APMSensorsComponentControllerVerboseLog) << "_handleMagCalProgress id:mask:pct" - << magCalProgress.compass_id << magCalProgress.cal_mask << magCalProgress.completion_pct; + << magCalProgress.compass_id << magCalProgress.cal_mask << magCalProgress.completion_pct; // How many compasses are we calibrating? int compassCalCount = 0; @@ -705,7 +706,7 @@ void APMSensorsComponentController::_handleMagCalReport(mavlink_message_t& messa mavlink_msg_mag_cal_report_decode(&message, &magCalReport); qCDebug(APMSensorsComponentControllerVerboseLog) << "_handleMagCalReport id:mask:status:fitness" - << magCalReport.compass_id << magCalReport.cal_mask << magCalReport.cal_status << magCalReport.fitness; + << magCalReport.compass_id << magCalReport.cal_mask << magCalReport.cal_status << magCalReport.fitness; bool additionalCompassCompleted = false; if (magCalReport.compass_id < 3 && !_rgCompassCalComplete[magCalReport.compass_id]) { diff --git a/src/comm/MockLink.cc b/src/comm/MockLink.cc index b3cd24ff6..e5d4226dc 100644 --- a/src/comm/MockLink.cc +++ b/src/comm/MockLink.cc @@ -847,7 +847,8 @@ void MockLink::_handleCommandLong(const mavlink_message_t& msg) mavlinkChannel(), &commandAck, request.command, - commandResult); + commandResult, + 0); respondWithMavlinkMessage(commandAck); } -- 2.22.0