From f61ce67f87c163534974f5db5ef092a6d6b210a4 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Thu, 26 Sep 2019 11:52:28 -0700 Subject: [PATCH] Stream HOME_POSITION on ArduPilot --- src/FirmwarePlugin/APM/APMFirmwarePlugin.cc | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 2f2f7a80c..e8fd34d17 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -656,6 +656,10 @@ void APMFirmwarePlugin::initializeStreamRates(Vehicle* vehicle) vehicle->requestDataStream(streamInfo.mavStream, static_cast(streamInfo.streamRate)); } } + + // Streaming of home position is required for various features in QGC to work correctly. Otherwise relative altitudes + // cannot be calculated correctly. + vehicle->sendMavCommand(MAV_COMP_ID_AUTOPILOT1, MAV_CMD_SET_MESSAGE_INTERVAL, true /* showError */, MAVLINK_MSG_ID_HOME_POSITION, 1000000 /* 1 second interval in usec */); } -- 2.22.0