Skip to content

Commit

Permalink
mavsdk tests: use tester sleep function
Browse files Browse the repository at this point in the history
the original std::this_thread::sleep_for is with respect to host system
time which is different from autopilot time if speed factor != 1, if
some component runs slower than real time, or if debugging.
tester.sleep_for (which already existed) correctly sleeps w.r.t.
px4/simulation time.
  • Loading branch information
mbjd committed Jan 29, 2025
1 parent d8834d1 commit 1111095
Show file tree
Hide file tree
Showing 5 changed files with 41 additions and 43 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,7 @@ void SensorAirspeedSim::Run()

if (_airspeed_blocked_timestamp > 0) {
airspeed_blockage_scale = math::constrain(1.f - (hrt_absolute_time() - _airspeed_blocked_timestamp) /
airspeed_blockage_rampup_time, 1.f - blockage_fraction, 1.f);
airspeed_blockage_rampup_time, 1.f - blockage_fraction, 1.f);
}


Expand Down
37 changes: 18 additions & 19 deletions test/mavsdk_tests/autopilot_tester.h
Original file line number Diff line number Diff line change
Expand Up @@ -164,24 +164,6 @@ class AutopilotTester
CHECK(_param->set_param_int(param, value) == Param::Result::Success);
}

protected:
mavsdk::Param *getParams() const { return _param.get();}
mavsdk::Telemetry *getTelemetry() const { return _telemetry.get();}
mavsdk::ManualControl *getManualControl() const { return _manual_control.get();}
MavlinkPassthrough *getMavlinkPassthrough() const { return _mavlink_passthrough.get();}
std::shared_ptr<System> get_system() { return _mavsdk.systems().at(0);}
mavsdk::geometry::CoordinateTransformation get_coordinate_transformation();
bool ground_truth_horizontal_position_close_to(const Telemetry::GroundTruth &target_pos, float acceptance_radius_m);

const Telemetry::GroundTruth &getHome()
{
// Check if home was stored before it is accessed
CHECK(_home.absolute_altitude_m != NAN);
CHECK(_home.latitude_deg != NAN);
CHECK(_home.longitude_deg != NAN);
return _home;
}

template<typename Rep, typename Period>
void sleep_for(std::chrono::duration<Rep, Period> duration)
{
Expand All @@ -207,6 +189,24 @@ class AutopilotTester
}
}

protected:
mavsdk::Param *getParams() const { return _param.get();}
mavsdk::Telemetry *getTelemetry() const { return _telemetry.get();}
mavsdk::ManualControl *getManualControl() const { return _manual_control.get();}
MavlinkPassthrough *getMavlinkPassthrough() const { return _mavlink_passthrough.get();}
std::shared_ptr<System> get_system() { return _mavsdk.systems().at(0);}
mavsdk::geometry::CoordinateTransformation get_coordinate_transformation();
bool ground_truth_horizontal_position_close_to(const Telemetry::GroundTruth &target_pos, float acceptance_radius_m);

const Telemetry::GroundTruth &getHome()
{
// Check if home was stored before it is accessed
CHECK(_home.absolute_altitude_m != NAN);
CHECK(_home.latitude_deg != NAN);
CHECK(_home.longitude_deg != NAN);
return _home;
}

private:
mavsdk::Mission::MissionItem create_mission_item(
const mavsdk::geometry::CoordinateTransformation::LocalCoordinate &local_coordinate,
Expand Down Expand Up @@ -282,7 +282,6 @@ class AutopilotTester
}



mavsdk::Mavsdk _mavsdk{};
std::unique_ptr<mavsdk::Action> _action{};
std::unique_ptr<mavsdk::Failure> _failure{};
Expand Down
33 changes: 16 additions & 17 deletions test/mavsdk_tests/test_multicopter_control_allocation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,8 +62,7 @@ TEST_CASE("Control Allocation - Remove one motor", "[controlallocation]")
tester.check_tracks_mission(5.f);
tester.store_home();
tester.enable_actuator_output_status();
std::this_thread::sleep_for(std::chrono::seconds(
1)); // This is necessary for the takeoff altitude to be applied properly
tester.sleep_for(std::chrono::seconds(1)); // This is necessary for the takeoff altitude to be applied properly

