From b9c359ffff0e4044a8625a5e172ed824c123a876 Mon Sep 17 00:00:00 2001 From: David Lechner Date: Thu, 17 Feb 2022 14:11:54 -0600 Subject: [PATCH] camera_server: implement additional information fields --- examples/camera_server/camera_server.cpp | 8 +- proto | 2 +- .../plugins/camera_server/camera_server.cpp | 10 +- .../camera_server/camera_server_impl.cpp | 71 ++++- .../camera_server/camera_server_impl.h | 2 + .../plugins/camera_server/camera_server.h | 18 +- .../camera_server/camera_server.grpc.pb.h | 24 +- .../camera_server/camera_server.pb.cc | 299 +++++++++++++----- .../camera_server/camera_server.pb.h | 216 ++++++++++++- .../camera_server_service_impl.h | 16 + 10 files changed, 545 insertions(+), 121 deletions(-) diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index c65e624376..19ba845b2c 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -83,9 +83,10 @@ int main(int argc, char** argv) // Finally call set_information() to "activate" the camera plugin. - camera_server->set_information({ + auto ret = camera_server->set_information({ .vendor_name = "MAVSDK", .model_name = "Example Camera Server", + .firmware_version = "1.0.0", .focal_length_mm = 3.0, .horizontal_sensor_size_mm = 3.68, .vertical_sensor_size_mm = 2.76, @@ -93,6 +94,11 @@ int main(int argc, char** argv) .vertical_resolution_px = 2464, }); + if (ret != CameraServer::Result::Success) { + std::cerr << "Failed to set camera info, exiting" << std::endl; + exit(1); + } + std::cout << "Connected to " << (system->is_standalone() ? "GCS" : "autopilot") << " system ID " << +system->get_system_id() << std::endl; } diff --git a/proto b/proto index 4b3f0573dd..dbb333e731 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 4b3f0573dddaf1de7efcc1efc76b1ec8e244d429 +Subproject commit dbb333e731ff411693b3e830d76e225ecbdc5e48 diff --git a/src/mavsdk/plugins/camera_server/camera_server.cpp b/src/mavsdk/plugins/camera_server/camera_server.cpp index d5e47cc2e5..80a18207f5 100644 --- a/src/mavsdk/plugins/camera_server/camera_server.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server.cpp @@ -50,6 +50,7 @@ CameraServer::Result CameraServer::respond_take_photo(CaptureInfo capture_info) bool operator==(const CameraServer::Information& lhs, const CameraServer::Information& rhs) { return (rhs.vendor_name == lhs.vendor_name) && (rhs.model_name == lhs.model_name) && + (rhs.firmware_version == lhs.firmware_version) && ((std::isnan(rhs.focal_length_mm) && std::isnan(lhs.focal_length_mm)) || rhs.focal_length_mm == lhs.focal_length_mm) && ((std::isnan(rhs.horizontal_sensor_size_mm) && @@ -58,7 +59,10 @@ bool operator==(const CameraServer::Information& lhs, const CameraServer::Inform ((std::isnan(rhs.vertical_sensor_size_mm) && std::isnan(lhs.vertical_sensor_size_mm)) || rhs.vertical_sensor_size_mm == lhs.vertical_sensor_size_mm) && (rhs.horizontal_resolution_px == lhs.horizontal_resolution_px) && - (rhs.vertical_resolution_px == lhs.vertical_resolution_px); + (rhs.vertical_resolution_px == lhs.vertical_resolution_px) && + (rhs.lens_id == lhs.lens_id) && + (rhs.definition_file_version == lhs.definition_file_version) && + (rhs.definition_file_uri == lhs.definition_file_uri); } std::ostream& operator<<(std::ostream& str, CameraServer::Information const& information) @@ -67,11 +71,15 @@ std::ostream& operator<<(std::ostream& str, CameraServer::Information const& inf str << "information:" << '\n' << "{\n"; str << " vendor_name: " << information.vendor_name << '\n'; str << " model_name: " << information.model_name << '\n'; + str << " firmware_version: " << information.firmware_version << '\n'; str << " focal_length_mm: " << information.focal_length_mm << '\n'; str << " horizontal_sensor_size_mm: " << information.horizontal_sensor_size_mm << '\n'; str << " vertical_sensor_size_mm: " << information.vertical_sensor_size_mm << '\n'; str << " horizontal_resolution_px: " << information.horizontal_resolution_px << '\n'; str << " vertical_resolution_px: " << information.vertical_resolution_px << '\n'; + str << " lens_id: " << information.lens_id << '\n'; + str << " definition_file_version: " << information.definition_file_version << '\n'; + str << " definition_file_uri: " << information.definition_file_uri << '\n'; str << '}'; return str; } diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp index ab10d5b010..e56b868138 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.cpp +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.cpp @@ -145,10 +145,66 @@ void CameraServerImpl::disable() stop_image_capture_interval(); } +/** + * Parses a firmware version string. + * + * The string must be in the format "...". + * + * @param [in] version_str The version string to be parsed. + * @return True if parsing was successful, otherwise false. + */ +bool CameraServerImpl::parse_version_string(std::string& version_str) +{ + uint32_t unused; + + return parse_version_string(version_str, unused); +} + +/** + * Parses a firmware version string. + * + * The string must be in the format "[.[.[.]]]". + * + * @param [in] version_str The version string to be parsed. + * @param [out] version Encoded version integer for passing to MAVSDK messages. + * @return True if parsing was successful, otherwise false. + */ +bool CameraServerImpl::parse_version_string(std::string& version_str, uint32_t& version) +{ + // empty string means no version + if (version_str.empty()) { + version = 0; + + return true; + } + + uint8_t major{}, minor{}, patch{}, dev{}; + + auto ret = sscanf(version_str.c_str(), "%hhu.%hhu.%hhu.%hhu", &major, &minor, &patch, &dev); + + if (ret == EOF) { + return false; + } + + // pack version according to MAVLINK spec + version = dev << 24 | patch << 16 | minor << 8 | major; + + return true; +} + CameraServer::Result CameraServerImpl::set_information(CameraServer::Information information) { + if (!parse_version_string(information.firmware_version)) { + LogDebug() << "incorrectly formatted firmware version string: " + << information.firmware_version; + return CameraServer::Result::WrongArgument; + } + + // TODO: validate information.definition_file_uri + _is_information_set = true; _information = information; + return CameraServer::Result::Success; } @@ -285,11 +341,10 @@ std::optional CameraServerImpl::process_camera_information_re // FIXME: why is this needed to prevent dropping messages? std::this_thread::sleep_for(std::chrono::milliseconds(100)); - // unsupported items - const uint32_t firmware_version = 0; - const uint8_t lens_id = 0; - const uint16_t camera_definition_version = 0; - auto camera_definition_uri = ""; + // It is safe to ignore the return value of parse_version_string() here + // since the string was already validated in set_information(). + uint32_t firmware_version; + parse_version_string(_information.firmware_version, firmware_version); // capability flags are determined by subscriptions uint32_t capability_flags{}; @@ -312,10 +367,10 @@ std::optional CameraServerImpl::process_camera_information_re _information.vertical_sensor_size_mm, _information.horizontal_resolution_px, _information.vertical_resolution_px, - lens_id, + _information.lens_id, capability_flags, - camera_definition_version, - camera_definition_uri); + _information.definition_file_version, + _information.definition_file_uri.c_str()); _parent->send_message(msg); LogDebug() << "sent info msg"; diff --git a/src/mavsdk/plugins/camera_server/camera_server_impl.h b/src/mavsdk/plugins/camera_server/camera_server_impl.h index 3c72cc7ef5..7bf452dded 100644 --- a/src/mavsdk/plugins/camera_server/camera_server_impl.h +++ b/src/mavsdk/plugins/camera_server/camera_server_impl.h @@ -49,6 +49,8 @@ class CameraServerImpl : public PluginImplBase { CameraServer::TakePhotoCallback _take_photo_callback{}; + bool parse_version_string(std::string& version_str); + bool parse_version_string(std::string& version_str, uint32_t& version); void start_image_capture_interval(float interval, int32_t count, int32_t index); void stop_image_capture_interval(); diff --git a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h index 259bd10975..4025bbc173 100644 --- a/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h +++ b/src/mavsdk/plugins/camera_server/include/plugins/camera_server/camera_server.h @@ -62,11 +62,18 @@ class CameraServer : public PluginBase { struct Information { std::string vendor_name{}; /**< @brief Name of the camera vendor */ std::string model_name{}; /**< @brief Name of the camera model */ + std::string firmware_version{}; /**< @brief Camera firmware version in + '...' format */ float focal_length_mm{}; /**< @brief Focal length */ float horizontal_sensor_size_mm{}; /**< @brief Horizontal sensor size */ float vertical_sensor_size_mm{}; /**< @brief Vertical sensor size */ uint32_t horizontal_resolution_px{}; /**< @brief Horizontal image resolution in pixels */ uint32_t vertical_resolution_px{}; /**< @brief Vertical image resolution in pixels */ + uint32_t lens_id{}; /**< @brief Lens ID */ + uint32_t + definition_file_version{}; /**< @brief Camera definition file version (iteration) */ + std::string + definition_file_uri{}; /**< @brief Camera definition URI (http or mavlink ftp) */ }; /** @@ -198,7 +205,8 @@ class CameraServer : public PluginBase { using ResultCallback = std::function; /** - * @brief Sets the camera information + * @brief Sets the camera information. This must be called as soon as the camera server is + * created. * * This function is blocking. * @@ -207,7 +215,8 @@ class CameraServer : public PluginBase { Result set_information(Information information) const; /** - * @brief Sets the camera capture status + * @brief Sets image capture in progress status flags. This should be set to true when the + * camera is busy taking a photo and false when it is done. * * This function is blocking. * @@ -222,12 +231,13 @@ class CameraServer : public PluginBase { using TakePhotoCallback = std::function; /** - * @brief Subscribe to single-image capture commands + * @brief Subscribe to image capture requests. Each request received should respond to using + * RespondTakePhoto. */ void subscribe_take_photo(TakePhotoCallback callback); /** - * @brief Respond to a single-image capture command. + * @brief Respond to an image capture request from SubscribeTakePhoto. * * This function is blocking. * diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h index a6cbce2438..1ada1bcd05 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.grpc.pb.h @@ -38,7 +38,7 @@ class CameraServerService final { class StubInterface { public: virtual ~StubInterface() {} - // Sets the camera information + // Sets the camera information. This must be called as soon as the camera server is created. virtual ::grpc::Status SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::mavsdk::rpc::camera_server::SetInformationResponse* response) = 0; std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>> AsyncSetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>>(AsyncSetInformationRaw(context, request, cq)); @@ -46,7 +46,7 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>> PrepareAsyncSetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInformationResponse>>(PrepareAsyncSetInformationRaw(context, request, cq)); } - // Sets the camera capture status + // Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done. virtual ::grpc::Status SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response) = 0; std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>> AsyncSetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>>(AsyncSetInProgressRaw(context, request, cq)); @@ -54,7 +54,7 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>> PrepareAsyncSetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::SetInProgressResponse>>(PrepareAsyncSetInProgressRaw(context, request, cq)); } - // Subscribe to single-image capture commands + // Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto. std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>> SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>>(SubscribeTakePhotoRaw(context, request)); } @@ -64,7 +64,7 @@ class CameraServerService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>> PrepareAsyncSubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::camera_server::TakePhotoResponse>>(PrepareAsyncSubscribeTakePhotoRaw(context, request, cq)); } - // Respond to a single-image capture command. + // Respond to an image capture request from SubscribeTakePhoto. virtual ::grpc::Status RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response) = 0; std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>> AsyncRespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::camera_server::RespondTakePhotoResponse>>(AsyncRespondTakePhotoRaw(context, request, cq)); @@ -75,15 +75,15 @@ class CameraServerService final { class async_interface { public: virtual ~async_interface() {} - // Sets the camera information + // Sets the camera information. This must be called as soon as the camera server is created. virtual void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, std::function) = 0; virtual void SetInformation(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // Sets the camera capture status + // Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done. virtual void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, std::function) = 0; virtual void SetInProgress(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; - // Subscribe to single-image capture commands + // Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto. virtual void SubscribeTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::camera_server::TakePhotoResponse>* reactor) = 0; - // Respond to a single-image capture command. + // Respond to an image capture request from SubscribeTakePhoto. virtual void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, std::function) = 0; virtual void RespondTakePhoto(::grpc::ClientContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; }; @@ -175,13 +175,13 @@ class CameraServerService final { public: Service(); virtual ~Service(); - // Sets the camera information + // Sets the camera information. This must be called as soon as the camera server is created. virtual ::grpc::Status SetInformation(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetInformationRequest* request, ::mavsdk::rpc::camera_server::SetInformationResponse* response); - // Sets the camera capture status + // Sets image capture in progress status flags. This should be set to true when the camera is busy taking a photo and false when it is done. virtual ::grpc::Status SetInProgress(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SetInProgressRequest* request, ::mavsdk::rpc::camera_server::SetInProgressResponse* response); - // Subscribe to single-image capture commands + // Subscribe to image capture requests. Each request received should respond to using RespondTakePhoto. virtual ::grpc::Status SubscribeTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::SubscribeTakePhotoRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::camera_server::TakePhotoResponse>* writer); - // Respond to a single-image capture command. + // Respond to an image capture request from SubscribeTakePhoto. virtual ::grpc::Status RespondTakePhoto(::grpc::ServerContext* context, const ::mavsdk::rpc::camera_server::RespondTakePhotoRequest* request, ::mavsdk::rpc::camera_server::RespondTakePhotoResponse* response); }; template diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc index 5cb1accb83..882e9d27f1 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.cc @@ -119,11 +119,15 @@ constexpr Information::Information( ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) : vendor_name_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) , model_name_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) + , firmware_version_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) + , definition_file_uri_(&::PROTOBUF_NAMESPACE_ID::internal::fixed_address_empty_string) , focal_length_mm_(0) , horizontal_sensor_size_mm_(0) , vertical_sensor_size_mm_(0) , horizontal_resolution_px_(0u) - , vertical_resolution_px_(0u){} + , vertical_resolution_px_(0u) + , lens_id_(0u) + , definition_file_version_(0u){} struct InformationDefaultTypeInternal { constexpr InformationDefaultTypeInternal() : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} @@ -257,11 +261,15 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_camera_5fserver_2fcamera_5fser ~0u, // no _weak_field_map_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, vendor_name_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, model_name_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, firmware_version_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, focal_length_mm_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, horizontal_sensor_size_mm_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, vertical_sensor_size_mm_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, horizontal_resolution_px_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, vertical_resolution_px_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, lens_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, definition_file_version_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Information, definition_file_uri_), ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera_server::Position, _internal_metadata_), ~0u, // no _extensions_ @@ -309,10 +317,10 @@ static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOB { 36, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoRequest)}, { 42, -1, sizeof(::mavsdk::rpc::camera_server::RespondTakePhotoResponse)}, { 48, -1, sizeof(::mavsdk::rpc::camera_server::Information)}, - { 60, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, - { 69, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, - { 78, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, - { 89, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, + { 64, -1, sizeof(::mavsdk::rpc::camera_server::Position)}, + { 73, -1, sizeof(::mavsdk::rpc::camera_server::Quaternion)}, + { 82, -1, sizeof(::mavsdk::rpc::camera_server::CaptureInfo)}, + { 93, -1, sizeof(::mavsdk::rpc::camera_server::CameraServerResult)}, }; static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = { @@ -350,51 +358,54 @@ const char descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto[] "\030\001 \001(\0132%.mavsdk.rpc.camera_server.Captur" "eInfo\"f\n\030RespondTakePhotoResponse\022J\n\024cam" "era_server_result\030\001 \001(\0132,.mavsdk.rpc.cam" - "era_server.CameraServerResult\"\325\001\n\013Inform" + "era_server.CameraServerResult\"\276\002\n\013Inform" "ation\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\031horiz" - "ontal_sensor_size_mm\030\004 \001(\002\022\037\n\027vertical_s" - "ensor_size_mm\030\005 \001(\002\022 \n\030horizontal_resolu" - "tion_px\030\006 \001(\r\022\036\n\026vertical_resolution_px\030" - "\007 \001(\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_altit" - "ude_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\001" - "y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"\320\001\n\013CaptureInfo\0224\n\010po" - "sition\030\001 \001(\0132\".mavsdk.rpc.camera_server." - "Position\022A\n\023attitude_quaternion\030\002 \001(\0132$." - "mavsdk.rpc.camera_server.Quaternion\022\023\n\013t" - "ime_utc_us\030\003 \001(\004\022\022\n\nis_success\030\004 \001(\010\022\r\n\005" - "index\030\005 \001(\005\022\020\n\010file_url\030\006 \001(\t\"\263\002\n\022Camera" - "ServerResult\022C\n\006result\030\001 \001(\01623.mavsdk.rp" - "c.camera_server.CameraServerResult.Resul" - "t\022\022\n\nresult_str\030\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESU" - "LT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\026\n\022RESU" - "LT_IN_PROGRESS\020\002\022\017\n\013RESULT_BUSY\020\003\022\021\n\rRES" - "ULT_DENIED\020\004\022\020\n\014RESULT_ERROR\020\005\022\022\n\016RESULT" - "_TIMEOUT\020\006\022\031\n\025RESULT_WRONG_ARGUMENT\020\007\022\024\n" - "\020RESULT_NO_SYSTEM\020\0102\211\004\n\023CameraServerServ" - "ice\022y\n\016SetInformation\022/.mavsdk.rpc.camer" - "a_server.SetInformationRequest\0320.mavsdk." - "rpc.camera_server.SetInformationResponse" - "\"\004\200\265\030\001\022v\n\rSetInProgress\022..mavsdk.rpc.cam" - "era_server.SetInProgressRequest\032/.mavsdk" - ".rpc.camera_server.SetInProgressResponse" - "\"\004\200\265\030\001\022~\n\022SubscribeTakePhoto\0223.mavsdk.rp" - "c.camera_server.SubscribeTakePhotoReques" - "t\032+.mavsdk.rpc.camera_server.TakePhotoRe" - "sponse\"\004\200\265\030\0000\001\022\177\n\020RespondTakePhoto\0221.mav" - "sdk.rpc.camera_server.RespondTakePhotoRe" - "quest\0322.mavsdk.rpc.camera_server.Respond" - "TakePhotoResponse\"\004\200\265\030\001B,\n\027io.mavsdk.cam" - "era_serverB\021CameraServerProtob\006proto3" + "\030\002 \001(\t\022\030\n\020firmware_version\030\003 \001(\t\022\027\n\017foca" + "l_length_mm\030\004 \001(\002\022!\n\031horizontal_sensor_s" + "ize_mm\030\005 \001(\002\022\037\n\027vertical_sensor_size_mm\030" + "\006 \001(\002\022 \n\030horizontal_resolution_px\030\007 \001(\r\022" + "\036\n\026vertical_resolution_px\030\010 \001(\r\022\017\n\007lens_" + "id\030\t \001(\r\022\037\n\027definition_file_version\030\n \001(" + "\r\022\033\n\023definition_file_uri\030\013 \001(\t\"q\n\010Positi" + "on\022\024\n\014latitude_deg\030\001 \001(\001\022\025\n\rlongitude_de" + "g\030\002 \001(\001\022\033\n\023absolute_altitude_m\030\003 \001(\002\022\033\n\023" + "relative_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\"\320\001\n\013CaptureInfo\0224\n\010position\030\001 \001(\0132\"." + "mavsdk.rpc.camera_server.Position\022A\n\023att" + "itude_quaternion\030\002 \001(\0132$.mavsdk.rpc.came" + "ra_server.Quaternion\022\023\n\013time_utc_us\030\003 \001(" + "\004\022\022\n\nis_success\030\004 \001(\010\022\r\n\005index\030\005 \001(\005\022\020\n\010" + "file_url\030\006 \001(\t\"\263\002\n\022CameraServerResult\022C\n" + "\006result\030\001 \001(\01623.mavsdk.rpc.camera_server" + ".CameraServerResult.Result\022\022\n\nresult_str" + "\030\002 \001(\t\"\303\001\n\006Result\022\022\n\016RESULT_UNKNOWN\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_DENIED\020\004\022\020\n" + "\014RESULT_ERROR\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\031\n\025R" + "ESULT_WRONG_ARGUMENT\020\007\022\024\n\020RESULT_NO_SYST" + "EM\020\0102\211\004\n\023CameraServerService\022y\n\016SetInfor" + "mation\022/.mavsdk.rpc.camera_server.SetInf" + "ormationRequest\0320.mavsdk.rpc.camera_serv" + "er.SetInformationResponse\"\004\200\265\030\001\022v\n\rSetIn" + "Progress\022..mavsdk.rpc.camera_server.SetI" + "nProgressRequest\032/.mavsdk.rpc.camera_ser" + "ver.SetInProgressResponse\"\004\200\265\030\001\022~\n\022Subsc" + "ribeTakePhoto\0223.mavsdk.rpc.camera_server" + ".SubscribeTakePhotoRequest\032+.mavsdk.rpc." + "camera_server.TakePhotoResponse\"\004\200\265\030\0000\001\022" + "\177\n\020RespondTakePhoto\0221.mavsdk.rpc.camera_" + "server.RespondTakePhotoRequest\0322.mavsdk." + "rpc.camera_server.RespondTakePhotoRespon" + "se\"\004\200\265\030\001B,\n\027io.mavsdk.camera_serverB\021Cam" + "eraServerProtob\006proto3" ; static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps[1] = { &::descriptor_table_mavsdk_5foptions_2eproto, }; static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once; const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto = { - false, false, 2237, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", + false, false, 2342, descriptor_table_protodef_camera_5fserver_2fcamera_5fserver_2eproto, "camera_server/camera_server.proto", &descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_once, descriptor_table_camera_5fserver_2fcamera_5fserver_2eproto_deps, 1, 13, schemas, file_default_instances, TableStruct_camera_5fserver_2fcamera_5fserver_2eproto::offsets, file_level_metadata_camera_5fserver_2fcamera_5fserver_2eproto, file_level_enum_descriptors_camera_5fserver_2fcamera_5fserver_2eproto, file_level_service_descriptors_camera_5fserver_2fcamera_5fserver_2eproto, @@ -2041,19 +2052,31 @@ Information::Information(const Information& from) model_name_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_model_name(), GetArenaForAllocation()); } + firmware_version_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + if (!from._internal_firmware_version().empty()) { + firmware_version_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_firmware_version(), + GetArenaForAllocation()); + } + definition_file_uri_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + if (!from._internal_definition_file_uri().empty()) { + definition_file_uri_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, from._internal_definition_file_uri(), + GetArenaForAllocation()); + } ::memcpy(&focal_length_mm_, &from.focal_length_mm_, - static_cast(reinterpret_cast(&vertical_resolution_px_) - - reinterpret_cast(&focal_length_mm_)) + sizeof(vertical_resolution_px_)); + static_cast(reinterpret_cast(&definition_file_version_) - + reinterpret_cast(&focal_length_mm_)) + sizeof(definition_file_version_)); // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.camera_server.Information) } inline void Information::SharedCtor() { vendor_name_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); model_name_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +firmware_version_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); +definition_file_uri_.UnsafeSetDefault(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); ::memset(reinterpret_cast(this) + static_cast( reinterpret_cast(&focal_length_mm_) - reinterpret_cast(this)), - 0, static_cast(reinterpret_cast(&vertical_resolution_px_) - - reinterpret_cast(&focal_length_mm_)) + sizeof(vertical_resolution_px_)); + 0, static_cast(reinterpret_cast(&definition_file_version_) - + reinterpret_cast(&focal_length_mm_)) + sizeof(definition_file_version_)); } Information::~Information() { @@ -2067,6 +2090,8 @@ inline void Information::SharedDtor() { GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); vendor_name_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); model_name_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + firmware_version_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); + definition_file_uri_.DestroyNoArena(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited()); } void Information::ArenaDtor(void* object) { @@ -2087,9 +2112,11 @@ void Information::Clear() { vendor_name_.ClearToEmpty(); model_name_.ClearToEmpty(); + firmware_version_.ClearToEmpty(); + definition_file_uri_.ClearToEmpty(); ::memset(&focal_length_mm_, 0, static_cast( - reinterpret_cast(&vertical_resolution_px_) - - reinterpret_cast(&focal_length_mm_)) + sizeof(vertical_resolution_px_)); + reinterpret_cast(&definition_file_version_) - + reinterpret_cast(&focal_length_mm_)) + sizeof(definition_file_version_)); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } @@ -2117,41 +2144,73 @@ const char* Information::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID CHK_(ptr); } else goto handle_unusual; continue; - // float focal_length_mm = 3; + // string firmware_version = 3; case 3: - if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 29)) { - focal_length_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); - ptr += sizeof(float); + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 26)) { + auto str = _internal_mutable_firmware_version(); + ptr = ::PROTOBUF_NAMESPACE_ID::internal::InlineGreedyStringParser(str, ptr, ctx); + CHK_(::PROTOBUF_NAMESPACE_ID::internal::VerifyUTF8(str, "mavsdk.rpc.camera_server.Information.firmware_version")); + CHK_(ptr); } else goto handle_unusual; continue; - // float horizontal_sensor_size_mm = 4; + // float focal_length_mm = 4; case 4: if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 37)) { - horizontal_sensor_size_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + focal_length_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); ptr += sizeof(float); } else goto handle_unusual; continue; - // float vertical_sensor_size_mm = 5; + // float horizontal_sensor_size_mm = 5; case 5: if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 45)) { - vertical_sensor_size_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + horizontal_sensor_size_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); ptr += sizeof(float); } else goto handle_unusual; continue; - // uint32 horizontal_resolution_px = 6; + // float vertical_sensor_size_mm = 6; case 6: - if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 48)) { - horizontal_resolution_px_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); - CHK_(ptr); + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 53)) { + vertical_sensor_size_mm_ = ::PROTOBUF_NAMESPACE_ID::internal::UnalignedLoad(ptr); + ptr += sizeof(float); } else goto handle_unusual; continue; - // uint32 vertical_resolution_px = 7; + // uint32 horizontal_resolution_px = 7; case 7: if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 56)) { + horizontal_resolution_px_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // uint32 vertical_resolution_px = 8; + case 8: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 64)) { vertical_resolution_px_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); CHK_(ptr); } else goto handle_unusual; continue; + // uint32 lens_id = 9; + case 9: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 72)) { + lens_id_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // uint32 definition_file_version = 10; + case 10: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 80)) { + definition_file_version_ = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint32(&ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; + // string definition_file_uri = 11; + case 11: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 90)) { + auto str = _internal_mutable_definition_file_uri(); + ptr = ::PROTOBUF_NAMESPACE_ID::internal::InlineGreedyStringParser(str, ptr, ctx); + CHK_(::PROTOBUF_NAMESPACE_ID::internal::VerifyUTF8(str, "mavsdk.rpc.camera_server.Information.definition_file_uri")); + CHK_(ptr); + } else goto handle_unusual; + continue; default: { handle_unusual: if ((tag == 0) || ((tag & 7) == 4)) { @@ -2201,34 +2260,66 @@ ::PROTOBUF_NAMESPACE_ID::uint8* Information::_InternalSerialize( 2, this->_internal_model_name(), target); } - // float focal_length_mm = 3; + // string firmware_version = 3; + if (!this->_internal_firmware_version().empty()) { + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + this->_internal_firmware_version().data(), static_cast(this->_internal_firmware_version().length()), + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, + "mavsdk.rpc.camera_server.Information.firmware_version"); + target = stream->WriteStringMaybeAliased( + 3, this->_internal_firmware_version(), target); + } + + // float focal_length_mm = 4; if (!(this->_internal_focal_length_mm() <= 0 && this->_internal_focal_length_mm() >= 0)) { target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(3, this->_internal_focal_length_mm(), target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(4, this->_internal_focal_length_mm(), target); } - // float horizontal_sensor_size_mm = 4; + // float horizontal_sensor_size_mm = 5; if (!(this->_internal_horizontal_sensor_size_mm() <= 0 && this->_internal_horizontal_sensor_size_mm() >= 0)) { target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(4, this->_internal_horizontal_sensor_size_mm(), target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(5, this->_internal_horizontal_sensor_size_mm(), target); } - // float vertical_sensor_size_mm = 5; + // float vertical_sensor_size_mm = 6; if (!(this->_internal_vertical_sensor_size_mm() <= 0 && this->_internal_vertical_sensor_size_mm() >= 0)) { target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(5, this->_internal_vertical_sensor_size_mm(), target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(6, this->_internal_vertical_sensor_size_mm(), target); } - // uint32 horizontal_resolution_px = 6; + // uint32 horizontal_resolution_px = 7; if (this->_internal_horizontal_resolution_px() != 0) { target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(6, this->_internal_horizontal_resolution_px(), target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(7, this->_internal_horizontal_resolution_px(), target); } - // uint32 vertical_resolution_px = 7; + // uint32 vertical_resolution_px = 8; if (this->_internal_vertical_resolution_px() != 0) { target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(7, this->_internal_vertical_resolution_px(), target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(8, this->_internal_vertical_resolution_px(), target); + } + + // uint32 lens_id = 9; + if (this->_internal_lens_id() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(9, this->_internal_lens_id(), target); + } + + // uint32 definition_file_version = 10; + if (this->_internal_definition_file_version() != 0) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteUInt32ToArray(10, this->_internal_definition_file_version(), target); + } + + // string definition_file_uri = 11; + if (!this->_internal_definition_file_uri().empty()) { + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::VerifyUtf8String( + this->_internal_definition_file_uri().data(), static_cast(this->_internal_definition_file_uri().length()), + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::SERIALIZE, + "mavsdk.rpc.camera_server.Information.definition_file_uri"); + target = stream->WriteStringMaybeAliased( + 11, this->_internal_definition_file_uri(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -2261,35 +2352,63 @@ size_t Information::ByteSizeLong() const { this->_internal_model_name()); } - // float focal_length_mm = 3; + // string firmware_version = 3; + if (!this->_internal_firmware_version().empty()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_firmware_version()); + } + + // string definition_file_uri = 11; + if (!this->_internal_definition_file_uri().empty()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::StringSize( + this->_internal_definition_file_uri()); + } + + // float focal_length_mm = 4; if (!(this->_internal_focal_length_mm() <= 0 && this->_internal_focal_length_mm() >= 0)) { total_size += 1 + 4; } - // float horizontal_sensor_size_mm = 4; + // float horizontal_sensor_size_mm = 5; if (!(this->_internal_horizontal_sensor_size_mm() <= 0 && this->_internal_horizontal_sensor_size_mm() >= 0)) { total_size += 1 + 4; } - // float vertical_sensor_size_mm = 5; + // float vertical_sensor_size_mm = 6; if (!(this->_internal_vertical_sensor_size_mm() <= 0 && this->_internal_vertical_sensor_size_mm() >= 0)) { total_size += 1 + 4; } - // uint32 horizontal_resolution_px = 6; + // uint32 horizontal_resolution_px = 7; if (this->_internal_horizontal_resolution_px() != 0) { total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size( this->_internal_horizontal_resolution_px()); } - // uint32 vertical_resolution_px = 7; + // uint32 vertical_resolution_px = 8; if (this->_internal_vertical_resolution_px() != 0) { total_size += 1 + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size( this->_internal_vertical_resolution_px()); } + // uint32 lens_id = 9; + if (this->_internal_lens_id() != 0) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size( + this->_internal_lens_id()); + } + + // uint32 definition_file_version = 10; + if (this->_internal_definition_file_version() != 0) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::UInt32Size( + this->_internal_definition_file_version()); + } + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( _internal_metadata_, total_size, &_cached_size_); @@ -2324,6 +2443,12 @@ void Information::MergeFrom(const Information& from) { if (!from._internal_model_name().empty()) { _internal_set_model_name(from._internal_model_name()); } + if (!from._internal_firmware_version().empty()) { + _internal_set_firmware_version(from._internal_firmware_version()); + } + if (!from._internal_definition_file_uri().empty()) { + _internal_set_definition_file_uri(from._internal_definition_file_uri()); + } if (!(from._internal_focal_length_mm() <= 0 && from._internal_focal_length_mm() >= 0)) { _internal_set_focal_length_mm(from._internal_focal_length_mm()); } @@ -2339,6 +2464,12 @@ void Information::MergeFrom(const Information& from) { if (from._internal_vertical_resolution_px() != 0) { _internal_set_vertical_resolution_px(from._internal_vertical_resolution_px()); } + if (from._internal_lens_id() != 0) { + _internal_set_lens_id(from._internal_lens_id()); + } + if (from._internal_definition_file_version() != 0) { + _internal_set_definition_file_version(from._internal_definition_file_version()); + } _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } @@ -2366,9 +2497,19 @@ void Information::InternalSwap(Information* other) { &model_name_, GetArenaForAllocation(), &other->model_name_, other->GetArenaForAllocation() ); + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::InternalSwap( + &::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), + &firmware_version_, GetArenaForAllocation(), + &other->firmware_version_, other->GetArenaForAllocation() + ); + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::InternalSwap( + &::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), + &definition_file_uri_, GetArenaForAllocation(), + &other->definition_file_uri_, other->GetArenaForAllocation() + ); ::PROTOBUF_NAMESPACE_ID::internal::memswap< - PROTOBUF_FIELD_OFFSET(Information, vertical_resolution_px_) - + sizeof(Information::vertical_resolution_px_) + PROTOBUF_FIELD_OFFSET(Information, definition_file_version_) + + sizeof(Information::definition_file_version_) - PROTOBUF_FIELD_OFFSET(Information, focal_length_mm_)>( reinterpret_cast(&focal_length_mm_), reinterpret_cast(&other->focal_length_mm_)); diff --git a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h index 6828a984e1..721d3bef45 100644 --- a/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h +++ b/src/mavsdk_server/src/generated/camera_server/camera_server.pb.h @@ -1434,11 +1434,15 @@ class Information final : enum : int { kVendorNameFieldNumber = 1, kModelNameFieldNumber = 2, - kFocalLengthMmFieldNumber = 3, - kHorizontalSensorSizeMmFieldNumber = 4, - kVerticalSensorSizeMmFieldNumber = 5, - kHorizontalResolutionPxFieldNumber = 6, - kVerticalResolutionPxFieldNumber = 7, + kFirmwareVersionFieldNumber = 3, + kDefinitionFileUriFieldNumber = 11, + kFocalLengthMmFieldNumber = 4, + kHorizontalSensorSizeMmFieldNumber = 5, + kVerticalSensorSizeMmFieldNumber = 6, + kHorizontalResolutionPxFieldNumber = 7, + kVerticalResolutionPxFieldNumber = 8, + kLensIdFieldNumber = 9, + kDefinitionFileVersionFieldNumber = 10, }; // string vendor_name = 1; void clear_vendor_name(); @@ -1468,7 +1472,35 @@ class Information final : std::string* _internal_mutable_model_name(); public: - // float focal_length_mm = 3; + // string firmware_version = 3; + void clear_firmware_version(); + const std::string& firmware_version() const; + template + void set_firmware_version(ArgT0&& arg0, ArgT... args); + std::string* mutable_firmware_version(); + PROTOBUF_MUST_USE_RESULT std::string* release_firmware_version(); + void set_allocated_firmware_version(std::string* firmware_version); + private: + const std::string& _internal_firmware_version() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_firmware_version(const std::string& value); + std::string* _internal_mutable_firmware_version(); + public: + + // string definition_file_uri = 11; + void clear_definition_file_uri(); + const std::string& definition_file_uri() const; + template + void set_definition_file_uri(ArgT0&& arg0, ArgT... args); + std::string* mutable_definition_file_uri(); + PROTOBUF_MUST_USE_RESULT std::string* release_definition_file_uri(); + void set_allocated_definition_file_uri(std::string* definition_file_uri); + private: + const std::string& _internal_definition_file_uri() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_definition_file_uri(const std::string& value); + std::string* _internal_mutable_definition_file_uri(); + public: + + // float focal_length_mm = 4; void clear_focal_length_mm(); float focal_length_mm() const; void set_focal_length_mm(float value); @@ -1477,7 +1509,7 @@ class Information final : void _internal_set_focal_length_mm(float value); public: - // float horizontal_sensor_size_mm = 4; + // float horizontal_sensor_size_mm = 5; void clear_horizontal_sensor_size_mm(); float horizontal_sensor_size_mm() const; void set_horizontal_sensor_size_mm(float value); @@ -1486,7 +1518,7 @@ class Information final : void _internal_set_horizontal_sensor_size_mm(float value); public: - // float vertical_sensor_size_mm = 5; + // float vertical_sensor_size_mm = 6; void clear_vertical_sensor_size_mm(); float vertical_sensor_size_mm() const; void set_vertical_sensor_size_mm(float value); @@ -1495,7 +1527,7 @@ class Information final : void _internal_set_vertical_sensor_size_mm(float value); public: - // uint32 horizontal_resolution_px = 6; + // uint32 horizontal_resolution_px = 7; void clear_horizontal_resolution_px(); ::PROTOBUF_NAMESPACE_ID::uint32 horizontal_resolution_px() const; void set_horizontal_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value); @@ -1504,7 +1536,7 @@ class Information final : void _internal_set_horizontal_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value); public: - // uint32 vertical_resolution_px = 7; + // uint32 vertical_resolution_px = 8; void clear_vertical_resolution_px(); ::PROTOBUF_NAMESPACE_ID::uint32 vertical_resolution_px() const; void set_vertical_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value); @@ -1513,6 +1545,24 @@ class Information final : void _internal_set_vertical_resolution_px(::PROTOBUF_NAMESPACE_ID::uint32 value); public: + // uint32 lens_id = 9; + void clear_lens_id(); + ::PROTOBUF_NAMESPACE_ID::uint32 lens_id() const; + void set_lens_id(::PROTOBUF_NAMESPACE_ID::uint32 value); + private: + ::PROTOBUF_NAMESPACE_ID::uint32 _internal_lens_id() const; + void _internal_set_lens_id(::PROTOBUF_NAMESPACE_ID::uint32 value); + public: + + // uint32 definition_file_version = 10; + void clear_definition_file_version(); + ::PROTOBUF_NAMESPACE_ID::uint32 definition_file_version() const; + void set_definition_file_version(::PROTOBUF_NAMESPACE_ID::uint32 value); + private: + ::PROTOBUF_NAMESPACE_ID::uint32 _internal_definition_file_version() const; + void _internal_set_definition_file_version(::PROTOBUF_NAMESPACE_ID::uint32 value); + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.camera_server.Information) private: class _Internal; @@ -1522,11 +1572,15 @@ class Information final : typedef void DestructorSkippable_; ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr vendor_name_; ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr model_name_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr firmware_version_; + ::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr definition_file_uri_; float focal_length_mm_; float horizontal_sensor_size_mm_; float vertical_sensor_size_mm_; ::PROTOBUF_NAMESPACE_ID::uint32 horizontal_resolution_px_; ::PROTOBUF_NAMESPACE_ID::uint32 vertical_resolution_px_; + ::PROTOBUF_NAMESPACE_ID::uint32 lens_id_; + ::PROTOBUF_NAMESPACE_ID::uint32 definition_file_version_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; friend struct ::TableStruct_camera_5fserver_2fcamera_5fserver_2eproto; }; @@ -3005,7 +3059,53 @@ inline void Information::set_allocated_model_name(std::string* model_name) { // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.Information.model_name) } -// float focal_length_mm = 3; +// string firmware_version = 3; +inline void Information::clear_firmware_version() { + firmware_version_.ClearToEmpty(); +} +inline const std::string& Information::firmware_version() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.firmware_version) + return _internal_firmware_version(); +} +template +inline PROTOBUF_ALWAYS_INLINE +void Information::set_firmware_version(ArgT0&& arg0, ArgT... args) { + + firmware_version_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, static_cast(arg0), args..., GetArenaForAllocation()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.firmware_version) +} +inline std::string* Information::mutable_firmware_version() { + std::string* _s = _internal_mutable_firmware_version(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.Information.firmware_version) + return _s; +} +inline const std::string& Information::_internal_firmware_version() const { + return firmware_version_.Get(); +} +inline void Information::_internal_set_firmware_version(const std::string& value) { + + firmware_version_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, value, GetArenaForAllocation()); +} +inline std::string* Information::_internal_mutable_firmware_version() { + + return firmware_version_.Mutable(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, GetArenaForAllocation()); +} +inline std::string* Information::release_firmware_version() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.Information.firmware_version) + return firmware_version_.Release(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArenaForAllocation()); +} +inline void Information::set_allocated_firmware_version(std::string* firmware_version) { + if (firmware_version != nullptr) { + + } else { + + } + firmware_version_.SetAllocated(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), firmware_version, + GetArenaForAllocation()); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.Information.firmware_version) +} + +// float focal_length_mm = 4; inline void Information::clear_focal_length_mm() { focal_length_mm_ = 0; } @@ -3025,7 +3125,7 @@ inline void Information::set_focal_length_mm(float value) { // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.focal_length_mm) } -// float horizontal_sensor_size_mm = 4; +// float horizontal_sensor_size_mm = 5; inline void Information::clear_horizontal_sensor_size_mm() { horizontal_sensor_size_mm_ = 0; } @@ -3045,7 +3145,7 @@ inline void Information::set_horizontal_sensor_size_mm(float value) { // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.horizontal_sensor_size_mm) } -// float vertical_sensor_size_mm = 5; +// float vertical_sensor_size_mm = 6; inline void Information::clear_vertical_sensor_size_mm() { vertical_sensor_size_mm_ = 0; } @@ -3065,7 +3165,7 @@ inline void Information::set_vertical_sensor_size_mm(float value) { // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.vertical_sensor_size_mm) } -// uint32 horizontal_resolution_px = 6; +// uint32 horizontal_resolution_px = 7; inline void Information::clear_horizontal_resolution_px() { horizontal_resolution_px_ = 0u; } @@ -3085,7 +3185,7 @@ inline void Information::set_horizontal_resolution_px(::PROTOBUF_NAMESPACE_ID::u // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.horizontal_resolution_px) } -// uint32 vertical_resolution_px = 7; +// uint32 vertical_resolution_px = 8; inline void Information::clear_vertical_resolution_px() { vertical_resolution_px_ = 0u; } @@ -3105,6 +3205,92 @@ inline void Information::set_vertical_resolution_px(::PROTOBUF_NAMESPACE_ID::uin // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.vertical_resolution_px) } +// uint32 lens_id = 9; +inline void Information::clear_lens_id() { + lens_id_ = 0u; +} +inline ::PROTOBUF_NAMESPACE_ID::uint32 Information::_internal_lens_id() const { + return lens_id_; +} +inline ::PROTOBUF_NAMESPACE_ID::uint32 Information::lens_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.lens_id) + return _internal_lens_id(); +} +inline void Information::_internal_set_lens_id(::PROTOBUF_NAMESPACE_ID::uint32 value) { + + lens_id_ = value; +} +inline void Information::set_lens_id(::PROTOBUF_NAMESPACE_ID::uint32 value) { + _internal_set_lens_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.lens_id) +} + +// uint32 definition_file_version = 10; +inline void Information::clear_definition_file_version() { + definition_file_version_ = 0u; +} +inline ::PROTOBUF_NAMESPACE_ID::uint32 Information::_internal_definition_file_version() const { + return definition_file_version_; +} +inline ::PROTOBUF_NAMESPACE_ID::uint32 Information::definition_file_version() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.definition_file_version) + return _internal_definition_file_version(); +} +inline void Information::_internal_set_definition_file_version(::PROTOBUF_NAMESPACE_ID::uint32 value) { + + definition_file_version_ = value; +} +inline void Information::set_definition_file_version(::PROTOBUF_NAMESPACE_ID::uint32 value) { + _internal_set_definition_file_version(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.definition_file_version) +} + +// string definition_file_uri = 11; +inline void Information::clear_definition_file_uri() { + definition_file_uri_.ClearToEmpty(); +} +inline const std::string& Information::definition_file_uri() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera_server.Information.definition_file_uri) + return _internal_definition_file_uri(); +} +template +inline PROTOBUF_ALWAYS_INLINE +void Information::set_definition_file_uri(ArgT0&& arg0, ArgT... args) { + + definition_file_uri_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, static_cast(arg0), args..., GetArenaForAllocation()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.camera_server.Information.definition_file_uri) +} +inline std::string* Information::mutable_definition_file_uri() { + std::string* _s = _internal_mutable_definition_file_uri(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera_server.Information.definition_file_uri) + return _s; +} +inline const std::string& Information::_internal_definition_file_uri() const { + return definition_file_uri_.Get(); +} +inline void Information::_internal_set_definition_file_uri(const std::string& value) { + + definition_file_uri_.Set(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, value, GetArenaForAllocation()); +} +inline std::string* Information::_internal_mutable_definition_file_uri() { + + return definition_file_uri_.Mutable(::PROTOBUF_NAMESPACE_ID::internal::ArenaStringPtr::EmptyDefault{}, GetArenaForAllocation()); +} +inline std::string* Information::release_definition_file_uri() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera_server.Information.definition_file_uri) + return definition_file_uri_.Release(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), GetArenaForAllocation()); +} +inline void Information::set_allocated_definition_file_uri(std::string* definition_file_uri) { + if (definition_file_uri != nullptr) { + + } else { + + } + definition_file_uri_.SetAllocated(&::PROTOBUF_NAMESPACE_ID::internal::GetEmptyStringAlreadyInited(), definition_file_uri, + GetArenaForAllocation()); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera_server.Information.definition_file_uri) +} + // ------------------------------------------------------------------- // Position diff --git a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h index 427d58a0e4..648e50da9a 100644 --- a/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/camera_server/camera_server_service_impl.h @@ -48,6 +48,8 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer rpc_obj->set_model_name(information.model_name); + rpc_obj->set_firmware_version(information.firmware_version); + rpc_obj->set_focal_length_mm(information.focal_length_mm); rpc_obj->set_horizontal_sensor_size_mm(information.horizontal_sensor_size_mm); @@ -58,6 +60,12 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer rpc_obj->set_vertical_resolution_px(information.vertical_resolution_px); + rpc_obj->set_lens_id(information.lens_id); + + rpc_obj->set_definition_file_version(information.definition_file_version); + + rpc_obj->set_definition_file_uri(information.definition_file_uri); + return rpc_obj; } @@ -70,6 +78,8 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer obj.model_name = information.model_name(); + obj.firmware_version = information.firmware_version(); + obj.focal_length_mm = information.focal_length_mm(); obj.horizontal_sensor_size_mm = information.horizontal_sensor_size_mm(); @@ -80,6 +90,12 @@ class CameraServerServiceImpl final : public rpc::camera_server::CameraServerSer obj.vertical_resolution_px = information.vertical_resolution_px(); + obj.lens_id = information.lens_id(); + + obj.definition_file_version = information.definition_file_version(); + + obj.definition_file_uri = information.definition_file_uri(); + return obj; }