From 0aeeb3d8c9362c8bc1f57559da5bca29b3d6f787 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 2 Oct 2024 08:12:02 +1300 Subject: [PATCH] better system tests --- src/mavsdk/core/http_loader.h | 2 +- .../plugins/camera/camera_definition.cpp | 6 +--- src/mavsdk/plugins/camera/camera_definition.h | 4 +-- src/mavsdk/plugins/camera/camera_impl.cpp | 33 +++++++++++++------ src/mavsdk/plugins/camera/camera_impl.h | 2 ++ src/system_tests/camera_definition.cpp | 10 ++++-- src/system_tests/camera_list_cameras.cpp | 6 ++-- src/system_tests/camera_take_photo.cpp | 17 ++++++++-- 8 files changed, 53 insertions(+), 27 deletions(-) diff --git a/src/mavsdk/core/http_loader.h b/src/mavsdk/core/http_loader.h index 1b8c45a5de..094dfb9c0b 100644 --- a/src/mavsdk/core/http_loader.h +++ b/src/mavsdk/core/http_loader.h @@ -18,7 +18,7 @@ class HttpLoader { HttpLoader(const std::shared_ptr& curl_wrapper); #endif - explicit HttpLoader(); + HttpLoader(); ~HttpLoader(); void start(); diff --git a/src/mavsdk/plugins/camera/camera_definition.cpp b/src/mavsdk/plugins/camera/camera_definition.cpp index 01ac614a97..1c5ffed425 100644 --- a/src/mavsdk/plugins/camera/camera_definition.cpp +++ b/src/mavsdk/plugins/camera/camera_definition.cpp @@ -3,10 +3,6 @@ namespace mavsdk { -CameraDefinition::CameraDefinition() {} - -CameraDefinition::~CameraDefinition() {} - bool CameraDefinition::load_file(const std::string& filepath) { tinyxml2::XMLError xml_error = _doc.LoadFile(filepath.c_str()); @@ -542,7 +538,7 @@ bool CameraDefinition::get_possible_settings_locked( settings[setting.first] = setting.second.value; } - return (settings.size() > 0); + return !settings.empty(); } bool CameraDefinition::set_setting(const std::string& name, const ParamValue& value) diff --git a/src/mavsdk/plugins/camera/camera_definition.h b/src/mavsdk/plugins/camera/camera_definition.h index 74d8697f95..b0cf4468a3 100644 --- a/src/mavsdk/plugins/camera/camera_definition.h +++ b/src/mavsdk/plugins/camera/camera_definition.h @@ -14,8 +14,8 @@ namespace mavsdk { class CameraDefinition { public: - CameraDefinition(); - ~CameraDefinition(); + CameraDefinition() = default; + ~CameraDefinition() = default; bool load_file(const std::string& filepath); bool load_string(const std::string& content); diff --git a/src/mavsdk/plugins/camera/camera_impl.cpp b/src/mavsdk/plugins/camera/camera_impl.cpp index 0a04fbdbce..a765626091 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -889,9 +889,12 @@ void CameraImpl::save_camera_mode_with_lock(PotentialCamera& potential_camera, C // different from {PHOTO, VIDEO}, in which case the mode received from // CAMERA_SETTINGS will be wrong. + if (!potential_camera.camera_definition) { + return; + } + ParamValue value; - if (potential_camera.camera_definition && - potential_camera.camera_definition->get_setting("CAM_MODE", value)) { + if (potential_camera.camera_definition->get_setting("CAM_MODE", value)) { if (value.is()) { value.set(static_cast(mode)); } else if (value.is()) { @@ -1298,7 +1301,8 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca const std::string url = potential_camera.camera_definition_url; if (potential_camera.camera_definition_url.empty()) { - return; + potential_camera.camera_definition_result = Camera::Result::SettingsUnavailable; + notify_camera_list(); } const auto& info = potential_camera.maybe_information.value(); @@ -1314,6 +1318,9 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca if (cached_file_option) { LogDebug() << "Using cached file " << cached_file_option.value(); load_camera_definition_with_lock(potential_camera, cached_file_option.value()); + potential_camera.is_fetching_camera_definition = false; + potential_camera.camera_definition_result = Camera::Result::Success; + notify_camera_list(); } else { potential_camera.is_fetching_camera_definition = true; @@ -1324,12 +1331,14 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca potential_camera.camera_definition_result = Camera::Result::ProtocolUnsupported; notify_camera_list(); #else - HttpLoader http_loader; + if (_http_loader == nullptr) { + _http_loader = std::make_unique(); + } LogInfo() << "Downloading camera definition from: " << url; auto camera_id = camera_id_for_potential_camera_with_lock(potential_camera); - http_loader.download_async( + _http_loader->download_async( url, download_path, [download_path, file_cache_tag, camera_id, this]( @@ -1382,11 +1391,15 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca MavlinkFtpClient::ClientResult client_result, MavlinkFtpClient::ProgressData progress_data) mutable { // TODO: check if we still exist - LogDebug() << "Mavlink FTP download progress: " - << 100 * progress_data.bytes_transferred / progress_data.total_bytes - << " %"; - if (client_result == MavlinkFtpClient::ClientResult::Next) { - return; + if (client_result == MavlinkFtpClient::ClientResult::Success || + client_result == MavlinkFtpClient::ClientResult::Next) { + LogDebug() + << "Mavlink FTP download progress: " + << 100 * progress_data.bytes_transferred / progress_data.total_bytes + << " %"; + if (client_result == MavlinkFtpClient::ClientResult::Next) { + return; + } } std::lock_guard lock(_mutex); diff --git a/src/mavsdk/plugins/camera/camera_impl.h b/src/mavsdk/plugins/camera/camera_impl.h index d1b7d489bb..b7a7c11976 100644 --- a/src/mavsdk/plugins/camera/camera_impl.h +++ b/src/mavsdk/plugins/camera/camera_impl.h @@ -388,6 +388,8 @@ class CameraImpl : public PluginImplBase { std::condition_variable _captured_request_cv; std::mutex _captured_request_mutex; + + std::unique_ptr _http_loader{nullptr}; }; } // namespace mavsdk diff --git a/src/system_tests/camera_definition.cpp b/src/system_tests/camera_definition.cpp index af5733e1c9..496204b01e 100644 --- a/src/system_tests/camera_definition.cpp +++ b/src/system_tests/camera_definition.cpp @@ -1,6 +1,7 @@ #include "mavsdk.h" #include "plugins/camera/camera.h" #include "plugins/camera_server/camera_server.h" +#include "plugins/ftp_server/ftp_server.h" #include "log.h" #include #include @@ -21,6 +22,10 @@ TEST(SystemTest, CameraDefinition) ASSERT_EQ( mavsdk_camera.add_any_connection("udpout://127.0.0.1:17000"), ConnectionResult::Success); + auto ftp_server = FtpServer{mavsdk_camera.server_component()}; + + EXPECT_EQ(ftp_server.set_root_dir("src/plugins/camera/"), FtpServer::Result::Success); + auto camera_server = CameraServer{mavsdk_camera.server_component()}; CameraServer::Information information{}; @@ -28,9 +33,8 @@ TEST(SystemTest, CameraDefinition) information.model_name = "Frozen Super"; information.firmware_version = "4.0.0"; information.definition_file_version = 1; - information.definition_file_uri = - "https://raw.githubusercontent.com/mavlink/MAVSDK/main/src/mavsdk/plugins/camera/e90_unit_test.xml"; - camera_server.set_information(information); + information.definition_file_uri = "mavlinkftp://e90_unit_test.xml"; + EXPECT_EQ(camera_server.set_information(information), CameraServer::Result::Success); auto prom = std::promise>(); auto fut = prom.get_future(); diff --git a/src/system_tests/camera_list_cameras.cpp b/src/system_tests/camera_list_cameras.cpp index 020a82ae55..4d76dd5639 100644 --- a/src/system_tests/camera_list_cameras.cpp +++ b/src/system_tests/camera_list_cameras.cpp @@ -28,8 +28,7 @@ TEST(SystemTest, CameraListCameras) information.model_name = "Frozen Super"; information.firmware_version = "4.0.0"; information.definition_file_version = 1; - information.definition_file_uri = - "https://raw.githubusercontent.com/mavlink/MAVSDK/main/src/mavsdk/plugins/camera/e90_unit_test.xml"; + information.definition_file_uri = ""; camera_server.set_information(information); auto prom = std::promise>(); @@ -51,14 +50,13 @@ TEST(SystemTest, CameraListCameras) bool found_camera = false; camera.subscribe_camera_list([&](Camera::CameraList camera_list) { - LogWarn() << "got called"; if (!camera_list.cameras.empty()) { found_camera = true; } }); // We have to wait until camera is found. - std::this_thread::sleep_for(std::chrono::milliseconds(100)); + std::this_thread::sleep_for(std::chrono::milliseconds(1000)); EXPECT_EQ(camera.camera_list().cameras.size(), 1); EXPECT_TRUE(found_camera); diff --git a/src/system_tests/camera_take_photo.cpp b/src/system_tests/camera_take_photo.cpp index 0325edb76c..5d1159154e 100644 --- a/src/system_tests/camera_take_photo.cpp +++ b/src/system_tests/camera_take_photo.cpp @@ -22,6 +22,15 @@ TEST(SystemTest, CameraTakePhoto) mavsdk_camera.add_any_connection("udpout://127.0.0.1:17000"), ConnectionResult::Success); auto camera_server = CameraServer{mavsdk_camera.server_component()}; + + CameraServer::Information information{}; + information.vendor_name = "CoolCameras"; + information.model_name = "Frozen Super"; + information.firmware_version = "4.0.0"; + information.definition_file_version = 1; + information.definition_file_uri = ""; + camera_server.set_information(information); + camera_server.subscribe_take_photo([&camera_server](int32_t index) { LogInfo() << "Let's take photo " << index; @@ -54,8 +63,12 @@ TEST(SystemTest, CameraTakePhoto) auto camera = Camera{system}; + std::this_thread::sleep_for(std::chrono::milliseconds(500)); + // We expect to find one camera. + ASSERT_EQ(camera.camera_list().cameras.size(), 1); + // We want to take the picture in photo mode. - EXPECT_EQ(camera.set_mode(0, Camera::Mode::Photo), Camera::Result::Success); + EXPECT_EQ(camera.set_mode(1, Camera::Mode::Photo), Camera::Result::Success); auto received_captured_info_prom = std::promise{}; auto received_captured_info_fut = received_captured_info_prom.get_future(); @@ -68,7 +81,7 @@ TEST(SystemTest, CameraTakePhoto) received_captured_info_prom.set_value(); }); - EXPECT_EQ(camera.take_photo(0), Camera::Result::Success); + EXPECT_EQ(camera.take_photo(1), Camera::Result::Success); ASSERT_EQ( received_captured_info_fut.wait_for(std::chrono::seconds(10)), std::future_status::ready); received_captured_info_fut.get();