// Takeoff
tester.arm();
Expand All @@ -78,7 +77,7 @@ TEST_CASE("Control Allocation - Remove one motor", "[controlallocation]")
const unsigned num_motors = 6; // TODO: get from model
tester.inject_failure(mavsdk::Failure::FailureUnit::SystemMotor, mavsdk::Failure::FailureType::Off, motor_instance,
mavsdk::Failure::Result::Success);
std::this_thread::sleep_for(std::chrono::seconds(1));
tester.sleep_for(std::chrono::seconds(1));
tester.ensure_motor_stopped(motor_instance - 1, num_motors);

tester.execute_mission();
Expand Down Expand Up @@ -115,8 +114,8 @@ TEST_CASE("Control Allocation - Remove two motors", "[controlallocation]")
tester.set_rtl_altitude(flight_altitude);
tester.check_tracks_mission(5.f);
tester.store_home();
std::this_thread::sleep_for(std::chrono::seconds(
1)); // This is necessary for the takeoff altitude to be applied properly
tester.sleep_for(std::chrono::seconds(
1)); // This is necessary for the takeoff altitude to be applied properly

tester.arm();
tester.takeoff();
Expand All @@ -131,11 +130,11 @@ TEST_CASE("Control Allocation - Remove two motors", "[controlallocation]")
tester.inject_failure(mavsdk::Failure::FailureUnit::SystemMotor, mavsdk::Failure::FailureType::Off,
first_motor_instance,
mavsdk::Failure::Result::Success);
std::this_thread::sleep_for(std::chrono::seconds(1));
tester.sleep_for(std::chrono::seconds(1));
tester.inject_failure(mavsdk::Failure::FailureUnit::SystemMotor, mavsdk::Failure::FailureType::Off,
second_motor_instance,
mavsdk::Failure::Result::Success);
std::this_thread::sleep_for(std::chrono::seconds(1));
tester.sleep_for(std::chrono::seconds(1));

