From af1541789a51b742b92f03c21d6ffbc55eb64994 Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Tue, 9 Apr 2024 01:25:46 +0200 Subject: [PATCH] SendMavCommandWithSignallingTest.cc: ignore MAV_CMD_REQUEST_MESSAGE: gimbal controller sends some message requests when receiving a hearbeat, and the cmd results collide with this test, so we filter out MAV_CMD_REQUEST_MESSAGE from gimbal controller --- src/Vehicle/SendMavCommandWithSignallingTest.cc | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/src/Vehicle/SendMavCommandWithSignallingTest.cc b/src/Vehicle/SendMavCommandWithSignallingTest.cc index ff1c26ecd5f..e1b40a4057c 100644 --- a/src/Vehicle/SendMavCommandWithSignallingTest.cc +++ b/src/Vehicle/SendMavCommandWithSignallingTest.cc @@ -38,6 +38,16 @@ void SendMavCommandWithSignallingTest::_testCaseWorker(TestCase_t& testCase) QCOMPARE(spyResult.wait(10000), true); QList arguments = spyResult.takeFirst(); + + // Gimbal controler requests MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION on vehicle connection, + // and that messes with this test, as it receives response to that command instead. So if we + // are taking the response to that MAV_CMD_REQUEST_MESSAGE, we discard it and take the next + while (arguments.at(2).toInt() == MAV_CMD_REQUEST_MESSAGE) { + qDebug() << "Received response to MAV_CMD_REQUEST_MESSAGE(512), ignoring, waiting for: " << testCase.command; + QCOMPARE(spyResult.wait(10000), true); + arguments = spyResult.takeFirst(); + } + QCOMPARE(arguments.count(), 5); QCOMPARE(arguments.at(0).toInt(), vehicle->id()); QCOMPARE(arguments.at(1).toInt(), MAV_COMP_ID_AUTOPILOT1);