From b38630b395ed4f24df697f66239dd08c203c10e7 Mon Sep 17 00:00:00 2001 From: Michael Carpenter Date: Wed, 31 Jul 2013 07:30:10 -0400 Subject: [PATCH] Added 250ms delay between sending data requests to increase probability of it working. --- src/uas/ArduPilotMegaMAV.cc | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/uas/ArduPilotMegaMAV.cc b/src/uas/ArduPilotMegaMAV.cc index c3c34c5e8..cb972df4e 100644 --- a/src/uas/ArduPilotMegaMAV.cc +++ b/src/uas/ArduPilotMegaMAV.cc @@ -53,11 +53,17 @@ ArduPilotMegaMAV::ArduPilotMegaMAV(MAVLinkProtocol* mavlink, int id) : void ArduPilotMegaMAV::sendTxRequests() { enableExtendedSystemStatusTransmission(2); + QGC::SLEEP::msleep(250); enablePositionTransmission(3); + QGC::SLEEP::msleep(250); enableExtra1Transmission(10); + QGC::SLEEP::msleep(250); enableExtra2Transmission(10); + QGC::SLEEP::msleep(250); enableExtra3Transmission(2); + QGC::SLEEP::msleep(250); enableRawSensorDataTransmission(2); + QGC::SLEEP::msleep(250); enableRCChannelDataTransmission(2); } -- 2.22.0