From 0b156cdd0f285ee96fd63ef80201f0b02cfde27a Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Tue, 25 Apr 2017 10:53:29 -0700 Subject: [PATCH] Handle autopilot home position updates --- src/MissionManager/MissionManager.cc | 24 ++++++++++++++++++------ 1 file changed, 18 insertions(+), 6 deletions(-) diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index db35e2fca..8a88bada0 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -409,11 +409,6 @@ void MissionManager::_requestNextMissionItem(void) void MissionManager::_handleMissionItem(const mavlink_message_t& message, bool missionItemInt) { - - if (!_checkForExpectedAck(AckMissionItem)) { - return; - } - MAV_CMD command; MAV_FRAME frame; double param1; @@ -468,7 +463,24 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message, bool m frame = MAV_FRAME_GLOBAL_RELATIVE_ALT; } - qCDebug(MissionManagerLog) << "_handleMissionItem seq:command:current" << seq << command << isCurrentItem; + + bool ardupilotHomePositionUpdate = false; + if (!_checkForExpectedAck(AckMissionItem)) { + if (_vehicle->apmFirmware() && seq == 0) { + ardupilotHomePositionUpdate = true; + } else { + qCDebug(MissionManagerLog) << "_handleMissionItem dropping spurious item seq:command:current" << seq << command << isCurrentItem; + return; + } + } + + qCDebug(MissionManagerLog) << "_handleMissionItem seq:command:current:ardupilotHomePositionUpdate" << seq << command << isCurrentItem << ardupilotHomePositionUpdate; + + if (ardupilotHomePositionUpdate) { + QGeoCoordinate newHomePosition(param5, param6, param7); + _vehicle->_setHomePosition(newHomePosition); + return; + } if (_itemIndicesToRead.contains(seq)) { _itemIndicesToRead.removeOne(seq); -- 2.22.0