@ -42,7 +42,9 @@ void SendMavCommandWithSignallingTest::_testCaseWorker(TestCase_t& testCase)
// Gimbal controler requests MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION on vehicle connection,
// 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
// 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
// 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 ) {
// Also, the camera manager requests MAVLINK_MSG_ID_CAMERA_INFORMATION on vehicle connection,
// so we need to ignore that as well.
while ( arguments . at ( 2 ) . toInt ( ) = = MAV_CMD_REQUEST_MESSAGE | | arguments . at ( 2 ) . toInt ( ) = = MAV_CMD_REQUEST_CAMERA_INFORMATION ) {
qDebug ( ) < < " Received response to MAV_CMD_REQUEST_MESSAGE(512), ignoring, waiting for: " < < testCase . command ;
qDebug ( ) < < " Received response to MAV_CMD_REQUEST_MESSAGE(512), ignoring, waiting for: " < < testCase . command ;
QCOMPARE ( spyResult . wait ( 10000 ) , true ) ;
QCOMPARE ( spyResult . wait ( 10000 ) , true ) ;
arguments = spyResult . takeFirst ( ) ;
arguments = spyResult . takeFirst ( ) ;