tester.execute_mission();
tester.stop_checking_altitude();
Expand Down Expand Up @@ -170,8 +169,8 @@ TEST_CASE("Control Allocation - Remove and restore every motor once", "[controla
tester.set_rtl_altitude(flight_altitude);
tester.check_tracks_mission(5.f);
tester.store_home();
std::this_thread::sleep_for(std::chrono::seconds(
1)); // This is necessary for the takeoff altitude to be applied properly
tester.sleep_for(std::chrono::seconds(
1)); // This is necessary for the takeoff altitude to be applied properly

tester.arm();
tester.takeoff();
Expand All @@ -184,10 +183,10 @@ TEST_CASE("Control Allocation - Remove and restore every motor once", "[controla
for (int m = 1; m <= 6; m++) {
tester.inject_failure(mavsdk::Failure::FailureUnit::SystemMotor, mavsdk::Failure::FailureType::Off, m,
mavsdk::Failure::Result::Success);
std::this_thread::sleep_for(std::chrono::seconds(1));
tester.sleep_for(std::chrono::seconds(1));
tester.inject_failure(mavsdk::Failure::FailureUnit::SystemMotor, mavsdk::Failure::FailureType::Ok, m,
mavsdk::Failure::Result::Success);
std::this_thread::sleep_for(std::chrono::seconds(1));
tester.sleep_for(std::chrono::seconds(1));
}

tester.execute_mission();
Expand Down Expand Up @@ -216,8 +215,8 @@ TEST_CASE("Control Allocation - Return home on motor failure", "[controlallocati
tester.set_param_com_act_fail_act(3); // RTL on motor failure
tester.set_takeoff_altitude(flight_altitude);
tester.store_home();
std::this_thread::sleep_for(std::chrono::seconds(
1)); // This is necessary for the takeoff altitude to be applied properly
tester.sleep_for(std::chrono::seconds(
1)); // This is necessary for the takeoff altitude to be applied properly

// Takeoff
tester.arm();
Expand All @@ -232,7 +231,7 @@ TEST_CASE("Control Allocation - Return home on motor failure", "[controlallocati
const int motor_instance = 1;
tester.inject_failure(mavsdk::Failure::FailureUnit::SystemMotor, mavsdk::Failure::FailureType::Off, motor_instance,
mavsdk::Failure::Result::Success);
std::this_thread::sleep_for(std::chrono::seconds(1));
tester.sleep_for(std::chrono::seconds(1));

// Wait for RTL to trigger automatically
std::chrono::seconds until_disarmed_timeout = std::chrono::seconds(180);
Expand All @@ -256,8 +255,8 @@ TEST_CASE("Control Allocation - Terminate on motor failure", "[controlallocation
tester.set_param_ca_failure_mode(1); // Enable control allocation handling of failed motor
tester.set_param_com_act_fail_act(4); // Terminate on motor failure
tester.set_takeoff_altitude(flight_altitude);
std::this_thread::sleep_for(std::chrono::seconds(
1)); // This is necessary for the takeoff altitude to be applied properly
tester.sleep_for(std::chrono::seconds(
1)); // This is necessary for the takeoff altitude to be applied properly

// Takeoff
tester.arm();
Expand All @@ -269,7 +268,7 @@ TEST_CASE("Control Allocation - Terminate on motor failure", "[controlallocation
const int motor_instance = 1;
tester.inject_failure(mavsdk::Failure::FailureUnit::SystemMotor, mavsdk::Failure::FailureType::Off, motor_instance,
mavsdk::Failure::Result::Success);
std::this_thread::sleep_for(std::chrono::seconds(1));
tester.sleep_for(std::chrono::seconds(1));

// Wait for disarm with a low enough timeout such that it's necessary for the
// drone to freefall (terminate) in order to disarm quickly enough:
Expand Down
8 changes: 4 additions & 4 deletions test/mavsdk_tests/test_vtol_figure_eight.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,14 +44,14 @@ TEST_CASE("Figure eight execution clockwise", "[vtol]")
tester.store_home();
const float takeoff_altitude = 20.f;
tester.set_takeoff_altitude(takeoff_altitude);
std::this_thread::sleep_for(std::chrono::seconds(3));
tester.sleep_for(std::chrono::seconds(3));
tester.arm();
tester.takeoff();
tester.wait_until_hovering();
tester.wait_until_altitude(takeoff_altitude, std::chrono::seconds(30));
tester.transition_to_fixedwing();
tester.wait_until_fixedwing(std::chrono::seconds(5));
std::this_thread::sleep_for(std::chrono::seconds(1));
tester.sleep_for(std::chrono::seconds(1));
tester.set_figure_eight(150., 50., 0., 200., 0., 20.);
tester.execute_figure_eight();
tester.check_tracks_figure_eight(std::chrono::seconds(120), 10.);
Expand All @@ -67,14 +67,14 @@ TEST_CASE("Figure eight execution counterclockwise", "[vtol]")
tester.store_home();
const float takeoff_altitude = 20.f;
tester.set_takeoff_altitude(takeoff_altitude);
std::this_thread::sleep_for(std::chrono::seconds(3));
tester.sleep_for(std::chrono::seconds(3));
tester.arm();
tester.takeoff();
tester.wait_until_hovering();
tester.wait_until_altitude(takeoff_altitude, std::chrono::seconds(30));
tester.transition_to_fixedwing();
tester.wait_until_fixedwing(std::chrono::seconds(5));
std::this_thread::sleep_for(std::chrono::seconds(1));
tester.sleep_for(std::chrono::seconds(1));
tester.set_figure_eight(-150., 50., 30.*M_PI / 180., 200., 0., 20.);
tester.execute_figure_eight();
tester.check_tracks_figure_eight(std::chrono::seconds(120), 10.);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,12 +56,12 @@ TEST_CASE("Fly VTOL Loiter with airspeed failure", "[vtol_airspeed_fail]")


// tester.wait_until_altitude(50.f, std::chrono::seconds(30));
std::this_thread::sleep_for(std::chrono::seconds(10));
tester.sleep_for(std::chrono::seconds(10));
tester.inject_failure(mavsdk::Failure::FailureUnit::SensorAirspeed, mavsdk::Failure::FailureType::Wrong, 0,
mavsdk::Failure::Result::Success);


std::this_thread::sleep_for(std::chrono::seconds(10));
tester.sleep_for(std::chrono::seconds(10));

tester.check_airspeed_is_invalid(); // it's enough to check once after landing, as invalidation is permanent
}

0 comments on commit 1111095

Please sign in to comment.