diff --git a/src/mavsdk/core/CMakeLists.txt b/src/mavsdk/core/CMakeLists.txt index fdb72e373e..07485c3756 100644 --- a/src/mavsdk/core/CMakeLists.txt +++ b/src/mavsdk/core/CMakeLists.txt @@ -17,14 +17,12 @@ target_sources(mavsdk call_every_handler.cpp connection.cpp connection_result.cpp - curl_wrapper.cpp crc32.cpp system.cpp system_impl.cpp flight_mode.cpp mavsdk.cpp mavsdk_impl.cpp - http_loader.cpp mavlink_channels.cpp mavlink_command_receiver.cpp mavlink_command_sender.cpp @@ -62,11 +60,33 @@ target_sources(mavsdk cmake_policy(SET CMP0079 NEW) target_link_libraries(mavsdk PRIVATE - MAVLink::mavlink - CURL::libcurl Threads::Threads ) +if (NOT BUILD_WITHOUT_CURL) + target_sources(mavsdk + PRIVATE + curl_wrapper.cpp + http_loader.cpp + ) + + target_link_libraries(mavsdk + PRIVATE + CURL::libcurl + ) + + list(APPEND UNIT_TEST_SOURCES + # TODO: add this again + ${PROJECT_SOURCE_DIR}/mavsdk/core/curl_test.cpp + #${PROJECT_SOURCE_DIR}/mavsdk/core/http_loader_test.cpp + ) +else() + target_compile_definitions(mavsdk + PRIVATE + BUILD_WITHOUT_CURL=1 + ) +endif() + set_target_properties(mavsdk PROPERTIES VERSION ${MAVSDK_VERSION_STRING} SOVERSION ${MAVSDK_SOVERSION_STRING} @@ -151,11 +171,8 @@ list(APPEND UNIT_TEST_SOURCES ${PROJECT_SOURCE_DIR}/mavsdk/core/callback_list_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/call_every_handler_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/cli_arg_test.cpp - ${PROJECT_SOURCE_DIR}/mavsdk/core/curl_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/locked_queue_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/geometry_test.cpp - # TODO: add this again - #${PROJECT_SOURCE_DIR}/mavsdk/core/http_loader_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/mavsdk_math_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/mavsdk_test.cpp ${PROJECT_SOURCE_DIR}/mavsdk/core/mavsdk_time_test.cpp diff --git a/src/mavsdk/plugins/camera/camera_impl.cpp b/src/mavsdk/plugins/camera/camera_impl.cpp index 78150d3be6..5fbadde834 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -163,12 +163,8 @@ void CameraImpl::prepare_async(const Camera::ResultCallback& callback) _system_impl->call_user_callback( [temp_callback]() { temp_callback(Camera::Result::Success); }); } else { - _camera_definition_callback = [this, temp_callback](bool has_succeeded) { - if (has_succeeded) { - temp_callback(Camera::Result::Success); - } else { - temp_callback(Camera::Result::Error); - } + _camera_definition_callback = [this, temp_callback](Camera::Result result) { + temp_callback(result); _camera_definition_callback = nullptr; }; @@ -1162,19 +1158,28 @@ void CameraImpl::process_camera_information(const mavlink_message_t& message) std::thread([this, camera_information]() { std::string content{}; - const auto has_succeeded = fetch_camera_definition(camera_information, content); + const auto result = fetch_camera_definition(camera_information, content); - if (has_succeeded) { + if (result == Camera::Result::Success) { LogDebug() << "Successfully loaded camera definition"; if (_camera_definition_callback) { _system_impl->call_user_callback( - [this]() { _camera_definition_callback(true); }); + [this, result]() { _camera_definition_callback(result); }); } _camera_definition.reset(new CameraDefinition()); _camera_definition->load_string(content); refresh_params(); + + } else if (result == Camera::Result::ProtocolUnsupported) { + LogWarn() << "Protocol for " << camera_information.cam_definition_uri + << " not supported"; + if (_camera_definition_callback) { + _system_impl->call_user_callback( + [this, result]() { _camera_definition_callback(result); }); + } + } else { LogDebug() << "Failed to fetch camera definition!"; @@ -1186,7 +1191,7 @@ void CameraImpl::process_camera_information(const mavlink_message_t& message) if (_camera_definition_callback) { _system_impl->call_user_callback( - [this]() { _camera_definition_callback(false); }); + [this, result]() { _camera_definition_callback(result); }); } } } @@ -1203,33 +1208,39 @@ bool CameraImpl::should_fetch_camera_definition(const std::string& uri) const !_has_camera_definition_timed_out; } -bool CameraImpl::fetch_camera_definition( +Camera::Result CameraImpl::fetch_camera_definition( const mavlink_camera_information_t& camera_information, std::string& camera_definition_out) { - auto download_succeeded = + auto result = download_definition_file(camera_information.cam_definition_uri, camera_definition_out); - if (download_succeeded) { - return true; + if (result == Camera::Result::Success) { + return result; } return load_stored_definition(camera_information, camera_definition_out); } -bool CameraImpl::download_definition_file( - const std::string& uri, std::string& camera_definition_out) +Camera::Result +CameraImpl::download_definition_file(const std::string& uri, std::string& camera_definition_out) { +#if BUILD_WITHOUT_CURL == 1 + UNUSED(uri); + UNUSED(camera_definition_out); + return Camera::Result::ProtocolUnsupported; +#else HttpLoader http_loader; LogInfo() << "Downloading camera definition from: " << uri; if (!http_loader.download_text_sync(uri, camera_definition_out)) { LogErr() << "Failed to download camera definition."; - return false; + return Camera::Result::Error; } +#endif - return true; + return Camera::Result::Success; } -bool CameraImpl::load_stored_definition( +Camera::Result CameraImpl::load_stored_definition( const mavlink_camera_information_t& camera_information, std::string& camera_definition_out) { // TODO: we might also try to support the correct version of the xml files. @@ -1246,33 +1257,33 @@ bool CameraImpl::load_stored_definition( if (model_name == "E90") { LogInfo() << "Using cached file for Yuneec E90."; camera_definition_out = e90xml; - return true; + return Camera::Result::Success; } else if (model_name == "E50") { LogInfo() << "Using cached file for Yuneec E50."; camera_definition_out = e50xml; - return true; + return Camera::Result::Success; } else if (model_name == "CGOET") { LogInfo() << "Using cached file for Yuneec ET."; camera_definition_out = cgoetxml; - return true; + return Camera::Result::Success; } else if (model_name == "E10T") { LogInfo() << "Using cached file for Yuneec E10T."; camera_definition_out = e10txml; - return true; + return Camera::Result::Success; } else if (model_name == "E30Z") { LogInfo() << "Using cached file for Yuneec E30Z."; camera_definition_out = e30zxml; - return true; + return Camera::Result::Success; } } else if (vendor_name == "Sony") { if (model_name == "ILCE-7RM4") { LogInfo() << "Using cached file for Sony ILCE-7RM4."; camera_definition_out = ILCE7RM4xml; - return true; + return Camera::Result::Success; } } - return false; + return Camera::Result::Error; } void CameraImpl::process_video_information(const mavlink_message_t& message) diff --git a/src/mavsdk/plugins/camera/camera_impl.h b/src/mavsdk/plugins/camera/camera_impl.h index 8fd922bda7..4514b410a0 100644 --- a/src/mavsdk/plugins/camera/camera_impl.h +++ b/src/mavsdk/plugins/camera/camera_impl.h @@ -158,10 +158,11 @@ class CameraImpl : public PluginImplBase { void check_status(); bool should_fetch_camera_definition(const std::string& uri) const; - bool fetch_camera_definition( + Camera::Result fetch_camera_definition( const mavlink_camera_information_t& camera_information, std::string& camera_definition_out); - bool download_definition_file(const std::string& uri, std::string& camera_definition_out); - bool + Camera::Result + download_definition_file(const std::string& uri, std::string& camera_definition_out); + Camera::Result load_stored_definition(const mavlink_camera_information_t&, std::string& camera_definition_out); void refresh_params(); @@ -209,7 +210,7 @@ class CameraImpl : public PluginImplBase { bool _is_fetching_camera_definition{false}; bool _has_camera_definition_timed_out{false}; size_t _camera_definition_fetch_count{0}; - using CameraDefinitionCallback = std::function; + using CameraDefinitionCallback = std::function; CameraDefinitionCallback _camera_definition_callback{}; std::atomic _camera_id{0}; diff --git a/third_party/CMakeLists.txt b/third_party/CMakeLists.txt index 647a866a00..1503e7b83b 100644 --- a/third_party/CMakeLists.txt +++ b/third_party/CMakeLists.txt @@ -12,12 +12,13 @@ if (SUPERBUILD) build_target(jsoncpp) build_target(tinyxml2) - if(NOT IOS) - build_target(zlib) + if(NOT BUILD_WITHOUT_CURL) + if(NOT IOS) + build_target(zlib) + endif() + build_target(curl) endif() - build_target(curl) - if(BUILD_MAVSDK_SERVER) build_target(openssl) build_target(cares)