Browse Source

Vehicle: fix unit tests after camera change

Since we no longer request cameras to have specific camera component IDs
but allow the autopilot to "be" a camera as well, we need to adjust the
unit tests to account for that.
QGC4.4
Julian Oes 10 months ago
parent
commit
a02e74a47e
No known key found for this signature in database
GPG Key ID: F0ED380FEA56DE41
  1. 3
      src/Vehicle/RequestMessageTest.cc
  2. 4
      src/Vehicle/SendMavCommandWithSignallingTest.cc
  3. 8
      src/Vehicle/Vehicle.cc
  4. 3
      src/Vehicle/Vehicle.h

3
src/Vehicle/RequestMessageTest.cc

@ -41,6 +41,9 @@ void RequestMessageTest::_testCaseWorker(TestCase_t& testCase) @@ -41,6 +41,9 @@ void RequestMessageTest::_testCaseWorker(TestCase_t& testCase)
// Gimbal controller sends message requests when receiving heartbeats, trying to find a gimbal, and it messes with this test so we disable it
vehicle->deleteGimbalController();
// Camera manager also messes with it.
vehicle->deleteCameraManager();
_mockLink->clearReceivedMavCommandCounts();
_mockLink->setRequestMessageFailureMode(testCase.failureMode);

4
src/Vehicle/SendMavCommandWithSignallingTest.cc

@ -42,7 +42,9 @@ void SendMavCommandWithSignallingTest::_testCaseWorker(TestCase_t& testCase) @@ -42,7 +42,9 @@ void SendMavCommandWithSignallingTest::_testCaseWorker(TestCase_t& testCase)
// 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) {
// 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;
QCOMPARE(spyResult.wait(10000), true);
arguments = spyResult.takeFirst();

8
src/Vehicle/Vehicle.cc

@ -535,6 +535,14 @@ void Vehicle::prepareDelete() @@ -535,6 +535,14 @@ void Vehicle::prepareDelete()
}
}
void Vehicle::deleteCameraManager()
{
if(_cameraManager) {
delete _cameraManager;
_cameraManager = nullptr;
}
}
void Vehicle::deleteGimbalController()
{
if (_gimbalController) {

3
src/Vehicle/Vehicle.h

@ -901,6 +901,9 @@ public: @@ -901,6 +901,9 @@ public:
/// Delete gimbal controller, handy for RequestMessageTest.cc, otherwise gimbal controller message requests will mess with this test
void deleteGimbalController();
/// Delete camera manager, just for testing
void deleteCameraManager();
quint64 mavlinkSentCount () const{ return _mavlinkSentCount; } /// Calculated total number of messages sent to us
quint64 mavlinkReceivedCount () const{ return _mavlinkReceivedCount; } /// Total number of sucessful messages received
quint64 mavlinkLossCount () const{ return _mavlinkLossCount; } /// Total number of lost messages

Loading…
Cancel
Save