diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 2f2f7a80c2e1f8f0d923b3ffc9d0383baabd8cbb..e8fd34d1724d21407c0f12be9f5340924bb89553 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 */); }