diff --git a/proto b/proto index cce2f02cd..4e59e5f91 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit cce2f02cd86847fbf9414131e1edc33516415b14 +Subproject commit 4e59e5f9182d6a3b0e61c0a54ab8e4ff6fcf67af diff --git a/src/mavsdk/core/mavlink_command_receiver.cpp b/src/mavsdk/core/mavlink_command_receiver.cpp index b16913513..41154da19 100644 --- a/src/mavsdk/core/mavlink_command_receiver.cpp +++ b/src/mavsdk/core/mavlink_command_receiver.cpp @@ -95,8 +95,9 @@ void MavlinkCommandReceiver::receive_command_long(const mavlink_message_t& messa if (cmd.target_component_id != _server_component_impl.get_own_component_id() && cmd.target_component_id != MAV_COMP_ID_ALL) { if (_debugging) { - LogDebug() << "Ignored command long to component " << (int)cmd.target_component_id - << " instead of " << (int)_server_component_impl.get_own_component_id(); + LogDebug() << "Ignored command long to component " + << std::to_string(cmd.target_component_id) << " instead of " + << std::to_string(_server_component_impl.get_own_component_id()); } return; } @@ -106,7 +107,7 @@ void MavlinkCommandReceiver::receive_command_long(const mavlink_message_t& messa for (auto& handler : _mavlink_command_long_handler_table) { if (handler.cmd_id == cmd.command) { if (_debugging) { - LogDebug() << "Handling command long " << (int)cmd.command; + LogDebug() << "Handling command long " << std::to_string(cmd.command); } // The client side can pack a COMMAND_ACK as a response to receiving the command. @@ -124,8 +125,8 @@ void MavlinkCommandReceiver::receive_command_long(const mavlink_message_t& messa return response_message; }); if (_debugging) { - LogDebug() << "Acked command long " << (int)cmd.command << " with " - << maybe_command_ack.value().result; + LogDebug() << "Acked command long " << std::to_string(cmd.command) << " with " + << std::to_string(maybe_command_ack.value().result); } } } diff --git a/src/mavsdk/core/string_utils_test.cpp b/src/mavsdk/core/string_utils_test.cpp index f03f0b03a..02373d2b3 100644 --- a/src/mavsdk/core/string_utils_test.cpp +++ b/src/mavsdk/core/string_utils_test.cpp @@ -19,6 +19,6 @@ TEST(StringUtils, StripPrefix) EXPECT_EQ(strip_prefix("blafoo", "1234"), "blafoo"); EXPECT_EQ(strip_prefix("blafoo", "foo"), "blafoo"); EXPECT_EQ(strip_prefix("", ""), ""); - EXPECT_EQ(strip_prefix("", "b"), "b"); + EXPECT_EQ(strip_prefix("", "b"), ""); EXPECT_EQ(strip_prefix("f", ""), "f"); } diff --git a/src/mavsdk/plugins/camera/camera.cpp b/src/mavsdk/plugins/camera/camera.cpp index 5f7139e79..d1bc11b86 100644 --- a/src/mavsdk/plugins/camera/camera.cpp +++ b/src/mavsdk/plugins/camera/camera.cpp @@ -433,6 +433,8 @@ std::ostream& operator<<(std::ostream& str, Camera::Result const& result) return str << "Settings Loading"; case Camera::Result::CameraIdInvalid: return str << "Camera Id Invalid"; + case Camera::Result::ActionUnsupported: + return str << "Action Unsupported"; default: return str << "Unknown"; } diff --git a/src/mavsdk/plugins/camera/camera_impl.cpp b/src/mavsdk/plugins/camera/camera_impl.cpp index a8a394851..0a04fbdbc 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -165,7 +165,7 @@ CameraImpl::make_command_take_photo(int32_t camera_id, float interval_s, float n cmd.params.maybe_param1 = 0.0f; // Reserved, set to 0 cmd.params.maybe_param2 = interval_s; cmd.params.maybe_param3 = no_of_photos; - cmd.params.maybe_param4 = static_cast(_capture.sequence++); + cmd.params.maybe_param4 = capture_sequence_for_camera_id(camera_id); cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; @@ -175,7 +175,7 @@ MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_out(int32_t came { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_SET_CAMERA_ZOOM; - cmd.params.maybe_param1 = (float)ZOOM_TYPE_CONTINUOUS; + cmd.params.maybe_param1 = static_cast(ZOOM_TYPE_CONTINUOUS); cmd.params.maybe_param2 = -1.f; cmd.target_component_id = component_id_for_camera_id(camera_id); @@ -186,7 +186,7 @@ MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_in(int32_t camer { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_SET_CAMERA_ZOOM; - cmd.params.maybe_param1 = (float)ZOOM_TYPE_CONTINUOUS; + cmd.params.maybe_param1 = static_cast(ZOOM_TYPE_CONTINUOUS); cmd.params.maybe_param2 = 1.f; cmd.target_component_id = component_id_for_camera_id(camera_id); @@ -197,7 +197,7 @@ MavlinkCommandSender::CommandLong CameraImpl::make_command_zoom_stop(int32_t cam { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_SET_CAMERA_ZOOM; - cmd.params.maybe_param1 = (float)ZOOM_TYPE_CONTINUOUS; + cmd.params.maybe_param1 = static_cast(ZOOM_TYPE_CONTINUOUS); cmd.params.maybe_param2 = 0.f; cmd.target_component_id = component_id_for_camera_id(camera_id); @@ -212,7 +212,7 @@ CameraImpl::make_command_zoom_range(int32_t camera_id, float range) MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_SET_CAMERA_ZOOM; - cmd.params.maybe_param1 = (float)ZOOM_TYPE_RANGE; + cmd.params.maybe_param1 = static_cast(ZOOM_TYPE_RANGE); cmd.params.maybe_param2 = range; cmd.target_component_id = component_id_for_camera_id(camera_id); @@ -224,9 +224,9 @@ CameraImpl::make_command_track_point(int32_t camera_id, float point_x, float poi { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_CAMERA_TRACK_POINT; - cmd.params.maybe_param1 = (float)point_x; - cmd.params.maybe_param2 = (float)point_y; - cmd.params.maybe_param3 = (float)radius; + cmd.params.maybe_param1 = point_x; + cmd.params.maybe_param2 = point_y; + cmd.params.maybe_param3 = radius; cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; @@ -249,6 +249,7 @@ MavlinkCommandSender::CommandLong CameraImpl::make_command_track_rectangle( return cmd; } + MavlinkCommandSender::CommandLong CameraImpl::make_command_track_stop(int32_t camera_id) { MavlinkCommandSender::CommandLong cmd{}; @@ -257,36 +258,40 @@ MavlinkCommandSender::CommandLong CameraImpl::make_command_track_stop(int32_t ca return cmd; } + MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_in(int32_t camera_id) { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_SET_CAMERA_FOCUS; - cmd.params.maybe_param1 = (float)FOCUS_TYPE_CONTINUOUS; + cmd.params.maybe_param1 = static_cast(FOCUS_TYPE_CONTINUOUS); cmd.params.maybe_param2 = -1.f; cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; } + MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_out(int32_t camera_id) { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_SET_CAMERA_FOCUS; - cmd.params.maybe_param1 = (float)FOCUS_TYPE_CONTINUOUS; + cmd.params.maybe_param1 = static_cast(FOCUS_TYPE_CONTINUOUS); cmd.params.maybe_param2 = 1.f; cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; } + MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_stop(int32_t camera_id) { MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_SET_CAMERA_FOCUS; - cmd.params.maybe_param1 = (float)FOCUS_TYPE_CONTINUOUS; + cmd.params.maybe_param1 = static_cast(FOCUS_TYPE_CONTINUOUS); cmd.params.maybe_param2 = 0.f; cmd.target_component_id = component_id_for_camera_id(camera_id); return cmd; } + MavlinkCommandSender::CommandLong CameraImpl::make_command_focus_range(int32_t camera_id, float range) { @@ -295,7 +300,7 @@ CameraImpl::make_command_focus_range(int32_t camera_id, float range) MavlinkCommandSender::CommandLong cmd{}; cmd.command = MAV_CMD_SET_CAMERA_FOCUS; - cmd.params.maybe_param1 = (float)FOCUS_TYPE_RANGE; + cmd.params.maybe_param1 = static_cast(FOCUS_TYPE_RANGE); cmd.params.maybe_param2 = range; cmd.target_component_id = component_id_for_camera_id(camera_id); @@ -349,56 +354,6 @@ CameraImpl::make_command_set_camera_mode(int32_t camera_id, float mavlink_mode) return cmd_set_camera_mode; } -MavlinkCommandSender::CommandLong -CameraImpl::make_command_request_camera_settings(int32_t camera_id) -{ - MavlinkCommandSender::CommandLong cmd_req_camera_settings{}; - - cmd_req_camera_settings.command = MAV_CMD_REQUEST_CAMERA_SETTINGS; - cmd_req_camera_settings.params.maybe_param1 = 1.f; // Request it - cmd_req_camera_settings.target_component_id = component_id_for_camera_id(camera_id); - - return cmd_req_camera_settings; -} - -MavlinkCommandSender::CommandLong -CameraImpl::make_command_request_camera_capture_status(int32_t camera_id) -{ - MavlinkCommandSender::CommandLong cmd_req_camera_cap_stat{}; - - cmd_req_camera_cap_stat.command = MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS; - cmd_req_camera_cap_stat.params.maybe_param1 = 1.0f; // Request it - cmd_req_camera_cap_stat.target_component_id = component_id_for_camera_id(camera_id); - - return cmd_req_camera_cap_stat; -} - -MavlinkCommandSender::CommandLong -CameraImpl::make_command_request_camera_image_captured(int32_t camera_id, const size_t photo_id) -{ - MavlinkCommandSender::CommandLong cmd_req_camera_image_captured{}; - - cmd_req_camera_image_captured.command = MAV_CMD_REQUEST_MESSAGE; - cmd_req_camera_image_captured.params.maybe_param1 = - static_cast(MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED); - cmd_req_camera_image_captured.params.maybe_param2 = static_cast(photo_id); - cmd_req_camera_image_captured.target_component_id = component_id_for_camera_id(camera_id); - - return cmd_req_camera_image_captured; -} - -MavlinkCommandSender::CommandLong CameraImpl::make_command_request_storage_info(int32_t camera_id) -{ - MavlinkCommandSender::CommandLong cmd_req_storage_info{}; - - cmd_req_storage_info.command = MAV_CMD_REQUEST_STORAGE_INFORMATION; - cmd_req_storage_info.params.maybe_param1 = 0.f; // Reserved, set to 0 - cmd_req_storage_info.params.maybe_param2 = 1.f; // Request it - cmd_req_storage_info.target_component_id = component_id_for_camera_id(camera_id); - - return cmd_req_storage_info; -} - MavlinkCommandSender::CommandLong CameraImpl::make_command_start_video_streaming(int32_t camera_id, int32_t stream_id) { @@ -425,10 +380,6 @@ CameraImpl::make_command_stop_video_streaming(int32_t camera_id, int32_t stream_ Camera::Result CameraImpl::take_photo(int32_t camera_id) { - // TODO: check whether we are in photo mode. - - std::lock_guard lock(_capture.mutex); - // Take 1 photo only with no interval auto cmd_take_photo = make_command_take_photo(camera_id, 0.f, 1.0f); @@ -437,8 +388,6 @@ Camera::Result CameraImpl::take_photo(int32_t camera_id) Camera::Result CameraImpl::zoom_out_start(int32_t camera_id) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_out(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd)); @@ -446,8 +395,6 @@ Camera::Result CameraImpl::zoom_out_start(int32_t camera_id) Camera::Result CameraImpl::zoom_in_start(int32_t camera_id) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_in(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd)); @@ -455,8 +402,6 @@ Camera::Result CameraImpl::zoom_in_start(int32_t camera_id) Camera::Result CameraImpl::zoom_stop(int32_t camera_id) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_stop(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd)); @@ -464,8 +409,6 @@ Camera::Result CameraImpl::zoom_stop(int32_t camera_id) Camera::Result CameraImpl::zoom_range(int32_t camera_id, float range) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_range(camera_id, range); return camera_result_from_command_result(_system_impl->send_command(cmd)); @@ -474,8 +417,6 @@ Camera::Result CameraImpl::zoom_range(int32_t camera_id, float range) Camera::Result CameraImpl::track_point(int32_t camera_id, float point_x, float point_y, float radius) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_track_point(camera_id, point_x, point_y, radius); return camera_result_from_command_result(_system_impl->send_command(cmd)); @@ -488,8 +429,6 @@ Camera::Result CameraImpl::track_rectangle( float bottom_right_x, float bottom_right_y) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_track_rectangle( camera_id, top_left_x, top_left_y, bottom_right_x, bottom_right_y); @@ -498,8 +437,6 @@ Camera::Result CameraImpl::track_rectangle( Camera::Result CameraImpl::track_stop(int32_t camera_id) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_track_stop(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd)); @@ -507,8 +444,6 @@ Camera::Result CameraImpl::track_stop(int32_t camera_id) Camera::Result CameraImpl::focus_in_start(int32_t camera_id) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_in(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd)); @@ -516,8 +451,6 @@ Camera::Result CameraImpl::focus_in_start(int32_t camera_id) Camera::Result CameraImpl::focus_out_start(int32_t camera_id) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_out(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd)); @@ -525,8 +458,6 @@ Camera::Result CameraImpl::focus_out_start(int32_t camera_id) Camera::Result CameraImpl::focus_stop(int32_t camera_id) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_stop(camera_id); return camera_result_from_command_result(_system_impl->send_command(cmd)); @@ -534,8 +465,6 @@ Camera::Result CameraImpl::focus_stop(int32_t camera_id) Camera::Result CameraImpl::focus_range(int32_t camera_id, float range) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_range(camera_id, range); return camera_result_from_command_result(_system_impl->send_command(cmd)); @@ -543,10 +472,6 @@ Camera::Result CameraImpl::focus_range(int32_t camera_id, float range) Camera::Result CameraImpl::start_photo_interval(int32_t camera_id, float interval_s) { - // TODO: check whether we are in photo mode. - - std::lock_guard lock(_capture.mutex); - auto cmd_take_photo_time_lapse = make_command_take_photo(camera_id, interval_s, 0.f); return camera_result_from_command_result(_system_impl->send_command(cmd_take_photo_time_lapse)); @@ -562,8 +487,6 @@ Camera::Result CameraImpl::stop_photo_interval(int32_t camera_id) Camera::Result CameraImpl::start_video(int32_t camera_id) { // TODO: check whether video capture is already in progress. - // TODO: check whether we are in video mode. - // Capture status rate is not set auto cmd_start_video = make_command_start_video(camera_id, 0.f); @@ -584,8 +507,6 @@ Camera::Result CameraImpl::stop_video(int32_t camera_id) void CameraImpl::zoom_in_start_async(int32_t camera_id, const Camera::ResultCallback& callback) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_in(camera_id); _system_impl->send_command_async( @@ -596,8 +517,6 @@ void CameraImpl::zoom_in_start_async(int32_t camera_id, const Camera::ResultCall void CameraImpl::zoom_out_start_async(int32_t camera_id, const Camera::ResultCallback& callback) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_out(camera_id); _system_impl->send_command_async( @@ -608,8 +527,6 @@ void CameraImpl::zoom_out_start_async(int32_t camera_id, const Camera::ResultCal void CameraImpl::zoom_stop_async(int32_t camera_id, const Camera::ResultCallback& callback) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_stop(camera_id); _system_impl->send_command_async( @@ -621,8 +538,6 @@ void CameraImpl::zoom_stop_async(int32_t camera_id, const Camera::ResultCallback void CameraImpl::zoom_range_async( int32_t camera_id, float range, const Camera::ResultCallback& callback) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_zoom_range(camera_id, range); _system_impl->send_command_async( @@ -638,8 +553,6 @@ void CameraImpl::track_point_async( float radius, const Camera::ResultCallback& callback) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_track_point(camera_id, point_x, point_y, radius); _system_impl->send_command_async( @@ -656,8 +569,6 @@ void CameraImpl::track_rectangle_async( float bottom_right_y, const Camera::ResultCallback& callback) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_track_rectangle( camera_id, top_left_x, top_left_y, bottom_right_x, bottom_right_y); @@ -669,8 +580,6 @@ void CameraImpl::track_rectangle_async( void CameraImpl::track_stop_async(int32_t camera_id, const Camera::ResultCallback& callback) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_track_stop(camera_id); _system_impl->send_command_async( @@ -681,8 +590,6 @@ void CameraImpl::track_stop_async(int32_t camera_id, const Camera::ResultCallbac void CameraImpl::focus_in_start_async(int32_t camera_id, const Camera::ResultCallback& callback) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_in(camera_id); _system_impl->send_command_async( @@ -693,8 +600,6 @@ void CameraImpl::focus_in_start_async(int32_t camera_id, const Camera::ResultCal void CameraImpl::focus_out_start_async(int32_t camera_id, const Camera::ResultCallback& callback) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_out(camera_id); _system_impl->send_command_async( @@ -705,8 +610,6 @@ void CameraImpl::focus_out_start_async(int32_t camera_id, const Camera::ResultCa void CameraImpl::focus_stop_async(int32_t camera_id, const Camera::ResultCallback& callback) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_stop(camera_id); _system_impl->send_command_async( @@ -718,8 +621,6 @@ void CameraImpl::focus_stop_async(int32_t camera_id, const Camera::ResultCallbac void CameraImpl::focus_range_async( int32_t camera_id, float range, const Camera::ResultCallback& callback) { - std::lock_guard lock(_capture.mutex); - auto cmd = make_command_focus_range(camera_id, range); _system_impl->send_command_async( @@ -730,10 +631,6 @@ void CameraImpl::focus_range_async( void CameraImpl::take_photo_async(int32_t camera_id, const Camera::ResultCallback& callback) { - // TODO: check whether we are in photo mode. - - std::lock_guard lock(_capture.mutex); - // Take 1 photo only with no interval auto cmd_take_photo = make_command_take_photo(camera_id, 0.f, 1.0f); @@ -746,10 +643,6 @@ void CameraImpl::take_photo_async(int32_t camera_id, const Camera::ResultCallbac void CameraImpl::start_photo_interval_async( int32_t camera_id, float interval_s, const Camera::ResultCallback& callback) { - // TODO: check whether we are in photo mode. - - std::lock_guard lock(_capture.mutex); - auto cmd_take_photo_time_lapse = make_command_take_photo(camera_id, interval_s, 0.f); _system_impl->send_command_async( @@ -772,7 +665,6 @@ void CameraImpl::stop_photo_interval_async( void CameraImpl::start_video_async(int32_t camera_id, const Camera::ResultCallback& callback) { // TODO: check whether video capture is already in progress. - // TODO: check whether we are in video mode. // Capture status rate is not set auto cmd_start_video = make_command_start_video(camera_id, 0.f); @@ -793,28 +685,45 @@ void CameraImpl::stop_video_async(int32_t camera_id, const Camera::ResultCallbac }); } -Camera::CameraList CameraImpl::camera_list() const +Camera::CameraList CameraImpl::camera_list() { - std::lock_guard lock(_camera_list.mutex); + Camera::CameraList result{}; - return _camera_list.data; + std::lock_guard lock(_mutex); + + for (auto& potential_camera : _potential_cameras) { + if (!potential_camera.maybe_information) { + continue; + } + result.cameras.push_back(potential_camera.maybe_information.value()); + } + + return result; } Camera::CameraListHandle CameraImpl::subscribe_camera_list(const Camera::CameraListCallback& callback) { - std::lock_guard lock(_camera_list.mutex); - auto handle = _camera_list.subscription_callbacks.subscribe(callback); + std::lock_guard lock(_mutex); + auto handle = camera_list_subscription_callbacks.subscribe(callback); - // TODO: what should we do? + notify_camera_list(); return handle; } void CameraImpl::unsubscribe_camera_list(Camera::CameraListHandle handle) { - std::lock_guard lock(_camera_list.mutex); - _camera_list.subscription_callbacks.unsubscribe(handle); + std::lock_guard lock(_mutex); + camera_list_subscription_callbacks.unsubscribe(handle); +} + +void CameraImpl::notify_camera_list() +{ + _system_impl->call_user_callback([&]() { + camera_list_subscription_callbacks.queue( + camera_list(), [this](const auto& func) { func(); }); + }); } Camera::Result CameraImpl::start_video_streaming(int32_t camera_id, int32_t stream_id) @@ -906,7 +815,7 @@ CameraImpl::camera_result_from_command_result(const MavlinkCommandSender::Result case MavlinkCommandSender::Result::ConnectionError: // FALLTHROUGH case MavlinkCommandSender::Result::Busy: - return Camera::Result::Error; + // FALLTHROUGH case MavlinkCommandSender::Result::Failed: return Camera::Result::Error; case MavlinkCommandSender::Result::Denied: @@ -915,6 +824,9 @@ CameraImpl::camera_result_from_command_result(const MavlinkCommandSender::Result return Camera::Result::Denied; case MavlinkCommandSender::Result::Timeout: return Camera::Result::Timeout; + case MavlinkCommandSender::Result::Unsupported: + return Camera::Result::ActionUnsupported; + case MavlinkCommandSender::Result::Cancelled: default: return Camera::Result::Unknown; } @@ -928,18 +840,18 @@ Camera::Result CameraImpl::camera_result_from_parameter_result( return Camera::Result::Success; case MavlinkParameterClient::Result::Timeout: return Camera::Result::Timeout; - case MavlinkParameterClient::Result::ConnectionError: - return Camera::Result::Error; case MavlinkParameterClient::Result::WrongType: - return Camera::Result::WrongArgument; + // FALLTHROUGH case MavlinkParameterClient::Result::ParamNameTooLong: - return Camera::Result::WrongArgument; + // FALLTHROUGH case MavlinkParameterClient::Result::NotFound: - return Camera::Result::WrongArgument; + // FALLTHROUGH case MavlinkParameterClient::Result::ValueUnsupported: return Camera::Result::WrongArgument; + case MavlinkParameterClient::Result::ConnectionError: + // FALLTHROUGH case MavlinkParameterClient::Result::Failed: - return Camera::Result::Error; + // FALLTHROUGH case MavlinkParameterClient::Result::UnknownError: return Camera::Result::Error; default: @@ -955,7 +867,7 @@ Camera::Result CameraImpl::set_mode(int32_t camera_id, const Camera::Mode mode) const auto camera_result = camera_result_from_command_result(command_result); if (camera_result == Camera::Result::Success) { - std::lock_guard lock(_potential_cameras_mutex); + std::lock_guard lock(_mutex); auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(camera_id); if (maybe_potential_camera != nullptr) { save_camera_mode_with_lock(*maybe_potential_camera, mode); @@ -974,7 +886,7 @@ void CameraImpl::save_camera_mode_with_lock(PotentialCamera& potential_camera, C // Otherwise, we hardcode it to `uint32_t`. // Note that it could be that the camera definition defines options - // different than {PHOTO, VIDEO}, in which case the mode received from + // different from {PHOTO, VIDEO}, in which case the mode received from // CAMERA_SETTINGS will be wrong. ParamValue value; @@ -1094,7 +1006,7 @@ void CameraImpl::unsubscribe_capture_info(Camera::CaptureInfoHandle handle) void CameraImpl::process_heartbeat(const mavlink_message_t& message) { // Check for potential camera - std::lock_guard lock(_potential_cameras_mutex); + std::lock_guard lock(_mutex); auto found = std::any_of(_potential_cameras.begin(), _potential_cameras.end(), [&](const auto& item) { return item.component_id == message.compid; @@ -1137,7 +1049,8 @@ void CameraImpl::process_camera_capture_status(const mavlink_message_t& message) _status.data.photo_interval_on = (camera_capture_status.image_status == 2 || camera_capture_status.image_status == 3); _status.received_camera_capture_status = true; - _status.data.recording_time_s = float(camera_capture_status.recording_time_ms) / 1e3f; + _status.data.recording_time_s = + static_cast(camera_capture_status.recording_time_ms) / 1e3f; _status.image_count = camera_capture_status.image_count; @@ -1157,8 +1070,8 @@ void CameraImpl::process_storage_information(const mavlink_message_t& message) if (storage_information.total_capacity == 0.0f) { // Some MAVLink systems happen to send the STORAGE_INFORMATION message // to indicate that the camera has a slot for a storage even if there - // is no way to know anything about that storage (e.g. whether or not - // there is an sdcard in the slot). + // is no way to know anything about that storage (e.g. regardless of + // whether there is a sdcard in the slot). // // We consider that a total capacity of 0 means that this is such a // message, and we don't expect MAVSDK users to leverage it, which is @@ -1318,7 +1231,7 @@ void CameraImpl::process_camera_settings(const mavlink_message_t& message) mavlink_camera_settings_t camera_settings; mavlink_msg_camera_settings_decode(&message, &camera_settings); - std::lock_guard lock(_potential_cameras_mutex); + std::lock_guard lock(_mutex); auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(message.compid); if (maybe_potential_camera == nullptr) { @@ -1359,7 +1272,7 @@ void CameraImpl::process_camera_information(const mavlink_message_t& message) new_information.horizontal_resolution_px = camera_information.resolution_h; new_information.vertical_resolution_px = camera_information.resolution_v; - std::lock_guard lock(_potential_cameras_mutex); + std::lock_guard lock(_mutex); auto potential_camera = std::find_if(_potential_cameras.begin(), _potential_cameras.end(), [&](auto& item) { @@ -1409,6 +1322,7 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca if (starts_with(url, "http://") || starts_with(url, "https://")) { #if BUILD_WITHOUT_CURL == 1 potential_camera.camera_definition_result = Camera::Result::ProtocolUnsupported; + notify_camera_list(); #else HttpLoader http_loader; LogInfo() << "Downloading camera definition from: " << url; @@ -1421,10 +1335,11 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca [download_path, file_cache_tag, camera_id, this]( int progress, HttpStatus status, CURLcode curl_code) mutable { // TODO: check if we still exist - LogDebug() << "Download progress: " << progress << ", status: " << (int)status - << ", curl_code: " << (int)curl_code; + LogDebug() << "Download progress: " << progress + << ", status: " << static_cast(status) + << ", curl_code: " << std::to_string(curl_code); - std::lock_guard lock(_potential_cameras_mutex); + std::lock_guard lock(_mutex); auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(camera_id); if (maybe_potential_camera != nullptr) { @@ -1432,9 +1347,11 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca } if (status == HttpStatus::Error) { - LogErr() << "File download failed with result " << curl_code; + LogErr() << "File download failed with result " + << std::to_string(curl_code); maybe_potential_camera->is_fetching_camera_definition = false; maybe_potential_camera->camera_definition_result = Camera::Result::Error; + notify_camera_list(); } else if (status == HttpStatus::Finished) { LogDebug() << "File download finished " << download_path; @@ -1448,6 +1365,7 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca maybe_potential_camera->is_fetching_camera_definition = false; // TODO: add parsing result maybe_potential_camera->camera_definition_result = Camera::Result::Success; + notify_camera_list(); } }); #endif @@ -1471,7 +1389,7 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca return; } - std::lock_guard lock(_potential_cameras_mutex); + std::lock_guard lock(_mutex); auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(camera_id); if (maybe_potential_camera != nullptr) { @@ -1483,6 +1401,7 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca LogErr() << "File download failed with result " << client_result; maybe_potential_camera->is_fetching_camera_definition = false; maybe_potential_camera->camera_definition_result = Camera::Result::Error; + notify_camera_list(); return; } @@ -1497,10 +1416,12 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca // TODO: add parsing result maybe_potential_camera->is_fetching_camera_definition = false; maybe_potential_camera->camera_definition_result = Camera::Result::Success; + notify_camera_list(); }); } else { LogErr() << "Unknown protocol for URL: " << url; potential_camera.camera_definition_result = Camera::Result::ProtocolUnsupported; + notify_camera_list(); } } } @@ -1598,7 +1519,7 @@ void CameraImpl::check_status() } void CameraImpl::receive_command_result( - MavlinkCommandSender::Result command_result, const Camera::ResultCallback& callback) + MavlinkCommandSender::Result command_result, const Camera::ResultCallback& callback) const { Camera::Result camera_result = camera_result_from_command_result(command_result); @@ -1609,7 +1530,7 @@ void CameraImpl::receive_command_result( void CameraImpl::receive_set_mode_command_result( const MavlinkCommandSender::Result command_result, - const Camera::ResultCallback callback, + const Camera::ResultCallback& callback, const Camera::Mode mode, int32_t camera_id) { @@ -1620,7 +1541,7 @@ void CameraImpl::receive_set_mode_command_result( } if (camera_result == Camera::Result::Success) { - std::lock_guard lock(_potential_cameras_mutex); + std::lock_guard lock(_mutex); auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(camera_id); if (maybe_potential_camera != nullptr) { save_camera_mode_with_lock(*maybe_potential_camera, mode); @@ -1664,10 +1585,10 @@ bool CameraImpl::get_possible_options_with_lock( options.push_back(option); } - return options.size() > 0; + return !options.empty(); } -Camera::Result CameraImpl::set_setting(int32_t camera_id, Camera::Setting setting) +Camera::Result CameraImpl::set_setting(int32_t camera_id, const Camera::Setting& setting) { auto prom = std::make_shared>(); @@ -1680,7 +1601,7 @@ Camera::Result CameraImpl::set_setting(int32_t camera_id, Camera::Setting settin } void CameraImpl::set_setting_async( - int32_t camera_id, Camera::Setting setting, const Camera::ResultCallback callback) + int32_t camera_id, const Camera::Setting& setting, const Camera::ResultCallback& callback) { set_option_async(camera_id, setting.setting_id, setting.option, callback); } @@ -1691,7 +1612,7 @@ void CameraImpl::set_option_async( const Camera::Option& option, const Camera::ResultCallback& callback) { - std::lock_guard lock(_potential_cameras_mutex); + std::lock_guard lock(_mutex); auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(camera_id); if (maybe_potential_camera == nullptr) { if (callback != nullptr) { @@ -1725,7 +1646,7 @@ void CameraImpl::set_option_async( return; } - if (all_values.size() == 0) { + if (all_values.empty()) { if (callback) { LogErr() << "Could not get any options to get type for range param."; _system_impl->call_user_callback([callback]() { callback(Camera::Result::Error); }); @@ -1773,7 +1694,7 @@ void CameraImpl::set_option_async( setting_id, value, [this, camera_id, callback, setting_id, value](MavlinkParameterClient::Result result) { - std::lock_guard lock_later(_potential_cameras_mutex); + std::lock_guard lock_later(_mutex); auto maybe_potential_camera_later = maybe_potential_camera_for_camera_id_with_lock(camera_id); // We already checked these fields earlier, so we don't check again. @@ -1812,9 +1733,9 @@ void CameraImpl::set_option_async( } void CameraImpl::get_setting_async( - int32_t camera_id, Camera::Setting setting, const Camera::GetSettingCallback callback) + int32_t camera_id, const Camera::Setting& setting, const Camera::GetSettingCallback& callback) { - std::lock_guard lock(_potential_cameras_mutex); + std::lock_guard lock(_mutex); auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(camera_id); if (maybe_potential_camera == nullptr) { if (callback != nullptr) { @@ -1837,7 +1758,7 @@ void CameraImpl::get_setting_async( get_option_async( camera_id, setting.setting_id, - [this, setting, callback](Camera::Result result, const Camera::Option& option) { + [this, callback](Camera::Result result, const Camera::Option& option) { Camera::Setting new_setting{}; new_setting.option = option; if (callback) { @@ -1848,7 +1769,7 @@ void CameraImpl::get_setting_async( } std::pair -CameraImpl::get_setting(int32_t camera_id, Camera::Setting setting) +CameraImpl::get_setting(int32_t camera_id, const Camera::Setting& setting) { auto prom = std::make_shared>>(); auto ret = prom->get_future(); @@ -1891,7 +1812,7 @@ void CameraImpl::get_option_async( const std::string& setting_id, const std::function& callback) { - std::lock_guard lock(_potential_cameras_mutex); + std::lock_guard lock(_mutex); auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(camera_id); if (maybe_potential_camera == nullptr) { if (callback != nullptr) { @@ -1973,7 +1894,7 @@ void CameraImpl::unsubscribe_possible_setting_options(Camera::PossibleSettingOpt void CameraImpl::notify_current_settings_for_all() { - std::lock_guard lock(_potential_cameras_mutex); + std::lock_guard lock(_mutex); for (auto& potential_camera : _potential_cameras) { if (potential_camera.camera_definition != nullptr) { @@ -1984,7 +1905,7 @@ void CameraImpl::notify_current_settings_for_all() void CameraImpl::notify_possible_setting_options_for_all() { - std::lock_guard lock(_potential_cameras_mutex); + std::lock_guard lock(_mutex); for (auto& potential_camera : _potential_cameras) { if (potential_camera.camera_definition != nullptr) { @@ -2045,7 +1966,7 @@ void CameraImpl::notify_possible_setting_options_with_lock(PotentialCamera& pote } auto setting_options = get_possible_setting_options_with_lock(potential_camera); - if (setting_options.second.size() == 0) { + if (setting_options.second.empty()) { return; } @@ -2059,7 +1980,7 @@ CameraImpl::get_possible_setting_options(int32_t camera_id) { std::pair> result; - std::lock_guard lock(_potential_cameras_mutex); + std::lock_guard lock(_mutex); auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(camera_id); if (maybe_potential_camera == nullptr) { result.first = Camera::Result::CameraIdInvalid; @@ -2132,12 +2053,12 @@ void CameraImpl::refresh_params_with_lock(PotentialCamera& potential_camera) param_name, param_value_type, [camera_id, param_name, is_last, this]( - MavlinkParameterClient::Result result, ParamValue value) { + MavlinkParameterClient::Result result, const ParamValue& value) { if (result != MavlinkParameterClient::Result::Success) { return; } - std::lock_guard lock_later(_potential_cameras_mutex); + std::lock_guard lock_later(_mutex); auto maybe_potential_camera_later = maybe_potential_camera_for_camera_id_with_lock(camera_id); // We already checked these fields earlier, so we don't check again. @@ -2163,7 +2084,7 @@ void CameraImpl::refresh_params_with_lock(PotentialCamera& potential_camera) } bool CameraImpl::get_setting_str_with_lock( - PotentialCamera& potential_camera, std::string& setting_id, std::string& description) + PotentialCamera& potential_camera, const std::string& setting_id, std::string& description) { if (potential_camera.camera_definition == nullptr) { return false; @@ -2209,7 +2130,7 @@ Camera::Result CameraImpl::format_storage(int32_t camera_id, int32_t storage_id) } void CameraImpl::format_storage_async( - int32_t camera_id, int32_t storage_id, Camera::ResultCallback callback) + int32_t camera_id, int32_t storage_id, const Camera::ResultCallback& callback) { MavlinkCommandSender::CommandLong cmd_format{}; @@ -2242,7 +2163,7 @@ Camera::Result CameraImpl::reset_settings(int32_t camera_id) return ret.get(); } -void CameraImpl::reset_settings_async(int32_t camera_id, const Camera::ResultCallback callback) +void CameraImpl::reset_settings_async(int32_t camera_id, const Camera::ResultCallback& callback) { MavlinkCommandSender::CommandLong cmd_format{}; @@ -2284,7 +2205,7 @@ CameraImpl::list_photos(int32_t camera_id, Camera::PhotosRange photos_range) list_photos_async( camera_id, photos_range, - [&prom](Camera::Result result, std::vector photo_list) { + [&prom](Camera::Result result, const std::vector& photo_list) { prom.set_value(std::make_pair(result, photo_list)); }); @@ -2292,7 +2213,7 @@ CameraImpl::list_photos(int32_t camera_id, Camera::PhotosRange photos_range) } void CameraImpl::list_photos_async( - int32_t camera_id, Camera::PhotosRange photos_range, const Camera::ListPhotosCallback callback) + int32_t camera_id, Camera::PhotosRange photos_range, const Camera::ListPhotosCallback& callback) { if (!callback) { LogWarn() << "Trying to get a photo list with a null callback, ignoring..."; @@ -2339,19 +2260,20 @@ void CameraImpl::list_photos_async( // In case the vehicle sends capture info, but not those we are asking, we do not // want to loop infinitely. The safety_count is here to abort if this happens. auto safety_count = 0; - const auto safety_count_boundary = 10; + constexpr auto safety_count_boundary = 10; while (_status.photo_list.find(i) == _status.photo_list.end() && safety_count < safety_count_boundary) { safety_count++; auto request_try_number = 0; - const auto request_try_limit = - 10; // Timeout if the request times out that many times auto cv_status = std::cv_status::timeout; while (cv_status == std::cv_status::timeout) { request_try_number++; + + // Timeout if the request times out that many times + const auto request_try_limit = 10; if (request_try_number >= request_try_limit) { std::lock_guard status_lock(_status.mutex); _status.is_fetching_photos = false; @@ -2385,7 +2307,7 @@ void CameraImpl::list_photos_async( { std::lock_guard status_lock(_status.mutex); - for (auto capture_info : _status.photo_list) { + for (const auto& capture_info : _status.photo_list) { if (capture_info.first >= start_index) { photo_list.push_back(capture_info.second); } @@ -2412,7 +2334,7 @@ CameraImpl::get_current_settings(int32_t camera_id) { std::pair> result; - std::lock_guard lock(_potential_cameras_mutex); + std::lock_guard lock(_mutex); auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(camera_id); if (maybe_potential_camera != nullptr) { result.first = Camera::Result::CameraIdInvalid; @@ -2509,6 +2431,8 @@ uint8_t CameraImpl::component_id_for_camera_id(int32_t camera_id) return 0; } + std::lock_guard lock(_mutex); + if (camera_id < 0 || static_cast(camera_id - 1) >= _potential_cameras.size()) { LogErr() << "Invalid camera ID"; return 0; @@ -2517,7 +2441,24 @@ uint8_t CameraImpl::component_id_for_camera_id(int32_t camera_id) return _potential_cameras[camera_id - 1].component_id; } -int32_t CameraImpl::camera_id_for_potential_camera_with_lock(PotentialCamera& potential_camera) +uint16_t CameraImpl::capture_sequence_for_camera_id(int32_t camera_id) +{ + if (camera_id == 0) { + // All cameras + return 0; + } + + std::lock_guard lock(_mutex); + auto maybe_potential_camera = maybe_potential_camera_for_camera_id_with_lock(camera_id); + if (maybe_potential_camera == nullptr) { + return 0; + } + + return maybe_potential_camera->capture_sequence++; +} + +int32_t +CameraImpl::camera_id_for_potential_camera_with_lock(const PotentialCamera& potential_camera) { if (const auto it = std::find(_potential_cameras.begin(), _potential_cameras.end(), potential_camera); diff --git a/src/mavsdk/plugins/camera/camera_impl.h b/src/mavsdk/plugins/camera/camera_impl.h index 49a8334eb..d1b7d489b 100644 --- a/src/mavsdk/plugins/camera/camera_impl.h +++ b/src/mavsdk/plugins/camera/camera_impl.h @@ -10,7 +10,6 @@ #include "plugin_impl_base.h" #include "system.h" #include "callback_list.h" -#include "string_utils.h" #include namespace mavsdk { @@ -85,7 +84,7 @@ class CameraImpl : public PluginImplBase { void start_video_async(int32_t camera_id, const Camera::ResultCallback& callback); void stop_video_async(int32_t camera_id, const Camera::ResultCallback& callback); - Camera::CameraList camera_list() const; + Camera::CameraList camera_list(); Camera::CameraListHandle subscribe_camera_list(const Camera::CameraListCallback& callback); void unsubscribe_camera_list(Camera::CameraListHandle handle); @@ -99,9 +98,9 @@ class CameraImpl : public PluginImplBase { Camera::Result start_video_streaming(int32_t camera_id, int32_t stream_id); Camera::Result stop_video_streaming(int32_t camera_id, int32_t stream_id); - Camera::Result set_mode(int32_t camera_id, const Camera::Mode mode); - void set_mode_async( - int32_t camera_id, const Camera::Mode mode, const Camera::ResultCallback& callback); + Camera::Result set_mode(int32_t camera_id, Camera::Mode mode); + void + set_mode_async(int32_t camera_id, Camera::Mode mode, const Camera::ResultCallback& callback); Camera::Mode get_mode(int32_t camera_id); @@ -117,13 +116,15 @@ class CameraImpl : public PluginImplBase { Camera::Status get_status(int32_t camera_id); void get_setting_async( - int32_t camera_id, Camera::Setting setting, const Camera::GetSettingCallback callback); - Camera::Result set_setting(int32_t camera_id, Camera::Setting setting); + int32_t camera_id, + const Camera::Setting& setting, + const Camera::GetSettingCallback& callback); + Camera::Result set_setting(int32_t camera_id, const Camera::Setting& setting); void set_setting_async( - int32_t camera_id, Camera::Setting setting, const Camera::ResultCallback callback); + int32_t camera_id, const Camera::Setting& setting, const Camera::ResultCallback& callback); std::pair - get_setting(int32_t camera_id, Camera::Setting setting); + get_setting(int32_t camera_id, const Camera::Setting& setting); bool is_setting_range(const std::string& setting_id); @@ -142,17 +143,17 @@ class CameraImpl : public PluginImplBase { Camera::Result format_storage(int32_t camera_id, int32_t storage_id); void format_storage_async( - int32_t camera_id, int32_t storage_id, const Camera::ResultCallback callback); + int32_t camera_id, int32_t storage_id, const Camera::ResultCallback& callback); Camera::Result reset_settings(int32_t camera_id); - void reset_settings_async(int32_t camera_id, const Camera::ResultCallback callback); + void reset_settings_async(int32_t camera_id, const Camera::ResultCallback& callback); std::pair> list_photos(int32_t camera_id, Camera::PhotosRange photos_range); void list_photos_async( int32_t camera_id, Camera::PhotosRange photos_range, - const Camera::ListPhotosCallback callback); + const Camera::ListPhotosCallback& callback); CameraImpl(const CameraImpl&) = delete; CameraImpl& operator=(const CameraImpl&) = delete; @@ -174,6 +175,7 @@ class CameraImpl : public PluginImplBase { uint8_t component_id; Camera::Mode mode{Camera::Mode::Unknown}; + uint16_t capture_sequence{0}; bool operator==(const PotentialCamera& other) const { @@ -187,7 +189,7 @@ class CameraImpl : public PluginImplBase { void get_setting_async_with_lock( PotentialCamera& potential_camera, Camera::Setting setting, - const Camera::GetSettingCallback callback); + const Camera::GetSettingCallback& callback); bool get_possible_options_with_lock( PotentialCamera& camera, @@ -208,7 +210,7 @@ class CameraImpl : public PluginImplBase { const std::function& callback); bool get_setting_str_with_lock( - PotentialCamera& potential_camera, std::string& setting_id, std::string& description); + PotentialCamera& potential_camera, const std::string& setting_id, std::string& description); bool get_option_str_with_lock( PotentialCamera& potential_camera, const std::string& setting_id, @@ -216,18 +218,18 @@ class CameraImpl : public PluginImplBase { std::string& description); void receive_set_mode_command_result( - const MavlinkCommandSender::Result command_result, - const Camera::ResultCallback callback, - const Camera::Mode mode, + MavlinkCommandSender::Result command_result, + const Camera::ResultCallback& callback, + Camera::Mode mode, int32_t camera_id); static Camera::Result - camera_result_from_command_result(const MavlinkCommandSender::Result command_result); + camera_result_from_command_result(MavlinkCommandSender::Result command_result); static Camera::Result - camera_result_from_parameter_result(const MavlinkParameterClient::Result parameter_result); + camera_result_from_parameter_result(MavlinkParameterClient::Result parameter_result); void receive_command_result( - MavlinkCommandSender::Result command_result, const Camera::ResultCallback& callback); + MavlinkCommandSender::Result command_result, const Camera::ResultCallback& callback) const; void process_heartbeat(const mavlink_message_t& message); void process_camera_image_captured(const mavlink_message_t& message); @@ -241,7 +243,7 @@ class CameraImpl : public PluginImplBase { void check_potential_cameras_with_lock(); void check_camera_definition_with_lock(PotentialCamera& potential_camera); - void load_camera_definition_with_lock( + static void load_camera_definition_with_lock( PotentialCamera& potential_camera, const std::filesystem::path& path); void notify_mode(); @@ -253,16 +255,18 @@ class CameraImpl : public PluginImplBase { void notify_possible_setting_options_for_all(); void notify_possible_setting_options_with_lock(PotentialCamera& potential_camera); + void notify_camera_list(); + void check_status(); void refresh_params_with_lock(PotentialCamera& camera); void save_camera_mode_with_lock(PotentialCamera& potential_camera, Camera::Mode mode); - static Camera::Status::StorageStatus storage_status_from_mavlink(const int storage_status); - static Camera::Status::StorageType storage_type_from_mavlink(const int storage_type); - static float to_mavlink_camera_mode(const Camera::Mode mode); - static Camera::Mode to_camera_mode(const uint8_t mavlink_camera_mode); + static Camera::Status::StorageStatus storage_status_from_mavlink(int storage_status); + static Camera::Status::StorageType storage_type_from_mavlink(int storage_type); + static float to_mavlink_camera_mode(Camera::Mode mode); + static Camera::Mode to_camera_mode(uint8_t mavlink_camera_mode); CallEveryHandler::Cookie _camera_information_call_every_cookie{}; CallEveryHandler::Cookie _request_missing_capture_info_cookie{}; @@ -277,14 +281,8 @@ class CameraImpl : public PluginImplBase { make_command_take_photo(int32_t camera_id, float interval_s, float no_of_photos); MavlinkCommandSender::CommandLong make_command_stop_photo(int32_t camera_id); - MavlinkCommandSender::CommandLong make_command_request_camera_info(int32_t camera_id); MavlinkCommandSender::CommandLong make_command_set_camera_mode(int32_t camera_id, float mavlink_mode); - MavlinkCommandSender::CommandLong make_command_request_camera_settings(int32_t camera_id); - MavlinkCommandSender::CommandLong make_command_request_camera_capture_status(int32_t camera_id); - MavlinkCommandSender::CommandLong - make_command_request_camera_image_captured(int32_t camera_id, size_t photo_id); - MavlinkCommandSender::CommandLong make_command_request_storage_info(int32_t camera_id); MavlinkCommandSender::CommandLong make_command_start_video(int32_t camera_id, float capture_status_rate_hz); @@ -316,14 +314,16 @@ class CameraImpl : public PluginImplBase { void request_missing_capture_info(); uint8_t component_id_for_camera_id(int32_t camera_id); + uint16_t capture_sequence_for_camera_id(int32_t camera_id); - int32_t camera_id_for_potential_camera_with_lock(PotentialCamera& potential_camera); + int32_t camera_id_for_potential_camera_with_lock(const PotentialCamera& potential_camera); PotentialCamera* maybe_potential_camera_for_camera_id_with_lock(int32_t camera_id); static std::string get_filename_from_path(const std::string& path); - std::mutex _potential_cameras_mutex; + std::mutex _mutex; std::vector _potential_cameras; + CallbackList camera_list_subscription_callbacks{}; CallEveryHandler::Cookie _check_potential_cameras_call_every_cookie{}; @@ -361,11 +361,6 @@ class CameraImpl : public PluginImplBase { CallEveryHandler::Cookie call_every_cookie{}; } _mode{}; - struct { - std::mutex mutex{}; - int sequence = 1; // The MAVLink spec says the sequence starts at 1. - } _capture{}; - struct { std::mutex mutex{}; CallbackList callbacks{}; @@ -381,12 +376,6 @@ class CameraImpl : public PluginImplBase { CallbackList subscription_callbacks{}; } _video_stream_info{}; - struct { - mutable std::mutex mutex{}; - Camera::CameraList data{}; - CallbackList subscription_callbacks{}; - } _camera_list{}; - struct { std::mutex mutex{}; CallbackList> callbacks{}; diff --git a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h index 01ec2ad93..c82b24097 100644 --- a/src/mavsdk/plugins/camera/include/plugins/camera/camera.h +++ b/src/mavsdk/plugins/camera/include/plugins/camera/camera.h @@ -134,6 +134,7 @@ class Camera : public PluginBase { SettingsUnavailable, /**< @brief Settings not available. */ SettingsLoading, /**< @brief Settings not available yet. */ CameraIdInvalid, /**< @brief Camera with camera ID not found. */ + ActionUnsupported, /**< @brief Camera action not supported. */ }; /** diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index 13da2fe39..126b6d71c 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -20,6 +20,12 @@ CameraServerImpl::~CameraServerImpl() void CameraServerImpl::init() { + _server_component_impl->register_mavlink_command_handler( + MAV_CMD_REQUEST_MESSAGE, + [this](const MavlinkCommandReceiver::CommandLong& command) { + return process_request_message(command); + }, + this); _server_component_impl->register_mavlink_command_handler( MAV_CMD_REQUEST_CAMERA_INFORMATION, [this](const MavlinkCommandReceiver::CommandLong& command) { @@ -968,15 +974,33 @@ void CameraServerImpl::stop_image_capture_interval() std::optional CameraServerImpl::process_camera_information_request( const MavlinkCommandReceiver::CommandLong& command) { - LogWarn() << "Camera info request"; - auto capabilities = static_cast(command.params.param1); + LogDebug() << "Camera info request"; - if (!capabilities) { - LogDebug() << "early info return"; + if (static_cast(command.params.param1) == 0) { return _server_component_impl->make_command_ack_message( command, MAV_RESULT::MAV_RESULT_ACCEPTED); } + return send_camera_information(command); +} + +std::optional +CameraServerImpl::process_request_message(const MavlinkCommandReceiver::CommandLong& command) +{ + switch (static_cast(command.params.param1)) { + case MAVLINK_MSG_ID_CAMERA_INFORMATION: + return send_camera_information(command); + + default: + LogWarn() << "Got unknown request message!"; + return _server_component_impl->make_command_ack_message( + command, MAV_RESULT::MAV_RESULT_DENIED); + } +} + +std::optional +CameraServerImpl::send_camera_information(const MavlinkCommandReceiver::CommandLong& command) +{ if (!_is_information_set) { return _server_component_impl->make_command_ack_message( command, MAV_RESULT::MAV_RESULT_TEMPORARILY_REJECTED); @@ -986,7 +1010,6 @@ std::optional CameraServerImpl::process_camera_informatio auto command_ack = _server_component_impl->make_command_ack_message(command, MAV_RESULT::MAV_RESULT_ACCEPTED); _server_component_impl->send_command_ack(command_ack); - LogDebug() << "sent info ack"; // It is safe to ignore the return value of parse_version_string() here // since the string was already validated in set_information(). @@ -1056,9 +1079,7 @@ std::optional CameraServerImpl::process_camera_informatio 0); return message; }); - LogDebug() << "sent info msg"; - // ack was already sent return std::nullopt; } @@ -1068,7 +1089,6 @@ std::optional CameraServerImpl::process_camera_settings_r auto settings = static_cast(command.params.param1); if (!settings) { - LogDebug() << "early settings return"; return _server_component_impl->make_command_ack_message( command, MAV_RESULT::MAV_RESULT_ACCEPTED); } @@ -1110,7 +1130,6 @@ std::optional CameraServerImpl::process_storage_informati auto information = static_cast(command.params.param2); if (!information) { - LogDebug() << "early storage return"; return _server_component_impl->make_command_ack_message( command, MAV_RESULT::MAV_RESULT_ACCEPTED); } diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index 54b13b959..a3ccdfbb6 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -193,6 +193,12 @@ class CameraServerImpl : public ServerPluginImplBase { std::optional process_set_message_interval(const MavlinkCommandReceiver::CommandLong& command); + std::optional + process_request_message(const MavlinkCommandReceiver::CommandLong& command); + + std::optional + send_camera_information(const MavlinkCommandReceiver::CommandLong& command); + void send_capture_status(); bool _is_information_set{}; diff --git a/src/mavsdk_server/src/generated/camera/camera.pb.cc b/src/mavsdk_server/src/generated/camera/camera.pb.cc index 40d76d38a..6178f9647 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.cc +++ b/src/mavsdk_server/src/generated/camera/camera.pb.cc @@ -2912,9 +2912,9 @@ const char descriptor_table_protodef_camera_2fcamera_2eproto[] PROTOBUF_SECTION_ "angeRequest\022\021\n\tcamera_id\030\001 \001(\005\022\r\n\005range\030" "\002 \001(\002\"L\n\022FocusRangeResponse\0226\n\rcamera_re" "sult\030\001 \001(\0132\037.mavsdk.rpc.camera.CameraRes" - "ult\"\235\003\n\014CameraResult\0226\n\006result\030\001 \001(\0162&.m" + "ult\"\274\003\n\014CameraResult\0226\n\006result\030\001 \001(\0162&.m" "avsdk.rpc.camera.CameraResult.Result\022\022\n\n" - "result_str\030\002 \001(\t\"\300\002\n\006Result\022\022\n\016RESULT_UN" + "result_str\030\002 \001(\t\"\337\002\n\006Result\022\022\n\016RESULT_UN" "KNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022RESULT_IN" "_PROGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRESULT_D" "ENIED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIME" @@ -2922,167 +2922,168 @@ const char descriptor_table_protodef_camera_2fcamera_2eproto[] PROTOBUF_SECTION_ "LT_NO_SYSTEM\020\010\022\037\n\033RESULT_PROTOCOL_UNSUPP" "ORTED\020\t\022\037\n\033RESULT_SETTINGS_UNAVAILABLE\020\n" "\022\033\n\027RESULT_SETTINGS_LOADING\020\013\022\034\n\030RESULT_" - "CAMERA_ID_INVALID\020\014\"q\n\010Position\022\024\n\014latit" - "ude_deg\030\001 \001(\001\022\025\n\rlongitude_deg\030\002 \001(\001\022\033\n\023" - "absolute_altitude_m\030\003 \001(\002\022\033\n\023relative_al" - "titude_m\030\004 \001(\002\"8\n\nQuaternion\022\t\n\001w\030\001 \001(\002\022" - "\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"B\n\nEule" - "rAngle\022\020\n\010roll_deg\030\001 \001(\002\022\021\n\tpitch_deg\030\002 " - "\001(\002\022\017\n\007yaw_deg\030\003 \001(\002\"\377\001\n\013CaptureInfo\022-\n\010" - "position\030\001 \001(\0132\033.mavsdk.rpc.camera.Posit" - "ion\022:\n\023attitude_quaternion\030\002 \001(\0132\035.mavsd" - "k.rpc.camera.Quaternion\022;\n\024attitude_eule" - "r_angle\030\003 \001(\0132\035.mavsdk.rpc.camera.EulerA" - "ngle\022\023\n\013time_utc_us\030\004 \001(\004\022\022\n\nis_success\030" - "\005 \001(\010\022\r\n\005index\030\006 \001(\005\022\020\n\010file_url\030\007 \001(\t\"\305" - "\001\n\023VideoStreamSettings\022\025\n\rframe_rate_hz\030" - "\001 \001(\002\022!\n\031horizontal_resolution_pix\030\002 \001(\r" - "\022\037\n\027vertical_resolution_pix\030\003 \001(\r\022\024\n\014bit" - "_rate_b_s\030\004 \001(\r\022\024\n\014rotation_deg\030\005 \001(\r\022\013\n" - "\003uri\030\006 \001(\t\022\032\n\022horizontal_fov_deg\030\007 \001(\002\"\325" - "\003\n\017VideoStreamInfo\022\021\n\tcamera_id\030\001 \001(\005\0228\n" - "\010settings\030\002 \001(\0132&.mavsdk.rpc.camera.Vide" - "oStreamSettings\022D\n\006status\030\003 \001(\01624.mavsdk" - ".rpc.camera.VideoStreamInfo.VideoStreamS" - "tatus\022H\n\010spectrum\030\004 \001(\01626.mavsdk.rpc.cam" - "era.VideoStreamInfo.VideoStreamSpectrum\"" - "]\n\021VideoStreamStatus\022#\n\037VIDEO_STREAM_STA" - "TUS_NOT_RUNNING\020\000\022#\n\037VIDEO_STREAM_STATUS" - "_IN_PROGRESS\020\001\"\205\001\n\023VideoStreamSpectrum\022!" - "\n\035VIDEO_STREAM_SPECTRUM_UNKNOWN\020\000\022\'\n#VID" - "EO_STREAM_SPECTRUM_VISIBLE_LIGHT\020\001\022\"\n\036VI" - "DEO_STREAM_SPECTRUM_INFRARED\020\002\"\232\005\n\006Statu" - "s\022\021\n\tcamera_id\030\001 \001(\005\022\020\n\010video_on\030\002 \001(\010\022\031" - "\n\021photo_interval_on\030\003 \001(\010\022\030\n\020used_storag" - "e_mib\030\004 \001(\002\022\035\n\025available_storage_mib\030\005 \001" - "(\002\022\031\n\021total_storage_mib\030\006 \001(\002\022\030\n\020recordi" - "ng_time_s\030\007 \001(\002\022\031\n\021media_folder_name\030\010 \001" - "(\t\022\?\n\016storage_status\030\t \001(\0162\'.mavsdk.rpc." - "camera.Status.StorageStatus\022\022\n\nstorage_i" - "d\030\n \001(\r\022;\n\014storage_type\030\013 \001(\0162%.mavsdk.r" - "pc.camera.Status.StorageType\"\221\001\n\rStorage" - "Status\022 \n\034STORAGE_STATUS_NOT_AVAILABLE\020\000" - "\022\036\n\032STORAGE_STATUS_UNFORMATTED\020\001\022\034\n\030STOR" - "AGE_STATUS_FORMATTED\020\002\022 \n\034STORAGE_STATUS" - "_NOT_SUPPORTED\020\003\"\240\001\n\013StorageType\022\030\n\024STOR" - "AGE_TYPE_UNKNOWN\020\000\022\032\n\026STORAGE_TYPE_USB_S" - "TICK\020\001\022\023\n\017STORAGE_TYPE_SD\020\002\022\030\n\024STORAGE_T" - "YPE_MICROSD\020\003\022\023\n\017STORAGE_TYPE_HD\020\007\022\027\n\022ST" - "ORAGE_TYPE_OTHER\020\376\001\"7\n\006Option\022\021\n\toption_" - "id\030\001 \001(\t\022\032\n\022option_description\030\002 \001(\t\"w\n\007" - "Setting\022\022\n\nsetting_id\030\001 \001(\t\022\033\n\023setting_d" - "escription\030\002 \001(\t\022)\n\006option\030\003 \001(\0132\031.mavsd" - "k.rpc.camera.Option\022\020\n\010is_range\030\004 \001(\010\"\222\001" - "\n\016SettingOptions\022\021\n\tcamera_id\030\001 \001(\005\022\022\n\ns" - "etting_id\030\002 \001(\t\022\033\n\023setting_description\030\003" - " \001(\t\022*\n\007options\030\004 \003(\0132\031.mavsdk.rpc.camer" - "a.Option\022\020\n\010is_range\030\005 \001(\010\"\325\001\n\013Informati" - "on\022\023\n\013vendor_name\030\001 \001(\t\022\022\n\nmodel_name\030\002 " - "\001(\t\022\027\n\017focal_length_mm\030\003 \001(\002\022!\n\031horizont" - "al_sensor_size_mm\030\004 \001(\002\022\037\n\027vertical_sens" - "or_size_mm\030\005 \001(\002\022 \n\030horizontal_resolutio" - "n_px\030\006 \001(\r\022\036\n\026vertical_resolution_px\030\007 \001" - "(\r\"=\n\nCameraList\022/\n\007cameras\030\001 \003(\0132\036.mavs" - "dk.rpc.camera.Information*8\n\004Mode\022\020\n\014MOD" - "E_UNKNOWN\020\000\022\016\n\nMODE_PHOTO\020\001\022\016\n\nMODE_VIDE" - "O\020\002*F\n\013PhotosRange\022\024\n\020PHOTOS_RANGE_ALL\020\000" - "\022!\n\035PHOTOS_RANGE_SINCE_CONNECTION\020\0012\327\035\n\r" - "CameraService\022X\n\tTakePhoto\022#.mavsdk.rpc." - "camera.TakePhotoRequest\032$.mavsdk.rpc.cam" - "era.TakePhotoResponse\"\000\022s\n\022StartPhotoInt" - "erval\022,.mavsdk.rpc.camera.StartPhotoInte" - "rvalRequest\032-.mavsdk.rpc.camera.StartPho" - "toIntervalResponse\"\000\022p\n\021StopPhotoInterva" - "l\022+.mavsdk.rpc.camera.StopPhotoIntervalR" - "equest\032,.mavsdk.rpc.camera.StopPhotoInte" - "rvalResponse\"\000\022[\n\nStartVideo\022$.mavsdk.rp" - "c.camera.StartVideoRequest\032%.mavsdk.rpc." - "camera.StartVideoResponse\"\000\022X\n\tStopVideo" - "\022#.mavsdk.rpc.camera.StopVideoRequest\032$." - "mavsdk.rpc.camera.StopVideoResponse\"\000\022z\n" - "\023StartVideoStreaming\022-.mavsdk.rpc.camera" - ".StartVideoStreamingRequest\032..mavsdk.rpc" - ".camera.StartVideoStreamingResponse\"\004\200\265\030" - "\001\022w\n\022StopVideoStreaming\022,.mavsdk.rpc.cam" - "era.StopVideoStreamingRequest\032-.mavsdk.r" - "pc.camera.StopVideoStreamingResponse\"\004\200\265" - "\030\001\022R\n\007SetMode\022!.mavsdk.rpc.camera.SetMod" - "eRequest\032\".mavsdk.rpc.camera.SetModeResp" - "onse\"\000\022[\n\nListPhotos\022$.mavsdk.rpc.camera" - ".ListPhotosRequest\032%.mavsdk.rpc.camera.L" - "istPhotosResponse\"\000\022o\n\023SubscribeCameraLi" - "st\022-.mavsdk.rpc.camera.SubscribeCameraLi" - "stRequest\032%.mavsdk.rpc.camera.CameraList" - "Response\"\0000\001\022a\n\rSubscribeMode\022\'.mavsdk.r" - "pc.camera.SubscribeModeRequest\032\037.mavsdk." - "rpc.camera.ModeResponse\"\004\200\265\030\0000\001\022V\n\007GetMo" - "de\022!.mavsdk.rpc.camera.GetModeRequest\032\"." - "mavsdk.rpc.camera.GetModeResponse\"\004\200\265\030\001\022" - "\202\001\n\030SubscribeVideoStreamInfo\0222.mavsdk.rp" - "c.camera.SubscribeVideoStreamInfoRequest" - "\032*.mavsdk.rpc.camera.VideoStreamInfoResp" - "onse\"\004\200\265\030\0000\001\022w\n\022GetVideoStreamInfo\022,.mav" - "sdk.rpc.camera.GetVideoStreamInfoRequest" - "\032-.mavsdk.rpc.camera.GetVideoStreamInfoR" - "esponse\"\004\200\265\030\001\022v\n\024SubscribeCaptureInfo\022.." - "mavsdk.rpc.camera.SubscribeCaptureInfoRe" - "quest\032&.mavsdk.rpc.camera.CaptureInfoRes" - "ponse\"\004\200\265\030\0000\001\022g\n\017SubscribeStatus\022).mavsd" - "k.rpc.camera.SubscribeStatusRequest\032!.ma" - "vsdk.rpc.camera.StatusResponse\"\004\200\265\030\0000\001\022\\" - "\n\tGetStatus\022#.mavsdk.rpc.camera.GetStatu" - "sRequest\032$.mavsdk.rpc.camera.GetStatusRe" - "sponse\"\004\200\265\030\001\022\202\001\n\030SubscribeCurrentSetting" - "s\0222.mavsdk.rpc.camera.SubscribeCurrentSe" - "ttingsRequest\032*.mavsdk.rpc.camera.Curren" - "tSettingsResponse\"\004\200\265\030\0000\001\022w\n\022GetCurrentS" - "ettings\022,.mavsdk.rpc.camera.GetCurrentSe" - "ttingsRequest\032-.mavsdk.rpc.camera.GetCur" - "rentSettingsResponse\"\004\200\265\030\001\022\227\001\n\037Subscribe" - "PossibleSettingOptions\0229.mavsdk.rpc.came" - "ra.SubscribePossibleSettingOptionsReques" - "t\0321.mavsdk.rpc.camera.PossibleSettingOpt" - "ionsResponse\"\004\200\265\030\0000\001\022\214\001\n\031GetPossibleSett" - "ingOptions\0223.mavsdk.rpc.camera.GetPossib" - "leSettingOptionsRequest\0324.mavsdk.rpc.cam" - "era.GetPossibleSettingOptionsResponse\"\004\200" - "\265\030\001\022[\n\nSetSetting\022$.mavsdk.rpc.camera.Se" - "tSettingRequest\032%.mavsdk.rpc.camera.SetS" - "ettingResponse\"\000\022[\n\nGetSetting\022$.mavsdk." - "rpc.camera.GetSettingRequest\032%.mavsdk.rp" - "c.camera.GetSettingResponse\"\000\022d\n\rFormatS" - "torage\022\'.mavsdk.rpc.camera.FormatStorage" - "Request\032(.mavsdk.rpc.camera.FormatStorag" - "eResponse\"\000\022d\n\rResetSettings\022\'.mavsdk.rp" - "c.camera.ResetSettingsRequest\032(.mavsdk.r" - "pc.camera.ResetSettingsResponse\"\000\022^\n\013Zoo" - "mInStart\022%.mavsdk.rpc.camera.ZoomInStart" - "Request\032&.mavsdk.rpc.camera.ZoomInStartR" - "esponse\"\000\022a\n\014ZoomOutStart\022&.mavsdk.rpc.c" - "amera.ZoomOutStartRequest\032\'.mavsdk.rpc.c" - "amera.ZoomOutStartResponse\"\000\022U\n\010ZoomStop" - "\022\".mavsdk.rpc.camera.ZoomStopRequest\032#.m" - "avsdk.rpc.camera.ZoomStopResponse\"\000\022X\n\tZ" - "oomRange\022#.mavsdk.rpc.camera.ZoomRangeRe" - "quest\032$.mavsdk.rpc.camera.ZoomRangeRespo" - "nse\"\000\022[\n\nTrackPoint\022$.mavsdk.rpc.camera." - "TrackPointRequest\032%.mavsdk.rpc.camera.Tr" - "ackPointResponse\"\000\022g\n\016TrackRectangle\022(.m" - "avsdk.rpc.camera.TrackRectangleRequest\032)" - ".mavsdk.rpc.camera.TrackRectangleRespons" - "e\"\000\022X\n\tTrackStop\022#.mavsdk.rpc.camera.Tra" - "ckStopRequest\032$.mavsdk.rpc.camera.TrackS" - "topResponse\"\000\022a\n\014FocusInStart\022&.mavsdk.r" - "pc.camera.FocusInStartRequest\032\'.mavsdk.r" - "pc.camera.FocusInStartResponse\"\000\022d\n\rFocu" - "sOutStart\022\'.mavsdk.rpc.camera.FocusOutSt" - "artRequest\032(.mavsdk.rpc.camera.FocusOutS" - "tartResponse\"\000\022X\n\tFocusStop\022#.mavsdk.rpc" - ".camera.FocusStopRequest\032$.mavsdk.rpc.ca" - "mera.FocusStopResponse\"\000\022[\n\nFocusRange\022$" - ".mavsdk.rpc.camera.FocusRangeRequest\032%.m" - "avsdk.rpc.camera.FocusRangeResponse\"\000B\037\n" - "\020io.mavsdk.cameraB\013CameraProtob\006proto3" + "CAMERA_ID_INVALID\020\014\022\035\n\031RESULT_ACTION_UNS" + "UPPORTED\020\r\"q\n\010Position\022\024\n\014latitude_deg\030\001" + " \001(\001\022\025\n\rlongitude_deg\030\002 \001(\001\022\033\n\023absolute_" + "altitude_m\030\003 \001(\002\022\033\n\023relative_altitude_m\030" + "\004 \001(\002\"8\n\nQuaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001(" + "\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"B\n\nEulerAngle\022\020\n" + "\010roll_deg\030\001 \001(\002\022\021\n\tpitch_deg\030\002 \001(\002\022\017\n\007ya" + "w_deg\030\003 \001(\002\"\377\001\n\013CaptureInfo\022-\n\010position\030" + "\001 \001(\0132\033.mavsdk.rpc.camera.Position\022:\n\023at" + "titude_quaternion\030\002 \001(\0132\035.mavsdk.rpc.cam" + "era.Quaternion\022;\n\024attitude_euler_angle\030\003" + " \001(\0132\035.mavsdk.rpc.camera.EulerAngle\022\023\n\013t" + "ime_utc_us\030\004 \001(\004\022\022\n\nis_success\030\005 \001(\010\022\r\n\005" + "index\030\006 \001(\005\022\020\n\010file_url\030\007 \001(\t\"\305\001\n\023VideoS" + "treamSettings\022\025\n\rframe_rate_hz\030\001 \001(\002\022!\n\031" + "horizontal_resolution_pix\030\002 \001(\r\022\037\n\027verti" + "cal_resolution_pix\030\003 \001(\r\022\024\n\014bit_rate_b_s" + "\030\004 \001(\r\022\024\n\014rotation_deg\030\005 \001(\r\022\013\n\003uri\030\006 \001(" + "\t\022\032\n\022horizontal_fov_deg\030\007 \001(\002\"\325\003\n\017VideoS" + "treamInfo\022\021\n\tcamera_id\030\001 \001(\005\0228\n\010settings" + "\030\002 \001(\0132&.mavsdk.rpc.camera.VideoStreamSe" + "ttings\022D\n\006status\030\003 \001(\01624.mavsdk.rpc.came" + "ra.VideoStreamInfo.VideoStreamStatus\022H\n\010" + "spectrum\030\004 \001(\01626.mavsdk.rpc.camera.Video" + "StreamInfo.VideoStreamSpectrum\"]\n\021VideoS" + "treamStatus\022#\n\037VIDEO_STREAM_STATUS_NOT_R" + "UNNING\020\000\022#\n\037VIDEO_STREAM_STATUS_IN_PROGR" + "ESS\020\001\"\205\001\n\023VideoStreamSpectrum\022!\n\035VIDEO_S" + "TREAM_SPECTRUM_UNKNOWN\020\000\022\'\n#VIDEO_STREAM" + "_SPECTRUM_VISIBLE_LIGHT\020\001\022\"\n\036VIDEO_STREA" + "M_SPECTRUM_INFRARED\020\002\"\232\005\n\006Status\022\021\n\tcame" + "ra_id\030\001 \001(\005\022\020\n\010video_on\030\002 \001(\010\022\031\n\021photo_i" + "nterval_on\030\003 \001(\010\022\030\n\020used_storage_mib\030\004 \001" + "(\002\022\035\n\025available_storage_mib\030\005 \001(\002\022\031\n\021tot" + "al_storage_mib\030\006 \001(\002\022\030\n\020recording_time_s" + "\030\007 \001(\002\022\031\n\021media_folder_name\030\010 \001(\t\022\?\n\016sto" + "rage_status\030\t \001(\0162\'.mavsdk.rpc.camera.St" + "atus.StorageStatus\022\022\n\nstorage_id\030\n \001(\r\022;" + "\n\014storage_type\030\013 \001(\0162%.mavsdk.rpc.camera" + ".Status.StorageType\"\221\001\n\rStorageStatus\022 \n" + "\034STORAGE_STATUS_NOT_AVAILABLE\020\000\022\036\n\032STORA" + "GE_STATUS_UNFORMATTED\020\001\022\034\n\030STORAGE_STATU" + "S_FORMATTED\020\002\022 \n\034STORAGE_STATUS_NOT_SUPP" + "ORTED\020\003\"\240\001\n\013StorageType\022\030\n\024STORAGE_TYPE_" + "UNKNOWN\020\000\022\032\n\026STORAGE_TYPE_USB_STICK\020\001\022\023\n" + "\017STORAGE_TYPE_SD\020\002\022\030\n\024STORAGE_TYPE_MICRO" + "SD\020\003\022\023\n\017STORAGE_TYPE_HD\020\007\022\027\n\022STORAGE_TYP" + "E_OTHER\020\376\001\"7\n\006Option\022\021\n\toption_id\030\001 \001(\t\022" + "\032\n\022option_description\030\002 \001(\t\"w\n\007Setting\022\022" + "\n\nsetting_id\030\001 \001(\t\022\033\n\023setting_descriptio" + "n\030\002 \001(\t\022)\n\006option\030\003 \001(\0132\031.mavsdk.rpc.cam" + "era.Option\022\020\n\010is_range\030\004 \001(\010\"\222\001\n\016Setting" + "Options\022\021\n\tcamera_id\030\001 \001(\005\022\022\n\nsetting_id" + "\030\002 \001(\t\022\033\n\023setting_description\030\003 \001(\t\022*\n\007o" + "ptions\030\004 \003(\0132\031.mavsdk.rpc.camera.Option\022" + "\020\n\010is_range\030\005 \001(\010\"\325\001\n\013Information\022\023\n\013ven" + "dor_name\030\001 \001(\t\022\022\n\nmodel_name\030\002 \001(\t\022\027\n\017fo" + "cal_length_mm\030\003 \001(\002\022!\n\031horizontal_sensor" + "_size_mm\030\004 \001(\002\022\037\n\027vertical_sensor_size_m" + "m\030\005 \001(\002\022 \n\030horizontal_resolution_px\030\006 \001(" + "\r\022\036\n\026vertical_resolution_px\030\007 \001(\r\"=\n\nCam" + "eraList\022/\n\007cameras\030\001 \003(\0132\036.mavsdk.rpc.ca" + "mera.Information*8\n\004Mode\022\020\n\014MODE_UNKNOWN" + "\020\000\022\016\n\nMODE_PHOTO\020\001\022\016\n\nMODE_VIDEO\020\002*F\n\013Ph" + "otosRange\022\024\n\020PHOTOS_RANGE_ALL\020\000\022!\n\035PHOTO" + "S_RANGE_SINCE_CONNECTION\020\0012\327\035\n\rCameraSer" + "vice\022X\n\tTakePhoto\022#.mavsdk.rpc.camera.Ta" + "kePhotoRequest\032$.mavsdk.rpc.camera.TakeP" + "hotoResponse\"\000\022s\n\022StartPhotoInterval\022,.m" + "avsdk.rpc.camera.StartPhotoIntervalReque" + "st\032-.mavsdk.rpc.camera.StartPhotoInterva" + "lResponse\"\000\022p\n\021StopPhotoInterval\022+.mavsd" + "k.rpc.camera.StopPhotoIntervalRequest\032,." + "mavsdk.rpc.camera.StopPhotoIntervalRespo" + "nse\"\000\022[\n\nStartVideo\022$.mavsdk.rpc.camera." + "StartVideoRequest\032%.mavsdk.rpc.camera.St" + "artVideoResponse\"\000\022X\n\tStopVideo\022#.mavsdk" + ".rpc.camera.StopVideoRequest\032$.mavsdk.rp" + "c.camera.StopVideoResponse\"\000\022z\n\023StartVid" + "eoStreaming\022-.mavsdk.rpc.camera.StartVid" + "eoStreamingRequest\032..mavsdk.rpc.camera.S" + "tartVideoStreamingResponse\"\004\200\265\030\001\022w\n\022Stop" + "VideoStreaming\022,.mavsdk.rpc.camera.StopV" + "ideoStreamingRequest\032-.mavsdk.rpc.camera" + ".StopVideoStreamingResponse\"\004\200\265\030\001\022R\n\007Set" + "Mode\022!.mavsdk.rpc.camera.SetModeRequest\032" + "\".mavsdk.rpc.camera.SetModeResponse\"\000\022[\n" + "\nListPhotos\022$.mavsdk.rpc.camera.ListPhot" + "osRequest\032%.mavsdk.rpc.camera.ListPhotos" + "Response\"\000\022o\n\023SubscribeCameraList\022-.mavs" + "dk.rpc.camera.SubscribeCameraListRequest" + "\032%.mavsdk.rpc.camera.CameraListResponse\"" + "\0000\001\022a\n\rSubscribeMode\022\'.mavsdk.rpc.camera" + ".SubscribeModeRequest\032\037.mavsdk.rpc.camer" + "a.ModeResponse\"\004\200\265\030\0000\001\022V\n\007GetMode\022!.mavs" + "dk.rpc.camera.GetModeRequest\032\".mavsdk.rp" + "c.camera.GetModeResponse\"\004\200\265\030\001\022\202\001\n\030Subsc" + "ribeVideoStreamInfo\0222.mavsdk.rpc.camera." + "SubscribeVideoStreamInfoRequest\032*.mavsdk" + ".rpc.camera.VideoStreamInfoResponse\"\004\200\265\030" + "\0000\001\022w\n\022GetVideoStreamInfo\022,.mavsdk.rpc.c" + "amera.GetVideoStreamInfoRequest\032-.mavsdk" + ".rpc.camera.GetVideoStreamInfoResponse\"\004" + "\200\265\030\001\022v\n\024SubscribeCaptureInfo\022..mavsdk.rp" + "c.camera.SubscribeCaptureInfoRequest\032&.m" + "avsdk.rpc.camera.CaptureInfoResponse\"\004\200\265" + "\030\0000\001\022g\n\017SubscribeStatus\022).mavsdk.rpc.cam" + "era.SubscribeStatusRequest\032!.mavsdk.rpc." + "camera.StatusResponse\"\004\200\265\030\0000\001\022\\\n\tGetStat" + "us\022#.mavsdk.rpc.camera.GetStatusRequest\032" + "$.mavsdk.rpc.camera.GetStatusResponse\"\004\200" + "\265\030\001\022\202\001\n\030SubscribeCurrentSettings\0222.mavsd" + "k.rpc.camera.SubscribeCurrentSettingsReq" + "uest\032*.mavsdk.rpc.camera.CurrentSettings" + "Response\"\004\200\265\030\0000\001\022w\n\022GetCurrentSettings\022," + ".mavsdk.rpc.camera.GetCurrentSettingsReq" + "uest\032-.mavsdk.rpc.camera.GetCurrentSetti" + "ngsResponse\"\004\200\265\030\001\022\227\001\n\037SubscribePossibleS" + "ettingOptions\0229.mavsdk.rpc.camera.Subscr" + "ibePossibleSettingOptionsRequest\0321.mavsd" + "k.rpc.camera.PossibleSettingOptionsRespo" + "nse\"\004\200\265\030\0000\001\022\214\001\n\031GetPossibleSettingOption" + "s\0223.mavsdk.rpc.camera.GetPossibleSetting" + "OptionsRequest\0324.mavsdk.rpc.camera.GetPo" + "ssibleSettingOptionsResponse\"\004\200\265\030\001\022[\n\nSe" + "tSetting\022$.mavsdk.rpc.camera.SetSettingR" + "equest\032%.mavsdk.rpc.camera.SetSettingRes" + "ponse\"\000\022[\n\nGetSetting\022$.mavsdk.rpc.camer" + "a.GetSettingRequest\032%.mavsdk.rpc.camera." + "GetSettingResponse\"\000\022d\n\rFormatStorage\022\'." + "mavsdk.rpc.camera.FormatStorageRequest\032(" + ".mavsdk.rpc.camera.FormatStorageResponse" + "\"\000\022d\n\rResetSettings\022\'.mavsdk.rpc.camera." + "ResetSettingsRequest\032(.mavsdk.rpc.camera" + ".ResetSettingsResponse\"\000\022^\n\013ZoomInStart\022" + "%.mavsdk.rpc.camera.ZoomInStartRequest\032&" + ".mavsdk.rpc.camera.ZoomInStartResponse\"\000" + "\022a\n\014ZoomOutStart\022&.mavsdk.rpc.camera.Zoo" + "mOutStartRequest\032\'.mavsdk.rpc.camera.Zoo" + "mOutStartResponse\"\000\022U\n\010ZoomStop\022\".mavsdk" + ".rpc.camera.ZoomStopRequest\032#.mavsdk.rpc" + ".camera.ZoomStopResponse\"\000\022X\n\tZoomRange\022" + "#.mavsdk.rpc.camera.ZoomRangeRequest\032$.m" + "avsdk.rpc.camera.ZoomRangeResponse\"\000\022[\n\n" + "TrackPoint\022$.mavsdk.rpc.camera.TrackPoin" + "tRequest\032%.mavsdk.rpc.camera.TrackPointR" + "esponse\"\000\022g\n\016TrackRectangle\022(.mavsdk.rpc" + ".camera.TrackRectangleRequest\032).mavsdk.r" + "pc.camera.TrackRectangleResponse\"\000\022X\n\tTr" + "ackStop\022#.mavsdk.rpc.camera.TrackStopReq" + "uest\032$.mavsdk.rpc.camera.TrackStopRespon" + "se\"\000\022a\n\014FocusInStart\022&.mavsdk.rpc.camera" + ".FocusInStartRequest\032\'.mavsdk.rpc.camera" + ".FocusInStartResponse\"\000\022d\n\rFocusOutStart" + "\022\'.mavsdk.rpc.camera.FocusOutStartReques" + "t\032(.mavsdk.rpc.camera.FocusOutStartRespo" + "nse\"\000\022X\n\tFocusStop\022#.mavsdk.rpc.camera.F" + "ocusStopRequest\032$.mavsdk.rpc.camera.Focu" + "sStopResponse\"\000\022[\n\nFocusRange\022$.mavsdk.r" + "pc.camera.FocusRangeRequest\032%.mavsdk.rpc" + ".camera.FocusRangeResponse\"\000B\037\n\020io.mavsd" + "k.cameraB\013CameraProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_camera_2fcamera_2eproto_deps[1] = { @@ -3092,7 +3093,7 @@ static ::absl::once_flag descriptor_table_camera_2fcamera_2eproto_once; const ::_pbi::DescriptorTable descriptor_table_camera_2fcamera_2eproto = { false, false, - 11918, + 11949, descriptor_table_protodef_camera_2fcamera_2eproto, "camera/camera.proto", &descriptor_table_camera_2fcamera_2eproto_once, @@ -3132,9 +3133,9 @@ const ::google::protobuf::EnumDescriptor* CameraResult_Result_descriptor() { return file_level_enum_descriptors_camera_2fcamera_2eproto[0]; } PROTOBUF_CONSTINIT const uint32_t CameraResult_Result_internal_data_[] = { - 851968u, 0u, }; + 917504u, 0u, }; bool CameraResult_Result_IsValid(int value) { - return 0 <= value && value <= 12; + return 0 <= value && value <= 13; } #if (__cplusplus < 201703) && \ (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) @@ -3152,6 +3153,7 @@ constexpr CameraResult_Result CameraResult::RESULT_PROTOCOL_UNSUPPORTED; constexpr CameraResult_Result CameraResult::RESULT_SETTINGS_UNAVAILABLE; constexpr CameraResult_Result CameraResult::RESULT_SETTINGS_LOADING; constexpr CameraResult_Result CameraResult::RESULT_CAMERA_ID_INVALID; +constexpr CameraResult_Result CameraResult::RESULT_ACTION_UNSUPPORTED; constexpr CameraResult_Result CameraResult::Result_MIN; constexpr CameraResult_Result CameraResult::Result_MAX; constexpr int CameraResult::Result_ARRAYSIZE; diff --git a/src/mavsdk_server/src/generated/camera/camera.pb.h b/src/mavsdk_server/src/generated/camera/camera.pb.h index f1efbff81..5d3effc89 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.h +++ b/src/mavsdk_server/src/generated/camera/camera.pb.h @@ -344,6 +344,7 @@ enum CameraResult_Result : int { CameraResult_Result_RESULT_SETTINGS_UNAVAILABLE = 10, CameraResult_Result_RESULT_SETTINGS_LOADING = 11, CameraResult_Result_RESULT_CAMERA_ID_INVALID = 12, + CameraResult_Result_RESULT_ACTION_UNSUPPORTED = 13, CameraResult_Result_CameraResult_Result_INT_MIN_SENTINEL_DO_NOT_USE_ = std::numeric_limits<::int32_t>::min(), CameraResult_Result_CameraResult_Result_INT_MAX_SENTINEL_DO_NOT_USE_ = @@ -353,8 +354,8 @@ enum CameraResult_Result : int { bool CameraResult_Result_IsValid(int value); extern const uint32_t CameraResult_Result_internal_data_[]; constexpr CameraResult_Result CameraResult_Result_Result_MIN = static_cast(0); -constexpr CameraResult_Result CameraResult_Result_Result_MAX = static_cast(12); -constexpr int CameraResult_Result_Result_ARRAYSIZE = 12 + 1; +constexpr CameraResult_Result CameraResult_Result_Result_MAX = static_cast(13); +constexpr int CameraResult_Result_Result_ARRAYSIZE = 13 + 1; const ::google::protobuf::EnumDescriptor* CameraResult_Result_descriptor(); template @@ -367,7 +368,7 @@ const std::string& CameraResult_Result_Name(T value) { template <> inline const std::string& CameraResult_Result_Name(CameraResult_Result value) { return ::google::protobuf::internal::NameOfDenseEnum( + 0, 13>( static_cast(value)); } inline bool CameraResult_Result_Parse(absl::string_view name, CameraResult_Result* value) { @@ -8621,6 +8622,7 @@ class CameraResult final : static constexpr Result RESULT_SETTINGS_UNAVAILABLE = CameraResult_Result_RESULT_SETTINGS_UNAVAILABLE; static constexpr Result RESULT_SETTINGS_LOADING = CameraResult_Result_RESULT_SETTINGS_LOADING; static constexpr Result RESULT_CAMERA_ID_INVALID = CameraResult_Result_RESULT_CAMERA_ID_INVALID; + static constexpr Result RESULT_ACTION_UNSUPPORTED = CameraResult_Result_RESULT_ACTION_UNSUPPORTED; static inline bool Result_IsValid(int value) { return CameraResult_Result_IsValid(value); } diff --git a/src/mavsdk_server/src/plugins/camera/camera_service_impl.h b/src/mavsdk_server/src/plugins/camera/camera_service_impl.h index 0e5054ae2..a087d8818 100644 --- a/src/mavsdk_server/src/plugins/camera/camera_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera/camera_service_impl.h @@ -156,6 +156,8 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { return rpc::camera::CameraResult_Result_RESULT_SETTINGS_LOADING; case mavsdk::Camera::Result::CameraIdInvalid: return rpc::camera::CameraResult_Result_RESULT_CAMERA_ID_INVALID; + case mavsdk::Camera::Result::ActionUnsupported: + return rpc::camera::CameraResult_Result_RESULT_ACTION_UNSUPPORTED; } } @@ -192,6 +194,8 @@ class CameraServiceImpl final : public rpc::camera::CameraService::Service { return mavsdk::Camera::Result::SettingsLoading; case rpc::camera::CameraResult_Result_RESULT_CAMERA_ID_INVALID: return mavsdk::Camera::Result::CameraIdInvalid; + case rpc::camera::CameraResult_Result_RESULT_ACTION_UNSUPPORTED: + return mavsdk::Camera::Result::ActionUnsupported; } } diff --git a/src/system_tests/CMakeLists.txt b/src/system_tests/CMakeLists.txt index 5b51453e9..3fc2161e6 100644 --- a/src/system_tests/CMakeLists.txt +++ b/src/system_tests/CMakeLists.txt @@ -1,6 +1,7 @@ add_executable(system_tests_runner - #camera_take_photo.cpp + camera_take_photo.cpp camera_definition.cpp + camera_list_cameras.cpp component_metadata.cpp action_arm_disarm.cpp param_set_and_get.cpp diff --git a/src/system_tests/camera_definition.cpp b/src/system_tests/camera_definition.cpp index 472c58537..af5733e1c 100644 --- a/src/system_tests/camera_definition.cpp +++ b/src/system_tests/camera_definition.cpp @@ -38,7 +38,6 @@ TEST(SystemTest, CameraDefinition) auto handle = mavsdk_groundstation.subscribe_on_new_system([&]() { const auto system = mavsdk_groundstation.systems().back(); - LogInfo() << "Found system"; if (system->is_connected() && system->has_camera()) { std::call_once(flag, [&]() { prom.set_value(system); }); } diff --git a/src/system_tests/camera_list_cameras.cpp b/src/system_tests/camera_list_cameras.cpp new file mode 100644 index 000000000..020a82ae5 --- /dev/null +++ b/src/system_tests/camera_list_cameras.cpp @@ -0,0 +1,65 @@ +#include "mavsdk.h" +#include "plugins/camera/camera.h" +#include "plugins/camera_server/camera_server.h" +#include "log.h" +#include +#include +#include +#include + +using namespace mavsdk; + +TEST(SystemTest, CameraListCameras) +{ + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + + Mavsdk mavsdk_camera{Mavsdk::Configuration{Mavsdk::ComponentType::Camera}}; + + ASSERT_EQ( + mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:17000"), + ConnectionResult::Success); + ASSERT_EQ( + 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 = + "https://raw.githubusercontent.com/mavlink/MAVSDK/main/src/mavsdk/plugins/camera/e90_unit_test.xml"; + camera_server.set_information(information); + + auto prom = std::promise>(); + auto fut = prom.get_future(); + std::once_flag flag; + + auto handle = mavsdk_groundstation.subscribe_on_new_system([&]() { + const auto system = mavsdk_groundstation.systems().back(); + if (system->is_connected() && system->has_camera()) { + std::call_once(flag, [&]() { prom.set_value(system); }); + } + }); + + ASSERT_EQ(fut.wait_for(std::chrono::seconds(10)), std::future_status::ready); + mavsdk_groundstation.unsubscribe_on_new_system(handle); + auto system = fut.get(); + + auto camera = Camera{system}; + + 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)); + + 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 e10db9602..0325edb76 100644 --- a/src/system_tests/camera_take_photo.cpp +++ b/src/system_tests/camera_take_photo.cpp @@ -1,4 +1,4 @@ -include "mavsdk.h" +#include "mavsdk.h" #include "plugins/camera/camera.h" #include "plugins/camera_server/camera_server.h" #include "log.h" @@ -7,7 +7,7 @@ include "mavsdk.h" #include #include - using namespace mavsdk; +using namespace mavsdk; TEST(SystemTest, CameraTakePhoto) { @@ -15,8 +15,11 @@ TEST(SystemTest, CameraTakePhoto) Mavsdk mavsdk_camera{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); + ASSERT_EQ( + mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:17000"), + ConnectionResult::Success); + ASSERT_EQ( + mavsdk_camera.add_any_connection("udpout://127.0.0.1:17000"), ConnectionResult::Success); auto camera_server = CameraServer{mavsdk_camera.server_component()}; camera_server.subscribe_take_photo([&camera_server](int32_t index) { @@ -29,6 +32,11 @@ TEST(SystemTest, CameraTakePhoto) camera_server.respond_take_photo(CameraServer::CameraFeedback::Ok, info); }); + camera_server.subscribe_set_mode([&](CameraServer::Mode mode) { + LogInfo() << "Set mode to " << mode; + camera_server.respond_set_mode(CameraServer::CameraFeedback::Ok); + }); + auto prom = std::promise>(); auto fut = prom.get_future(); std::once_flag flag; @@ -45,10 +53,9 @@ TEST(SystemTest, CameraTakePhoto) auto system = fut.get(); auto camera = Camera{system}; - return; // We want to take the picture in photo mode. - // EXPECT_EQ(camera.set_mode(Camera::Mode::Photo), Camera::Result::Success); + EXPECT_EQ(camera.set_mode(0, Camera::Mode::Photo), Camera::Result::Success); auto received_captured_info_prom = std::promise{}; auto received_captured_info_fut = received_captured_info_prom.get_future(); @@ -61,7 +68,7 @@ TEST(SystemTest, CameraTakePhoto) received_captured_info_prom.set_value(); }); - EXPECT_EQ(camera.take_photo(), Camera::Result::Success); + EXPECT_EQ(camera.take_photo(0), Camera::Result::Success); ASSERT_EQ( received_captured_info_fut.wait_for(std::chrono::seconds(10)), std::future_status::ready); received_captured_info_fut.get();