From 55d2bdc4388f1eda6fb97e4aa42e22a12b31894f Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 29 Jul 2020 14:04:55 +0200 Subject: [PATCH] mavsdk_tests: adapt to changed inject API We now need to say which instance, for now it's all instances. --- test/mavsdk_tests/autopilot_tester.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/test/mavsdk_tests/autopilot_tester.cpp b/test/mavsdk_tests/autopilot_tester.cpp index f65cc8efc0..0dad12ce02 100644 --- a/test/mavsdk_tests/autopilot_tester.cpp +++ b/test/mavsdk_tests/autopilot_tester.cpp @@ -238,7 +238,7 @@ void AutopilotTester::execute_mission_and_lose_gps() std::cout << "Progress: " << progress.current << "/" << progress.total; if (progress.current == 1) { - CHECK(_failure->inject(Failure::FailureUnit::SensorGps, Failure::FailureType::Off) + CHECK(_failure->inject(Failure::FailureUnit::SensorGps, Failure::FailureType::Off, 0) == Failure::Result::Success); } }); @@ -267,7 +267,7 @@ void AutopilotTester::execute_mission_and_lose_mag() std::cout << "Progress: " << progress.current << "/" << progress.total; if (progress.current == 1) { - CHECK(_failure->inject(Failure::FailureUnit::SensorMag, Failure::FailureType::Off) + CHECK(_failure->inject(Failure::FailureUnit::SensorMag, Failure::FailureType::Off, 0) == Failure::Result::Success); } }); @@ -297,7 +297,7 @@ void AutopilotTester::execute_mission_and_lose_baro() std::cout << "Progress: " << progress.current << "/" << progress.total; if (progress.current == 1) { - CHECK(_failure->inject(Failure::FailureUnit::SensorBaro, Failure::FailureType::Off) + CHECK(_failure->inject(Failure::FailureUnit::SensorBaro, Failure::FailureType::Off, 0) == Failure::Result::Success); } }); @@ -326,7 +326,7 @@ void AutopilotTester::execute_mission_and_get_baro_stuck() std::cout << "Progress: " << progress.current << "/" << progress.total; if (progress.current == 1) { - CHECK(_failure->inject(Failure::FailureUnit::SensorBaro, Failure::FailureType::Stuck) + CHECK(_failure->inject(Failure::FailureUnit::SensorBaro, Failure::FailureType::Stuck, 0) == Failure::Result::Success); } }); @@ -355,7 +355,7 @@ void AutopilotTester::execute_mission_and_get_mag_stuck() std::cout << "Progress: " << progress.current << "/" << progress.total; if (progress.current == 1) { - CHECK(_failure->inject(Failure::FailureUnit::SensorMag, Failure::FailureType::Stuck) + CHECK(_failure->inject(Failure::FailureUnit::SensorMag, Failure::FailureType::Stuck, 0) == Failure::Result::Success); } });