diff --git a/examples/autopilot_server/autopilot_server.cpp b/examples/autopilot_server/autopilot_server.cpp index 77b31bfab6..8342503582 100644 --- a/examples/autopilot_server/autopilot_server.cpp +++ b/examples/autopilot_server/autopilot_server.cpp @@ -59,8 +59,7 @@ int main(int argc, char** argv) // thread as a ground station. std::thread autopilotThread([]() { mavsdk::Mavsdk mavsdkTester; - mavsdk::Mavsdk::Configuration configuration( - mavsdk::Mavsdk::Configuration::UsageType::Autopilot); + mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::ComponentType::Autopilot); mavsdkTester.set_configuration(configuration); auto result = mavsdkTester.add_any_connection("udp://127.0.0.1:14551"); @@ -69,7 +68,7 @@ int main(int argc, char** argv) } auto server_component = - mavsdkTester.server_component_by_type(Mavsdk::ServerComponentType::Autopilot); + mavsdkTester.server_component_by_type(Mavsdk::ComponentType::Autopilot); // Create server plugins auto paramServer = mavsdk::ParamServer{server_component}; @@ -148,8 +147,7 @@ int main(int argc, char** argv) // Now this is the main thread, we run client plugins to act as the GCS // to communicate with the autopilot server plugins. mavsdk::Mavsdk mavsdk; - mavsdk::Mavsdk::Configuration configuration( - mavsdk::Mavsdk::Configuration::UsageType::GroundStation); + mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::ComponentType::GroundStation); mavsdk.set_configuration(configuration); auto result = mavsdk.add_any_connection("udp://:14551"); diff --git a/examples/camera_server/camera_client.cpp b/examples/camera_server/camera_client.cpp index 58c93583d0..526c983962 100644 --- a/examples/camera_server/camera_client.cpp +++ b/examples/camera_server/camera_client.cpp @@ -10,8 +10,7 @@ int main(int argc, const char* argv[]) // we run client plugins to act as the GCS // to communicate with the camera server plugins. mavsdk::Mavsdk mavsdk; - mavsdk::Mavsdk::Configuration configuration( - mavsdk::Mavsdk::Configuration::UsageType::GroundStation); + mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::ComponentType::GroundStation); mavsdk.set_configuration(configuration); auto result = mavsdk.add_any_connection("udp://:14030"); diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index 573ee544b1..e45821c458 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -6,7 +6,7 @@ int main(int argc, char** argv) { mavsdk::Mavsdk mavsdk; - mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::Configuration::UsageType::Camera); + mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::ComponentType::Camera); mavsdk.set_configuration(configuration); // 14030 is the default camera port for PX4 SITL @@ -18,7 +18,7 @@ int main(int argc, char** argv) std::cout << "Created camera server connection" << std::endl; auto camera_server = mavsdk::CameraServer{ - mavsdk.server_component_by_type(mavsdk::Mavsdk::ServerComponentType::Camera)}; + mavsdk.server_component_by_type(mavsdk::Mavsdk::ComponentType::Camera)}; // First add all subscriptions. This defines the camera capabilities. diff --git a/examples/ftp_server/ftp_server.cpp b/examples/ftp_server/ftp_server.cpp index be2afabf05..a652874ba4 100644 --- a/examples/ftp_server/ftp_server.cpp +++ b/examples/ftp_server/ftp_server.cpp @@ -29,7 +29,7 @@ int main(int argc, char** argv) } Mavsdk mavsdk; - Mavsdk::Configuration configuration(Mavsdk::Configuration::UsageType::CompanionComputer); + Mavsdk::Configuration configuration(Mavsdk::ComponentType::CompanionComputer); mavsdk.set_configuration(configuration); ConnectionResult connection_result = mavsdk.setup_udp_remote(argv[1], std::stoi(argv[2])); if (connection_result != ConnectionResult::Success) { @@ -38,7 +38,7 @@ int main(int argc, char** argv) } auto component = - mavsdk.server_component_by_type(mavsdk::Mavsdk::ServerComponentType::CompanionComputer); + mavsdk.server_component_by_type(mavsdk::Mavsdk::ComponentType::CompanionComputer); auto ftp_server = FtpServer{component}; ftp_server.set_root_dir(argv[3]); diff --git a/examples/gimbal_device_tester/gimbal_device_tester.cpp b/examples/gimbal_device_tester/gimbal_device_tester.cpp index 259946b0bd..48f1b8e578 100644 --- a/examples/gimbal_device_tester/gimbal_device_tester.cpp +++ b/examples/gimbal_device_tester/gimbal_device_tester.cpp @@ -816,7 +816,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk::Configuration config(Mavsdk::Configuration::UsageType::Autopilot); + Mavsdk::Configuration config(Mavsdk::ComponentType::Autopilot); config.set_system_id(own_sysid); mavsdk.set_configuration(config); diff --git a/src/integration_tests/camera_take_photo.cpp b/src/integration_tests/camera_take_photo.cpp index c0563d54c2..88a90deea1 100644 --- a/src/integration_tests/camera_take_photo.cpp +++ b/src/integration_tests/camera_take_photo.cpp @@ -12,17 +12,16 @@ TEST(CameraTest, TakePhotoSingle) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); Mavsdk mavsdk_camera; - mavsdk_camera.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Camera}); + mavsdk_camera.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Camera}); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ(mavsdk_camera.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); auto camera_server = - CameraServer{mavsdk_camera.server_component_by_type(Mavsdk::ServerComponentType::Camera)}; + CameraServer{mavsdk_camera.server_component_by_type(Mavsdk::ComponentType::Camera)}; camera_server.subscribe_take_photo([&camera_server](int32_t index) { LogInfo() << "Let's take photo " << index; diff --git a/src/integration_tests/connection.cpp b/src/integration_tests/connection.cpp index 870ba4c29b..aaf9bd5c61 100644 --- a/src/integration_tests/connection.cpp +++ b/src/integration_tests/connection.cpp @@ -29,7 +29,7 @@ connection_test(const std::string& client_system_address, const std::string& ser { // Start instance as a UDP server pretending to be an autopilot Mavsdk mavsdk_server; - Mavsdk::Configuration config_autopilot(Mavsdk::Configuration::UsageType::Autopilot); + Mavsdk::Configuration config_autopilot(Mavsdk::ComponentType::Autopilot); mavsdk_server.set_configuration(config_autopilot); ConnectionResult ret_server = mavsdk_server.add_any_connection(server_system_address); ASSERT_EQ(ret_server, ConnectionResult::Success); diff --git a/src/integration_tests/statustext.cpp b/src/integration_tests/statustext.cpp index cfe06ba213..8fd3a87921 100644 --- a/src/integration_tests/statustext.cpp +++ b/src/integration_tests/statustext.cpp @@ -16,12 +16,12 @@ static const auto type = ServerUtility::StatusTextType::Info; TEST(StatusTextTest, TestServer) { Mavsdk mavsdk_gcs; - Mavsdk::Configuration config_gcs(Mavsdk::Configuration::UsageType::GroundStation); + Mavsdk::Configuration config_gcs(Mavsdk::ComponentType::GroundStation); mavsdk_gcs.set_configuration(config_gcs); ASSERT_EQ(mavsdk_gcs.add_udp_connection(24550), ConnectionResult::Success); Mavsdk mavsdk_onboard; - Mavsdk::Configuration config_onboard(Mavsdk::Configuration::UsageType::CompanionComputer); + Mavsdk::Configuration config_onboard(Mavsdk::ComponentType::CompanionComputer); mavsdk_onboard.set_configuration(config_onboard); ASSERT_EQ(mavsdk_onboard.setup_udp_remote("127.0.0.1", 24550), ConnectionResult::Success); diff --git a/src/mavsdk/core/include/mavsdk/mavsdk.h b/src/mavsdk/core/include/mavsdk/mavsdk.h index 18603b3db8..9b379d99a2 100644 --- a/src/mavsdk/core/include/mavsdk/mavsdk.h +++ b/src/mavsdk/core/include/mavsdk/mavsdk.h @@ -223,23 +223,23 @@ class Mavsdk { */ std::optional> first_autopilot(double timeout_s) const; + /** + * @brief ComponentType of configurations, used for automatic ID setting + */ + enum class ComponentType { + Autopilot, /**< @brief SDK is used as an autopilot. */ + GroundStation, /**< @brief SDK is used as a ground station. */ + CompanionComputer, /**< @brief SDK is used as a companion computer on board the MAV. */ + Camera, /** < @brief SDK is used as a camera. */ + Custom /**< @brief the SDK is used in a custom configuration, no automatic ID will be + provided */ + }; + /** * @brief Possible configurations. */ class Configuration { public: - /** - * @brief UsageTypes of configurations, used for automatic ID setting - */ - enum class UsageType { - Autopilot, /**< @brief SDK is used as an autopilot. */ - GroundStation, /**< @brief SDK is used as a ground station. */ - CompanionComputer, /**< @brief SDK is used as a companion computer on board the MAV. */ - Camera, /** < @brief SDK is used as a camera. */ - Custom /**< @brief the SDK is used in a custom configuration, no automatic ID will be - provided */ - }; - /** * @brief Create new Configuration via manually configured * system and component ID. @@ -250,11 +250,11 @@ class Mavsdk { explicit Configuration( uint8_t system_id, uint8_t component_id, bool always_send_heartbeats); /** - * @brief Create new Configuration using a usage type. + * @brief Create new Configuration using a component type. * In this mode, the system and component ID will be automatically chosen. - * @param usage_type the usage type, used for automatically choosing ids. + * @param component_type the component type, used for automatically choosing ids. */ - explicit Configuration(UsageType usage_type); + explicit Configuration(ComponentType component_type); Configuration() = delete; ~Configuration() = default; @@ -292,21 +292,21 @@ class Mavsdk { */ void set_always_send_heartbeats(bool always_send_heartbeats); - /** @brief Usage type of this configuration, used for automatic ID set */ - UsageType get_usage_type() const; + /** @brief Component type of this configuration, used for automatic ID set */ + ComponentType get_component_type() const; /** - * @brief Set the usage type of this configuration. + * @brief Set the component type of this configuration. */ - void set_usage_type(UsageType usage_type); + void set_component_type(ComponentType component_type); private: uint8_t _system_id; uint8_t _component_id; bool _always_send_heartbeats; - UsageType _usage_type; + ComponentType _component_type; - static Mavsdk::Configuration::UsageType usage_type_for_component(uint8_t component_id); + static Mavsdk::ComponentType component_type_for_component_id(uint8_t component_id); }; /** @@ -367,30 +367,19 @@ class Mavsdk { */ void unsubscribe_on_new_system(NewSystemHandle handle); - /** - * @brief High level type of a server component. - */ - enum class ServerComponentType { - Autopilot, /**< @brief The component identifies as an autopilot. */ - GroundStation, /**< @brief The component identifies as a ground station. */ - CompanionComputer, /**< @brief The component identifies as a companion computer on board the - system. */ - Camera, /** < @brief The component identifies as a camera. */ - }; - /** * @brief Get server component by a high level type. * * This represents a server component of the MAVSDK instance. * - * @param server_component_type The high level type of the component. + * @param component_type The high level type of the component. * @param instance The instance of the component if there are multiple, starting at 0. * * @return A valid shared pointer to a server component if it was successful, an empty pointer * otherwise. */ std::shared_ptr - server_component_by_type(ServerComponentType server_component_type, unsigned instance = 0); + server_component_by_type(ComponentType component_type, unsigned instance = 0); /** * @brief Get server component by the low MAVLink component ID. diff --git a/src/mavsdk/core/lazy_server_plugin.h b/src/mavsdk/core/lazy_server_plugin.h index fb8b7aeabb..4dd847e7ea 100644 --- a/src/mavsdk/core/lazy_server_plugin.h +++ b/src/mavsdk/core/lazy_server_plugin.h @@ -16,7 +16,7 @@ template class LazyServerPlugin { std::lock_guard lock(_mutex); if (_server_plugin == nullptr) { _server_plugin = std::make_unique( - _mavsdk.server_component_by_type(Mavsdk::ServerComponentType::CompanionComputer)); + _mavsdk.server_component_by_type(Mavsdk::ComponentType::CompanionComputer)); } return _server_plugin.get(); } diff --git a/src/mavsdk/core/mavsdk.cpp b/src/mavsdk/core/mavsdk.cpp index fbceb99d72..3f8bd6fdc9 100644 --- a/src/mavsdk/core/mavsdk.cpp +++ b/src/mavsdk/core/mavsdk.cpp @@ -96,7 +96,7 @@ void Mavsdk::unsubscribe_on_new_system(NewSystemHandle handle) } std::shared_ptr -Mavsdk::server_component_by_type(ServerComponentType server_component_type, unsigned instance) +Mavsdk::server_component_by_type(ComponentType server_component_type, unsigned instance) { return _impl->server_component_by_type(server_component_type, instance); } @@ -111,50 +111,49 @@ Mavsdk::Configuration::Configuration( _system_id(system_id), _component_id(component_id), _always_send_heartbeats(always_send_heartbeats), - _usage_type(usage_type_for_component(component_id)) + _component_type(component_type_for_component_id(component_id)) {} -Mavsdk::Configuration::UsageType -Mavsdk::Configuration::usage_type_for_component(uint8_t component_id) +Mavsdk::ComponentType Mavsdk::Configuration::component_type_for_component_id(uint8_t component_id) { switch (component_id) { case MavsdkImpl::DEFAULT_COMPONENT_ID_GCS: - return UsageType::GroundStation; + return ComponentType::GroundStation; case MavsdkImpl::DEFAULT_COMPONENT_ID_CC: - return UsageType::CompanionComputer; + return ComponentType::CompanionComputer; case MavsdkImpl::DEFAULT_COMPONENT_ID_AUTOPILOT: - return UsageType::Autopilot; + return ComponentType::Autopilot; case MavsdkImpl::DEFAULT_COMPONENT_ID_CAMERA: - return UsageType::Camera; + return ComponentType::Camera; default: - return UsageType::Custom; + return ComponentType::Custom; } } -Mavsdk::Configuration::Configuration(UsageType usage_type) : +Mavsdk::Configuration::Configuration(ComponentType component_type) : _system_id(MavsdkImpl::DEFAULT_SYSTEM_ID_GCS), _component_id(MavsdkImpl::DEFAULT_COMPONENT_ID_GCS), _always_send_heartbeats(false), - _usage_type(usage_type) + _component_type(component_type) { - switch (usage_type) { - case Mavsdk::Configuration::UsageType::GroundStation: + switch (component_type) { + case Mavsdk::ComponentType::GroundStation: _system_id = MavsdkImpl::DEFAULT_SYSTEM_ID_GCS; _component_id = MavsdkImpl::DEFAULT_COMPONENT_ID_GCS; _always_send_heartbeats = false; break; - case Mavsdk::Configuration::UsageType::CompanionComputer: + case Mavsdk::ComponentType::CompanionComputer: // TODO implement auto-detection of system ID - maybe from heartbeats? _system_id = MavsdkImpl::DEFAULT_SYSTEM_ID_CC; _component_id = MavsdkImpl::DEFAULT_COMPONENT_ID_CC; _always_send_heartbeats = true; break; - case Mavsdk::Configuration::UsageType::Autopilot: + case Mavsdk::ComponentType::Autopilot: _system_id = MavsdkImpl::DEFAULT_SYSTEM_ID_AUTOPILOT; _component_id = MavsdkImpl::DEFAULT_COMPONENT_ID_AUTOPILOT; _always_send_heartbeats = true; break; - case Mavsdk::Configuration::UsageType::Camera: + case Mavsdk::ComponentType::Camera: _system_id = MavsdkImpl::DEFAULT_SYSTEM_ID_CAMERA; _component_id = MavsdkImpl::DEFAULT_COMPONENT_ID_CAMERA; _always_send_heartbeats = true; @@ -194,14 +193,14 @@ void Mavsdk::Configuration::set_always_send_heartbeats(bool always_send_heartbea _always_send_heartbeats = always_send_heartbeats; } -Mavsdk::Configuration::UsageType Mavsdk::Configuration::get_usage_type() const +Mavsdk::ComponentType Mavsdk::Configuration::get_component_type() const { - return _usage_type; + return _component_type; } -void Mavsdk::Configuration::set_usage_type(Mavsdk::Configuration::UsageType usage_type) +void Mavsdk::Configuration::set_component_type(Mavsdk::ComponentType component_type) { - _usage_type = usage_type; + _component_type = component_type; } void Mavsdk::intercept_incoming_messages_async(std::function callback) diff --git a/src/mavsdk/core/mavsdk_impl.cpp b/src/mavsdk/core/mavsdk_impl.cpp index 873a1b384d..a79d26fb47 100644 --- a/src/mavsdk/core/mavsdk_impl.cpp +++ b/src/mavsdk/core/mavsdk_impl.cpp @@ -164,11 +164,11 @@ std::optional> MavsdkImpl::first_autopilot(double timeou } } -std::shared_ptr MavsdkImpl::server_component_by_type( - Mavsdk::ServerComponentType server_component_type, unsigned instance) +std::shared_ptr +MavsdkImpl::server_component_by_type(Mavsdk::ComponentType server_component_type, unsigned instance) { switch (server_component_type) { - case Mavsdk::ServerComponentType::Autopilot: + case Mavsdk::ComponentType::Autopilot: if (instance == 0) { return server_component_by_id(MAV_COMP_ID_AUTOPILOT1); } else { @@ -176,7 +176,7 @@ std::shared_ptr MavsdkImpl::server_component_by_type( return {}; } - case Mavsdk::ServerComponentType::GroundStation: + case Mavsdk::ComponentType::GroundStation: if (instance == 0) { return server_component_by_id(MAV_COMP_ID_MISSIONPLANNER); } else { @@ -184,7 +184,7 @@ std::shared_ptr MavsdkImpl::server_component_by_type( return {}; } - case Mavsdk::ServerComponentType::CompanionComputer: + case Mavsdk::ComponentType::CompanionComputer: if (instance == 0) { return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER); } else if (instance == 1) { @@ -198,7 +198,7 @@ std::shared_ptr MavsdkImpl::server_component_by_type( return {}; } - case Mavsdk::ServerComponentType::Camera: + case Mavsdk::ComponentType::Camera: if (instance == 0) { return server_component_by_id(MAV_COMP_ID_CAMERA); } else if (instance == 1) { @@ -342,7 +342,7 @@ void MavsdkImpl::receive_message(mavlink_message_t& message, Connection* connect // mavlink instances which leads to existing implementations (including // examples and integration tests) to connect to QGroundControl by accident // instead of PX4 because the check `has_autopilot()` is not used. - if (_configuration.get_usage_type() == Mavsdk::Configuration::UsageType::GroundStation && + if (_configuration.get_component_type() == Mavsdk::ComponentType::GroundStation && message.sysid == 255 && message.compid == MAV_COMP_ID_MISSIONPLANNER) { if (_message_logging_on) { LogDebug() << "Ignoring messages from QGC as we are also a ground station"; @@ -680,20 +680,20 @@ Autopilot MavsdkImpl::autopilot() const // FIXME: this should be per component uint8_t MavsdkImpl::get_mav_type() const { - switch (_configuration.get_usage_type()) { - case Mavsdk::Configuration::UsageType::Autopilot: + switch (_configuration.get_component_type()) { + case Mavsdk::ComponentType::Autopilot: return MAV_TYPE_GENERIC; - case Mavsdk::Configuration::UsageType::GroundStation: + case Mavsdk::ComponentType::GroundStation: return MAV_TYPE_GCS; - case Mavsdk::Configuration::UsageType::CompanionComputer: + case Mavsdk::ComponentType::CompanionComputer: return MAV_TYPE_ONBOARD_CONTROLLER; - case Mavsdk::Configuration::UsageType::Camera: + case Mavsdk::ComponentType::Camera: return MAV_TYPE_CAMERA; - case Mavsdk::Configuration::UsageType::Custom: + case Mavsdk::ComponentType::Custom: return MAV_TYPE_GENERIC; default: diff --git a/src/mavsdk/core/mavsdk_impl.h b/src/mavsdk/core/mavsdk_impl.h index d50e6d2591..1afb891754 100644 --- a/src/mavsdk/core/mavsdk_impl.h +++ b/src/mavsdk/core/mavsdk_impl.h @@ -100,8 +100,8 @@ class MavsdkImpl { void intercept_incoming_messages_async(std::function callback); void intercept_outgoing_messages_async(std::function callback); - std::shared_ptr server_component_by_type( - Mavsdk::ServerComponentType server_component_type, unsigned instance = 0); + std::shared_ptr + server_component_by_type(Mavsdk::ComponentType server_component_type, unsigned instance = 0); std::shared_ptr server_component_by_id(uint8_t component_id); Time time{}; @@ -149,7 +149,7 @@ class MavsdkImpl { CallbackList<> _new_system_callbacks{}; - Mavsdk::Configuration _configuration{Mavsdk::Configuration::UsageType::GroundStation}; + Mavsdk::Configuration _configuration{Mavsdk::ComponentType::GroundStation}; struct UserCallback { UserCallback() = default; diff --git a/src/system_tests/action_arm_disarm.cpp b/src/system_tests/action_arm_disarm.cpp index db2093126f..4151e12a94 100644 --- a/src/system_tests/action_arm_disarm.cpp +++ b/src/system_tests/action_arm_disarm.cpp @@ -3,6 +3,7 @@ #include "plugins/action/action.h" #include "plugins/action_server/action_server.h" #include +#include using namespace mavsdk; @@ -10,18 +11,17 @@ TEST(SystemTest, ActionArmDisarm) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto action_server = ActionServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto action_server = + ActionServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -48,4 +48,6 @@ TEST(SystemTest, ActionArmDisarm) // And disarm again EXPECT_EQ(action.disarm(), Action::Result::Success); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/camera_take_photo.cpp b/src/system_tests/camera_take_photo.cpp index 0d5b24a365..6afa1ddf89 100644 --- a/src/system_tests/camera_take_photo.cpp +++ b/src/system_tests/camera_take_photo.cpp @@ -4,6 +4,7 @@ #include "log.h" #include #include +#include #include using namespace mavsdk; @@ -12,17 +13,16 @@ TEST(SystemTest, CameraTakePhoto) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); Mavsdk mavsdk_camera; - mavsdk_camera.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Camera}); + mavsdk_camera.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Camera}); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ(mavsdk_camera.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); auto camera_server = - CameraServer{mavsdk_camera.server_component_by_type(Mavsdk::ServerComponentType::Camera)}; + CameraServer{mavsdk_camera.server_component_by_type(Mavsdk::ComponentType::Camera)}; camera_server.subscribe_take_photo([&camera_server](int32_t index) { LogInfo() << "Let's take photo " << index; @@ -69,4 +69,6 @@ TEST(SystemTest, CameraTakePhoto) ASSERT_EQ( received_captured_info_fut.wait_for(std::chrono::seconds(10)), std::future_status::ready); received_captured_info_fut.get(); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/component_information.cpp b/src/system_tests/component_information.cpp index b379fa0d2e..74e10baaf6 100644 --- a/src/system_tests/component_information.cpp +++ b/src/system_tests/component_information.cpp @@ -3,6 +3,7 @@ #include #include #include +#include #include "mavsdk.h" #include "log.h" @@ -20,12 +21,12 @@ TEST(SystemTest, DISABLED_ComponentInformationConnect) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); Mavsdk mavsdk_companion; mavsdk_companion.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::CompanionComputer}); + Mavsdk::Configuration{Mavsdk::ComponentType::CompanionComputer}); ASSERT_EQ( mavsdk_companion.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); @@ -34,7 +35,7 @@ TEST(SystemTest, DISABLED_ComponentInformationConnect) auto system = maybe_system.value(); auto server = ComponentInformationServer{ - mavsdk_companion.server_component_by_type(Mavsdk::ServerComponentType::CompanionComputer)}; + mavsdk_companion.server_component_by_type(Mavsdk::ComponentType::CompanionComputer)}; auto param = ComponentInformationServer::FloatParam{}; param.name = "ANG_RATE_ACC_MAX"; @@ -67,4 +68,6 @@ TEST(SystemTest, DISABLED_ComponentInformationConnect) // Use another parameter to trigger the second callback. param_client.set_param_float("ANG_RATE_ACC_MAX", 6.0f); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/ftp_compare_files.cpp b/src/system_tests/ftp_compare_files.cpp index db4815ff66..cf513dae16 100644 --- a/src/system_tests/ftp_compare_files.cpp +++ b/src/system_tests/ftp_compare_files.cpp @@ -5,6 +5,7 @@ #include #include #include +#include #include "plugins/ftp/ftp.h" #include "plugins/ftp_server/ftp_server.h" #include "fs_helpers.h" @@ -30,20 +31,19 @@ TEST(SystemTest, FtpCompareFiles) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -73,4 +73,6 @@ TEST(SystemTest, FtpCompareFiles) (temp_dir_provided / temp_file).string(), temp_file_different.string()); EXPECT_EQ(result.first, Ftp::Result::Success); EXPECT_EQ(result.second, false); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/ftp_create_dir.cpp b/src/system_tests/ftp_create_dir.cpp index cf15c8bcc5..4b2c81ea51 100644 --- a/src/system_tests/ftp_create_dir.cpp +++ b/src/system_tests/ftp_create_dir.cpp @@ -7,6 +7,7 @@ #include #include #include +#include using namespace mavsdk; @@ -22,20 +23,19 @@ TEST(SystemTest, FtpCreateDir) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -57,4 +57,6 @@ TEST(SystemTest, FtpCreateDir) EXPECT_EQ(ftp.create_directory(temp_dir.string()), Ftp::Result::Success); EXPECT_TRUE(file_exists(temp_dir_provided / temp_dir)); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/ftp_download_file.cpp b/src/system_tests/ftp_download_file.cpp index ea7d2341c5..1e0dacdd60 100644 --- a/src/system_tests/ftp_download_file.cpp +++ b/src/system_tests/ftp_download_file.cpp @@ -5,6 +5,7 @@ #include #include #include +#include #include "plugins/ftp/ftp.h" #include "plugins/ftp_server/ftp_server.h" #include "fs_helpers.h" @@ -27,20 +28,19 @@ TEST(SystemTest, FtpDownloadFile) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -92,6 +92,8 @@ TEST(SystemTest, FtpDownloadFile) EXPECT_TRUE( are_files_identical(temp_dir_provided / temp_file, temp_dir_downloaded / temp_file)); } + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpDownloadBigFile) @@ -101,20 +103,19 @@ TEST(SystemTest, FtpDownloadBigFile) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; ftp_server.set_root_dir(temp_dir_provided.string()); @@ -147,6 +148,8 @@ TEST(SystemTest, FtpDownloadBigFile) EXPECT_TRUE( are_files_identical(temp_dir_provided / temp_file, temp_dir_downloaded / temp_file)); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpDownloadBigFileLossy) @@ -156,12 +159,11 @@ TEST(SystemTest, FtpDownloadBigFileLossy) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); unsigned counter = 0; @@ -174,8 +176,8 @@ TEST(SystemTest, FtpDownloadBigFileLossy) ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; ftp_server.set_root_dir(temp_dir_provided.string()); @@ -213,6 +215,8 @@ TEST(SystemTest, FtpDownloadBigFileLossy) // drop_some callback which accesses the local counter variable. mavsdk_groundstation.intercept_incoming_messages_async(nullptr); mavsdk_groundstation.intercept_outgoing_messages_async(nullptr); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpDownloadStopAndTryAgain) @@ -222,12 +226,11 @@ TEST(SystemTest, FtpDownloadStopAndTryAgain) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); // Once we received half, we want to stop all traffic. @@ -241,8 +244,8 @@ TEST(SystemTest, FtpDownloadStopAndTryAgain) ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; ftp_server.set_root_dir(temp_dir_provided.string()); @@ -302,6 +305,8 @@ TEST(SystemTest, FtpDownloadStopAndTryAgain) ASSERT_EQ(future_status, std::future_status::ready); EXPECT_EQ(fut.get(), Ftp::Result::Success); } + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpDownloadFileOutsideOfRoot) @@ -311,20 +316,19 @@ TEST(SystemTest, FtpDownloadFileOutsideOfRoot) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -352,4 +356,6 @@ TEST(SystemTest, FtpDownloadFileOutsideOfRoot) ASSERT_EQ(future_status, std::future_status::ready); EXPECT_EQ(fut.get(), Ftp::Result::ProtocolError); } + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/ftp_download_file_burst.cpp b/src/system_tests/ftp_download_file_burst.cpp index 1269b4e4fd..a65e09a619 100644 --- a/src/system_tests/ftp_download_file_burst.cpp +++ b/src/system_tests/ftp_download_file_burst.cpp @@ -5,6 +5,7 @@ #include #include #include +#include #include "plugins/ftp/ftp.h" #include "plugins/ftp_server/ftp_server.h" #include "fs_helpers.h" @@ -27,20 +28,19 @@ TEST(SystemTest, FtpDownloadBurstFile) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -92,6 +92,8 @@ TEST(SystemTest, FtpDownloadBurstFile) EXPECT_TRUE( are_files_identical(temp_dir_provided / temp_file, temp_dir_downloaded / temp_file)); } + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpDownloadBurstBigFile) @@ -101,20 +103,19 @@ TEST(SystemTest, FtpDownloadBurstBigFile) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; ftp_server.set_root_dir(temp_dir_provided.string()); @@ -147,6 +148,8 @@ TEST(SystemTest, FtpDownloadBurstBigFile) EXPECT_TRUE( are_files_identical(temp_dir_provided / temp_file, temp_dir_downloaded / temp_file)); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpDownloadBurstBigFileLossy) @@ -156,12 +159,11 @@ TEST(SystemTest, FtpDownloadBurstBigFileLossy) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); unsigned counter = 0; @@ -174,8 +176,8 @@ TEST(SystemTest, FtpDownloadBurstBigFileLossy) ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; ftp_server.set_root_dir(temp_dir_provided.string()); @@ -213,6 +215,8 @@ TEST(SystemTest, FtpDownloadBurstBigFileLossy) // drop_some callback which accesses the local counter variable. mavsdk_groundstation.intercept_incoming_messages_async(nullptr); mavsdk_groundstation.intercept_outgoing_messages_async(nullptr); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpDownloadBurstStopAndTryAgain) @@ -222,12 +226,11 @@ TEST(SystemTest, FtpDownloadBurstStopAndTryAgain) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); // Once we received half, we want to stop all traffic. @@ -241,8 +244,8 @@ TEST(SystemTest, FtpDownloadBurstStopAndTryAgain) ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; ftp_server.set_root_dir(temp_dir_provided.string()); @@ -302,6 +305,8 @@ TEST(SystemTest, FtpDownloadBurstStopAndTryAgain) ASSERT_EQ(future_status, std::future_status::ready); EXPECT_EQ(fut.get(), Ftp::Result::Success); } + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpDownloadBurstFileOutsideOfRoot) @@ -311,20 +316,19 @@ TEST(SystemTest, FtpDownloadBurstFileOutsideOfRoot) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -352,4 +356,6 @@ TEST(SystemTest, FtpDownloadBurstFileOutsideOfRoot) ASSERT_EQ(future_status, std::future_status::ready); EXPECT_EQ(fut.get(), Ftp::Result::ProtocolError); } + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/ftp_list_dir.cpp b/src/system_tests/ftp_list_dir.cpp index 38683fab01..4d7654094a 100644 --- a/src/system_tests/ftp_list_dir.cpp +++ b/src/system_tests/ftp_list_dir.cpp @@ -8,6 +8,7 @@ #include #include #include +#include using namespace mavsdk; @@ -40,20 +41,19 @@ TEST(SystemTest, FtpListDir) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -73,4 +73,6 @@ TEST(SystemTest, FtpListDir) EXPECT_EQ(ret.first, Ftp::Result::Success); EXPECT_EQ(ret.second, truth_list); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/ftp_remove_dir.cpp b/src/system_tests/ftp_remove_dir.cpp index 4aae10a351..64018a661a 100644 --- a/src/system_tests/ftp_remove_dir.cpp +++ b/src/system_tests/ftp_remove_dir.cpp @@ -7,6 +7,7 @@ #include #include #include +#include using namespace mavsdk; @@ -23,20 +24,19 @@ TEST(SystemTest, FtpRemoveDir) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -58,6 +58,8 @@ TEST(SystemTest, FtpRemoveDir) EXPECT_EQ(ftp.remove_directory(temp_dir.string()), Ftp::Result::Success); EXPECT_FALSE(file_exists(temp_dir_provided / temp_dir)); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpRemoveDirNotEmpty) @@ -67,20 +69,19 @@ TEST(SystemTest, FtpRemoveDirNotEmpty) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -97,4 +98,6 @@ TEST(SystemTest, FtpRemoveDirNotEmpty) EXPECT_EQ(ftp.remove_directory(temp_dir.string()), Ftp::Result::ProtocolError); EXPECT_TRUE(file_exists(temp_dir_provided / temp_dir)); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/ftp_remove_file.cpp b/src/system_tests/ftp_remove_file.cpp index 944fa8439b..b8a3c466e7 100644 --- a/src/system_tests/ftp_remove_file.cpp +++ b/src/system_tests/ftp_remove_file.cpp @@ -5,6 +5,7 @@ #include #include #include +#include #include "plugins/ftp/ftp.h" #include "plugins/ftp_server/ftp_server.h" #include "fs_helpers.h" @@ -25,20 +26,19 @@ TEST(SystemTest, FtpRemoveFile) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -58,26 +58,27 @@ TEST(SystemTest, FtpRemoveFile) EXPECT_EQ(ftp.remove_file(temp_file.string()), Ftp::Result::Success); EXPECT_FALSE(file_exists(temp_dir_provided / temp_file)); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpRemoveFileThatDoesNotExist) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -95,26 +96,27 @@ TEST(SystemTest, FtpRemoveFileThatDoesNotExist) EXPECT_EQ(ftp.remove_file(temp_file.string()), Ftp::Result::FileDoesNotExist); EXPECT_FALSE(file_exists(temp_dir_provided / temp_file)); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpRemoveFileOutsideOfRoot) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -130,4 +132,6 @@ TEST(SystemTest, FtpRemoveFileOutsideOfRoot) ftp_server.set_root_dir(temp_dir_provided.string()); EXPECT_EQ(ftp.remove_file((fs::path("..") / temp_file).string()), Ftp::Result::ProtocolError); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/ftp_rename_file.cpp b/src/system_tests/ftp_rename_file.cpp index 87a62813de..25a4ea2e5f 100644 --- a/src/system_tests/ftp_rename_file.cpp +++ b/src/system_tests/ftp_rename_file.cpp @@ -5,6 +5,7 @@ #include #include #include +#include #include "plugins/ftp/ftp.h" #include "plugins/ftp_server/ftp_server.h" #include "fs_helpers.h" @@ -27,20 +28,19 @@ TEST(SystemTest, FtpRenameFile) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -61,4 +61,6 @@ TEST(SystemTest, FtpRenameFile) EXPECT_EQ(ftp.rename(temp_file.string(), temp_file_renamed.string()), Ftp::Result::Success); EXPECT_TRUE(file_exists(temp_dir_provided / temp_file_renamed)); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/ftp_upload_file.cpp b/src/system_tests/ftp_upload_file.cpp index 04f9e1ed63..9262a32e0c 100644 --- a/src/system_tests/ftp_upload_file.cpp +++ b/src/system_tests/ftp_upload_file.cpp @@ -5,6 +5,7 @@ #include #include #include +#include #include "plugins/ftp/ftp.h" #include "plugins/ftp_server/ftp_server.h" #include "fs_helpers.h" @@ -31,20 +32,19 @@ TEST(SystemTest, FtpUploadFile) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -94,6 +94,8 @@ TEST(SystemTest, FtpUploadFile) EXPECT_TRUE( are_files_identical(temp_dir_to_upload / temp_file, temp_dir_provided / temp_file)); } + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpUploadBigFile) @@ -103,20 +105,19 @@ TEST(SystemTest, FtpUploadBigFile) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -150,6 +151,8 @@ TEST(SystemTest, FtpUploadBigFile) EXPECT_TRUE( are_files_identical(temp_dir_to_upload / temp_file, temp_dir_provided / temp_file)); } + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpUploadBigFileLossy) @@ -159,12 +162,11 @@ TEST(SystemTest, FtpUploadBigFileLossy) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); unsigned counter = 0; @@ -177,8 +179,8 @@ TEST(SystemTest, FtpUploadBigFileLossy) ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -215,6 +217,8 @@ TEST(SystemTest, FtpUploadBigFileLossy) mavsdk_groundstation.intercept_incoming_messages_async(nullptr); mavsdk_groundstation.intercept_outgoing_messages_async(nullptr); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpUploadStopAndTryAgain) @@ -224,12 +228,11 @@ TEST(SystemTest, FtpUploadStopAndTryAgain) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); // Once we received half, we want to stop all traffic. @@ -243,8 +246,8 @@ TEST(SystemTest, FtpUploadStopAndTryAgain) ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; ftp_server.set_root_dir(temp_dir_provided.string()); @@ -302,6 +305,8 @@ TEST(SystemTest, FtpUploadStopAndTryAgain) ASSERT_EQ(future_status, std::future_status::ready); EXPECT_EQ(fut.get(), Ftp::Result::Success); } + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, FtpUploadFileOutsideOfRoot) @@ -314,20 +319,19 @@ TEST(SystemTest, FtpUploadFileOutsideOfRoot) Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto ftp_server = FtpServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto ftp_server = + FtpServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -354,4 +358,6 @@ TEST(SystemTest, FtpUploadFileOutsideOfRoot) ASSERT_EQ(future_status, std::future_status::ready); EXPECT_EQ(fut.get(), Ftp::Result::ProtocolError); } + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/mission_raw_upload.cpp b/src/system_tests/mission_raw_upload.cpp index 474a919520..c9df0b613e 100644 --- a/src/system_tests/mission_raw_upload.cpp +++ b/src/system_tests/mission_raw_upload.cpp @@ -5,6 +5,7 @@ #include "plugins/mission_raw_server/mission_raw_server.h" #include #include +#include #include using namespace mavsdk; @@ -12,18 +13,17 @@ TEST(SystemTest, MissionRawUpload) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); auto mission_raw_server = MissionRawServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -42,4 +42,6 @@ TEST(SystemTest, MissionRawUpload) EXPECT_EQ( mission_raw.upload_mission(result_pair.second.mission_items), MissionRaw::Result::Success); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/param_custom_set_and_get.cpp b/src/system_tests/param_custom_set_and_get.cpp index ecdab0635d..9e26e81760 100644 --- a/src/system_tests/param_custom_set_and_get.cpp +++ b/src/system_tests/param_custom_set_and_get.cpp @@ -2,6 +2,7 @@ #include "mavsdk.h" #include "plugins/param/param.h" #include "plugins/param_server/param_server.h" +#include #include using namespace mavsdk; @@ -30,20 +31,19 @@ TEST(SystemTest, ParamCustomSetAndGet) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto param_server = ParamServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto param_server = + ParamServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -79,18 +79,19 @@ TEST(SystemTest, ParamCustomSetAndGet) auto server_result_pair = param_server.retrieve_param_custom(param_name); EXPECT_EQ(server_result_pair.first, ParamServer::Result::Success); EXPECT_EQ(server_result_pair.second, data_shorter); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, ParamCustomSetAndGetLossy) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); // Drop every third message @@ -104,8 +105,8 @@ TEST(SystemTest, ParamCustomSetAndGetLossy) ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto param_server = ParamServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto param_server = + ParamServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -146,4 +147,6 @@ TEST(SystemTest, ParamCustomSetAndGetLossy) // drop_some callback which accesses the local counter variable. mavsdk_groundstation.intercept_incoming_messages_async(nullptr); mavsdk_groundstation.intercept_incoming_messages_async(nullptr); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/param_get_all.cpp b/src/system_tests/param_get_all.cpp index 1680f2290c..c6396e7268 100644 --- a/src/system_tests/param_get_all.cpp +++ b/src/system_tests/param_get_all.cpp @@ -7,6 +7,7 @@ #include #include #include +#include using namespace mavsdk; @@ -61,20 +62,19 @@ TEST(SystemTest, ParamGetAll) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto param_server = ParamServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto param_server = + ParamServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -115,18 +115,19 @@ TEST(SystemTest, ParamGetAll) assert_equal(test_float_params, all_params.float_params); assert_equal(test_string_params, all_params.custom_params); } + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, ParamGetAllLossy) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); // Drop every third message @@ -140,8 +141,8 @@ TEST(SystemTest, ParamGetAllLossy) ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto param_server = ParamServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto param_server = + ParamServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -187,4 +188,6 @@ TEST(SystemTest, ParamGetAllLossy) // drop_some callback which accesses the local counter variable. mavsdk_groundstation.intercept_incoming_messages_async(nullptr); mavsdk_groundstation.intercept_outgoing_messages_async(nullptr); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } diff --git a/src/system_tests/param_set_and_get.cpp b/src/system_tests/param_set_and_get.cpp index 2f302e5f31..c9cc830981 100644 --- a/src/system_tests/param_set_and_get.cpp +++ b/src/system_tests/param_set_and_get.cpp @@ -3,6 +3,7 @@ #include "plugins/param/param.h" #include "plugins/param_server/param_server.h" #include +#include #include using namespace mavsdk; @@ -19,20 +20,19 @@ TEST(SystemTest, ParamSetAndGet) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto param_server = ParamServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto param_server = + ParamServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -94,13 +94,15 @@ TEST(SystemTest, ParamSetAndGet) auto server_result_all_params = param_server.retrieve_all_params(); EXPECT_EQ(server_result_all_params.int_params.size(), 1); EXPECT_EQ(server_result_all_params.float_params.size(), 1); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); } TEST(SystemTest, ParamSetAndGetLossy) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); mavsdk_groundstation.set_timeout_s(reduced_timeout_s); // Drop every third message @@ -111,16 +113,15 @@ TEST(SystemTest, ParamSetAndGetLossy) mavsdk_groundstation.intercept_incoming_messages_async(drop_some); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - auto param_server = ParamServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + auto param_server = + ParamServer{mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); diff --git a/src/system_tests/telemetry_subscription.cpp b/src/system_tests/telemetry_subscription.cpp index 9587baf29a..4ccc45bb6e 100644 --- a/src/system_tests/telemetry_subscription.cpp +++ b/src/system_tests/telemetry_subscription.cpp @@ -3,6 +3,7 @@ #include "plugins/telemetry/telemetry.h" #include "plugins/telemetry_server/telemetry_server.h" #include +#include #include using namespace mavsdk; @@ -11,18 +12,17 @@ TEST(SystemTest, TelemetrySubscription) { Mavsdk mavsdk_groundstation; mavsdk_groundstation.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::GroundStation}); + Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); Mavsdk mavsdk_autopilot; - mavsdk_autopilot.set_configuration( - Mavsdk::Configuration{Mavsdk::Configuration::UsageType::Autopilot}); + mavsdk_autopilot.set_configuration(Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( mavsdk_autopilot.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); auto telemetry_server = TelemetryServer{ - mavsdk_autopilot.server_component_by_type(Mavsdk::ServerComponentType::Autopilot)}; + mavsdk_autopilot.server_component_by_type(Mavsdk::ComponentType::Autopilot)}; auto maybe_system = mavsdk_groundstation.first_autopilot(10.0); ASSERT_TRUE(maybe_system); @@ -74,4 +74,6 @@ TEST(SystemTest, TelemetrySubscription) EXPECT_EQ(num_subscription1_called, 2); EXPECT_EQ(num_subscription2_called, 3); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); }