Browse Source

mavsdk_tests: adapt to changed inject API

We now need to say which instance, for now it's all instances.
sbg
Julian Oes 5 years ago committed by Daniel Agar
parent
commit
55d2bdc438
  1. 10
      test/mavsdk_tests/autopilot_tester.cpp

10
test/mavsdk_tests/autopilot_tester.cpp

@ -238,7 +238,7 @@ void AutopilotTester::execute_mission_and_lose_gps() @@ -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() @@ -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() @@ -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() @@ -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() @@ -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);
}
});

Loading…
Cancel
Save