diff --git a/src/mavsdk/plugins/mission_raw/include/plugins/mission_raw/mission_raw.h b/src/mavsdk/plugins/mission_raw/include/plugins/mission_raw/mission_raw.h index ce2c9ad8c5..e8fb26d5b5 100644 --- a/src/mavsdk/plugins/mission_raw/include/plugins/mission_raw/mission_raw.h +++ b/src/mavsdk/plugins/mission_raw/include/plugins/mission_raw/mission_raw.h @@ -124,7 +124,7 @@ class MissionRaw : public PluginBase { std::vector mission_items{}; /**< @brief Mission items */ std::vector geofence_items{}; /**< @brief Geofence items */ std::vector rally_items{}; /**< @brief Rally items */ - std::optional plannedHomePosition; + MissionItem planned_home_position{}; /**< @brief Planned home position */ }; /** diff --git a/src/mavsdk/plugins/mission_raw/mission_import.cpp b/src/mavsdk/plugins/mission_raw/mission_import.cpp index 08a82a6990..e3bf97c01c 100644 --- a/src/mavsdk/plugins/mission_raw/mission_import.cpp +++ b/src/mavsdk/plugins/mission_raw/mission_import.cpp @@ -30,7 +30,7 @@ MissionImport::parse_json(const std::string& raw_json, Sender::Autopilot autopil MissionRaw::MissionImportData import_data; import_data.mission_items = maybe_mission_items.first.value(); - import_data.plannedHomePosition = maybe_mission_items.second.value(); + import_data.planned_home_position = maybe_mission_items.second.value(); return {MissionRaw::Result::Success, import_data}; } @@ -48,7 +48,9 @@ bool MissionImport::check_overall_version(const Json::Value& root) return true; } -std::pair>, std::optional> +std::pair< + std::optional>, + std::optional> MissionImport::import_mission(const Json::Value& root, Sender::Autopilot autopilot) { // We need a mission part. @@ -134,9 +136,7 @@ MissionImport::import_mission(const Json::Value& root, Sender::Autopilot autopil // Add home position at 0 for ArduPilot if (autopilot == Sender::Autopilot::ArduPilot && home_item.has_value()) { - mission_items.insert( - mission_items.begin(), - home_item.value()); + mission_items.insert(mission_items.begin(), home_item.value()); } // Returning an empty vector is ok here if there were really no mission items. diff --git a/src/mavsdk/plugins/mission_raw/mission_import.h b/src/mavsdk/plugins/mission_raw/mission_import.h index 35f0b52b87..1a7eb1d052 100644 --- a/src/mavsdk/plugins/mission_raw/mission_import.h +++ b/src/mavsdk/plugins/mission_raw/mission_import.h @@ -16,7 +16,9 @@ class MissionImport { private: static bool check_overall_version(const Json::Value& root); - static std::pair>, std::optional> + static std::pair< + std::optional>, + std::optional> import_mission(const Json::Value& root, SystemImpl::Autopilot autopilot); static std::optional import_simple_mission_item(const Json::Value& json_item); diff --git a/src/mavsdk/plugins/mission_raw/mission_raw.cpp b/src/mavsdk/plugins/mission_raw/mission_raw.cpp index 0648f67e48..c5df448a81 100644 --- a/src/mavsdk/plugins/mission_raw/mission_raw.cpp +++ b/src/mavsdk/plugins/mission_raw/mission_raw.cpp @@ -170,7 +170,8 @@ std::ostream& operator<<(std::ostream& str, MissionRaw::MissionItem const& missi bool operator==(const MissionRaw::MissionImportData& lhs, const MissionRaw::MissionImportData& rhs) { return (rhs.mission_items == lhs.mission_items) && (rhs.geofence_items == lhs.geofence_items) && - (rhs.rally_items == lhs.rally_items); + (rhs.rally_items == lhs.rally_items) && + (rhs.planned_home_position == lhs.planned_home_position); } std::ostream& @@ -199,6 +200,7 @@ operator<<(std::ostream& str, MissionRaw::MissionImportData const& mission_impor str << *it; str << (it + 1 != mission_import_data.rally_items.end() ? ", " : "]\n"); } + str << " planned_home_position: " << mission_import_data.planned_home_position << '\n'; str << '}'; return str; } diff --git a/src/mavsdk_server/src/generated/mission_raw/mission_raw.pb.cc b/src/mavsdk_server/src/generated/mission_raw/mission_raw.pb.cc index db807b9a85..3620fe0314 100644 --- a/src/mavsdk_server/src/generated/mission_raw/mission_raw.pb.cc +++ b/src/mavsdk_server/src/generated/mission_raw/mission_raw.pb.cc @@ -318,7 +318,8 @@ constexpr MissionImportData::MissionImportData( ::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized) : mission_items_() , geofence_items_() - , rally_items_(){} + , rally_items_() + , planned_home_position_(nullptr){} struct MissionImportDataDefaultTypeInternal { constexpr MissionImportDataDefaultTypeInternal() : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} @@ -509,6 +510,7 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_mission_5fraw_2fmission_5fraw_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::mission_raw::MissionImportData, mission_items_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::mission_raw::MissionImportData, geofence_items_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::mission_raw::MissionImportData, rally_items_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::mission_raw::MissionImportData, planned_home_position_), ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::mission_raw::MissionRawResult, _internal_metadata_), ~0u, // no _extensions_ @@ -543,7 +545,7 @@ static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOB { 126, -1, sizeof(::mavsdk::rpc::mission_raw::MissionProgress)}, { 133, -1, sizeof(::mavsdk::rpc::mission_raw::MissionItem)}, { 151, -1, sizeof(::mavsdk::rpc::mission_raw::MissionImportData)}, - { 159, -1, sizeof(::mavsdk::rpc::mission_raw::MissionRawResult)}, + { 160, -1, sizeof(::mavsdk::rpc::mission_raw::MissionRawResult)}, }; static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = { @@ -624,67 +626,69 @@ const char descriptor_table_protodef_mission_5fraw_2fmission_5fraw_2eproto[] PRO "ocontinue\030\005 \001(\r\022\016\n\006param1\030\006 \001(\002\022\016\n\006param" "2\030\007 \001(\002\022\016\n\006param3\030\010 \001(\002\022\016\n\006param4\030\t \001(\002\022" "\t\n\001x\030\n \001(\005\022\t\n\001y\030\013 \001(\005\022\t\n\001z\030\014 \001(\002\022\024\n\014miss" - "ion_type\030\r \001(\r\"\306\001\n\021MissionImportData\022:\n\r" + "ion_type\030\r \001(\r\"\212\002\n\021MissionImportData\022:\n\r" "mission_items\030\001 \003(\0132#.mavsdk.rpc.mission" "_raw.MissionItem\022;\n\016geofence_items\030\002 \003(\013" "2#.mavsdk.rpc.mission_raw.MissionItem\0228\n" "\013rally_items\030\003 \003(\0132#.mavsdk.rpc.mission_" - "raw.MissionItem\"\310\003\n\020MissionRawResult\022\?\n\006" - "result\030\001 \001(\0162/.mavsdk.rpc.mission_raw.Mi" - "ssionRawResult.Result\022\022\n\nresult_str\030\002 \001(" - "\t\"\336\002\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESU" - "LT_SUCCESS\020\001\022\020\n\014RESULT_ERROR\020\002\022!\n\035RESULT" - "_TOO_MANY_MISSION_ITEMS\020\003\022\017\n\013RESULT_BUSY" - "\020\004\022\022\n\016RESULT_TIMEOUT\020\005\022\033\n\027RESULT_INVALID" - "_ARGUMENT\020\006\022\026\n\022RESULT_UNSUPPORTED\020\007\022\037\n\033R" - "ESULT_NO_MISSION_AVAILABLE\020\010\022\035\n\031RESULT_T" - "RANSFER_CANCELLED\020\t\022\"\n\036RESULT_FAILED_TO_" - "OPEN_QGC_PLAN\020\n\022#\n\037RESULT_FAILED_TO_PARS" - "E_QGC_PLAN\020\013\022\024\n\020RESULT_NO_SYSTEM\020\0142\223\013\n\021M" - "issionRawService\022n\n\rUploadMission\022,.mavs" - "dk.rpc.mission_raw.UploadMissionRequest\032" - "-.mavsdk.rpc.mission_raw.UploadMissionRe" - "sponse\"\000\022\204\001\n\023CancelMissionUpload\0222.mavsd" - "k.rpc.mission_raw.CancelMissionUploadReq" - "uest\0323.mavsdk.rpc.mission_raw.CancelMiss" - "ionUploadResponse\"\004\200\265\030\001\022t\n\017DownloadMissi" - "on\022..mavsdk.rpc.mission_raw.DownloadMiss" - "ionRequest\032/.mavsdk.rpc.mission_raw.Down" - "loadMissionResponse\"\000\022\212\001\n\025CancelMissionD" - "ownload\0224.mavsdk.rpc.mission_raw.CancelM" - "issionDownloadRequest\0325.mavsdk.rpc.missi" - "on_raw.CancelMissionDownloadResponse\"\004\200\265" - "\030\001\022k\n\014StartMission\022+.mavsdk.rpc.mission_" - "raw.StartMissionRequest\032,.mavsdk.rpc.mis" - "sion_raw.StartMissionResponse\"\000\022k\n\014Pause" - "Mission\022+.mavsdk.rpc.mission_raw.PauseMi" - "ssionRequest\032,.mavsdk.rpc.mission_raw.Pa" - "useMissionResponse\"\000\022k\n\014ClearMission\022+.m" - "avsdk.rpc.mission_raw.ClearMissionReques" - "t\032,.mavsdk.rpc.mission_raw.ClearMissionR" - "esponse\"\000\022\206\001\n\025SetCurrentMissionItem\0224.ma" - "vsdk.rpc.mission_raw.SetCurrentMissionIt" - "emRequest\0325.mavsdk.rpc.mission_raw.SetCu" - "rrentMissionItemResponse\"\000\022\210\001\n\030Subscribe" - "MissionProgress\0227.mavsdk.rpc.mission_raw" - ".SubscribeMissionProgressRequest\032/.mavsd" - "k.rpc.mission_raw.MissionProgressRespons" - "e\"\0000\001\022\211\001\n\027SubscribeMissionChanged\0226.mavs" - "dk.rpc.mission_raw.SubscribeMissionChang" - "edRequest\032..mavsdk.rpc.mission_raw.Missi" - "onChangedResponse\"\004\200\265\030\0000\001\022\234\001\n\033ImportQgro" - "undcontrolMission\022:.mavsdk.rpc.mission_r" - "aw.ImportQgroundcontrolMissionRequest\032;." - "mavsdk.rpc.mission_raw.ImportQgroundcont" - "rolMissionResponse\"\004\200\265\030\001B(\n\025io.mavsdk.mi" - "ssion_rawB\017MissionRawProtob\006proto3" + "raw.MissionItem\022B\n\025planned_home_position" + "\030\004 \001(\0132#.mavsdk.rpc.mission_raw.MissionI" + "tem\"\310\003\n\020MissionRawResult\022\?\n\006result\030\001 \001(\016" + "2/.mavsdk.rpc.mission_raw.MissionRawResu" + "lt.Result\022\022\n\nresult_str\030\002 \001(\t\"\336\002\n\006Result" + "\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001" + "\022\020\n\014RESULT_ERROR\020\002\022!\n\035RESULT_TOO_MANY_MI" + "SSION_ITEMS\020\003\022\017\n\013RESULT_BUSY\020\004\022\022\n\016RESULT" + "_TIMEOUT\020\005\022\033\n\027RESULT_INVALID_ARGUMENT\020\006\022" + "\026\n\022RESULT_UNSUPPORTED\020\007\022\037\n\033RESULT_NO_MIS" + "SION_AVAILABLE\020\010\022\035\n\031RESULT_TRANSFER_CANC" + "ELLED\020\t\022\"\n\036RESULT_FAILED_TO_OPEN_QGC_PLA" + "N\020\n\022#\n\037RESULT_FAILED_TO_PARSE_QGC_PLAN\020\013" + "\022\024\n\020RESULT_NO_SYSTEM\020\0142\223\013\n\021MissionRawSer" + "vice\022n\n\rUploadMission\022,.mavsdk.rpc.missi" + "on_raw.UploadMissionRequest\032-.mavsdk.rpc" + ".mission_raw.UploadMissionResponse\"\000\022\204\001\n" + "\023CancelMissionUpload\0222.mavsdk.rpc.missio" + "n_raw.CancelMissionUploadRequest\0323.mavsd" + "k.rpc.mission_raw.CancelMissionUploadRes" + "ponse\"\004\200\265\030\001\022t\n\017DownloadMission\022..mavsdk." + "rpc.mission_raw.DownloadMissionRequest\032/" + ".mavsdk.rpc.mission_raw.DownloadMissionR" + "esponse\"\000\022\212\001\n\025CancelMissionDownload\0224.ma" + "vsdk.rpc.mission_raw.CancelMissionDownlo" + "adRequest\0325.mavsdk.rpc.mission_raw.Cance" + "lMissionDownloadResponse\"\004\200\265\030\001\022k\n\014StartM" + "ission\022+.mavsdk.rpc.mission_raw.StartMis" + "sionRequest\032,.mavsdk.rpc.mission_raw.Sta" + "rtMissionResponse\"\000\022k\n\014PauseMission\022+.ma" + "vsdk.rpc.mission_raw.PauseMissionRequest" + "\032,.mavsdk.rpc.mission_raw.PauseMissionRe" + "sponse\"\000\022k\n\014ClearMission\022+.mavsdk.rpc.mi" + "ssion_raw.ClearMissionRequest\032,.mavsdk.r" + "pc.mission_raw.ClearMissionResponse\"\000\022\206\001" + "\n\025SetCurrentMissionItem\0224.mavsdk.rpc.mis" + "sion_raw.SetCurrentMissionItemRequest\0325." + "mavsdk.rpc.mission_raw.SetCurrentMission" + "ItemResponse\"\000\022\210\001\n\030SubscribeMissionProgr" + "ess\0227.mavsdk.rpc.mission_raw.SubscribeMi" + "ssionProgressRequest\032/.mavsdk.rpc.missio" + "n_raw.MissionProgressResponse\"\0000\001\022\211\001\n\027Su" + "bscribeMissionChanged\0226.mavsdk.rpc.missi" + "on_raw.SubscribeMissionChangedRequest\032.." + "mavsdk.rpc.mission_raw.MissionChangedRes" + "ponse\"\004\200\265\030\0000\001\022\234\001\n\033ImportQgroundcontrolMi" + "ssion\022:.mavsdk.rpc.mission_raw.ImportQgr" + "oundcontrolMissionRequest\032;.mavsdk.rpc.m" + "ission_raw.ImportQgroundcontrolMissionRe" + "sponse\"\004\200\265\030\001B(\n\025io.mavsdk.mission_rawB\017M" + "issionRawProtob\006proto3" ; static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_mission_5fraw_2fmission_5fraw_2eproto_deps[1] = { &::descriptor_table_mavsdk_5foptions_2eproto, }; static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_mission_5fraw_2fmission_5fraw_2eproto_once; const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_mission_5fraw_2fmission_5fraw_2eproto = { - false, false, 4074, descriptor_table_protodef_mission_5fraw_2fmission_5fraw_2eproto, "mission_raw/mission_raw.proto", + false, false, 4142, descriptor_table_protodef_mission_5fraw_2fmission_5fraw_2eproto, "mission_raw/mission_raw.proto", &descriptor_table_mission_5fraw_2fmission_5fraw_2eproto_once, descriptor_table_mission_5fraw_2fmission_5fraw_2eproto_deps, 1, 26, schemas, file_default_instances, TableStruct_mission_5fraw_2fmission_5fraw_2eproto::offsets, file_level_metadata_mission_5fraw_2fmission_5fraw_2eproto, file_level_enum_descriptors_mission_5fraw_2fmission_5fraw_2eproto, file_level_service_descriptors_mission_5fraw_2fmission_5fraw_2eproto, @@ -5491,8 +5495,13 @@ ::PROTOBUF_NAMESPACE_ID::Metadata MissionItem::GetMetadata() const { class MissionImportData::_Internal { public: + static const ::mavsdk::rpc::mission_raw::MissionItem& planned_home_position(const MissionImportData* msg); }; +const ::mavsdk::rpc::mission_raw::MissionItem& +MissionImportData::_Internal::planned_home_position(const MissionImportData* msg) { + return *msg->planned_home_position_; +} MissionImportData::MissionImportData(::PROTOBUF_NAMESPACE_ID::Arena* arena, bool is_message_owned) : ::PROTOBUF_NAMESPACE_ID::Message(arena, is_message_owned), @@ -5511,10 +5520,16 @@ MissionImportData::MissionImportData(const MissionImportData& from) geofence_items_(from.geofence_items_), rally_items_(from.rally_items_) { _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); + if (from._internal_has_planned_home_position()) { + planned_home_position_ = new ::mavsdk::rpc::mission_raw::MissionItem(*from.planned_home_position_); + } else { + planned_home_position_ = nullptr; + } // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.mission_raw.MissionImportData) } inline void MissionImportData::SharedCtor() { +planned_home_position_ = nullptr; } MissionImportData::~MissionImportData() { @@ -5526,6 +5541,7 @@ MissionImportData::~MissionImportData() { inline void MissionImportData::SharedDtor() { GOOGLE_DCHECK(GetArenaForAllocation() == nullptr); + if (this != internal_default_instance()) delete planned_home_position_; } void MissionImportData::ArenaDtor(void* object) { @@ -5547,6 +5563,10 @@ void MissionImportData::Clear() { mission_items_.Clear(); geofence_items_.Clear(); rally_items_.Clear(); + if (GetArenaForAllocation() == nullptr && planned_home_position_ != nullptr) { + delete planned_home_position_; + } + planned_home_position_ = nullptr; _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } @@ -5592,6 +5612,13 @@ const char* MissionImportData::_InternalParse(const char* ptr, ::PROTOBUF_NAMESP } while (::PROTOBUF_NAMESPACE_ID::internal::ExpectTag<26>(ptr)); } else goto handle_unusual; continue; + // .mavsdk.rpc.mission_raw.MissionItem planned_home_position = 4; + case 4: + if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 34)) { + ptr = ctx->ParseMessage(_internal_mutable_planned_home_position(), ptr); + CHK_(ptr); + } else goto handle_unusual; + continue; default: { handle_unusual: if ((tag == 0) || ((tag & 7) == 4)) { @@ -5645,6 +5672,14 @@ ::PROTOBUF_NAMESPACE_ID::uint8* MissionImportData::_InternalSerialize( InternalWriteMessage(3, this->_internal_rally_items(i), target, stream); } + // .mavsdk.rpc.mission_raw.MissionItem planned_home_position = 4; + if (this->_internal_has_planned_home_position()) { + target = stream->EnsureSpace(target); + target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite:: + InternalWriteMessage( + 4, _Internal::planned_home_position(this), target, stream); + } + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(::PROTOBUF_NAMESPACE_ID::UnknownFieldSet::default_instance), target, stream); @@ -5682,6 +5717,13 @@ size_t MissionImportData::ByteSizeLong() const { ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize(msg); } + // .mavsdk.rpc.mission_raw.MissionItem planned_home_position = 4; + if (this->_internal_has_planned_home_position()) { + total_size += 1 + + ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::MessageSize( + *planned_home_position_); + } + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( _internal_metadata_, total_size, &_cached_size_); @@ -5713,6 +5755,9 @@ void MissionImportData::MergeFrom(const MissionImportData& from) { mission_items_.MergeFrom(from.mission_items_); geofence_items_.MergeFrom(from.geofence_items_); rally_items_.MergeFrom(from.rally_items_); + if (from._internal_has_planned_home_position()) { + _internal_mutable_planned_home_position()->::mavsdk::rpc::mission_raw::MissionItem::MergeFrom(from._internal_planned_home_position()); + } _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); } @@ -5733,6 +5778,7 @@ void MissionImportData::InternalSwap(MissionImportData* other) { mission_items_.InternalSwap(&other->mission_items_); geofence_items_.InternalSwap(&other->geofence_items_); rally_items_.InternalSwap(&other->rally_items_); + swap(planned_home_position_, other->planned_home_position_); } ::PROTOBUF_NAMESPACE_ID::Metadata MissionImportData::GetMetadata() const { diff --git a/src/mavsdk_server/src/generated/mission_raw/mission_raw.pb.h b/src/mavsdk_server/src/generated/mission_raw/mission_raw.pb.h index 48a2544ec1..271ed1b9b9 100644 --- a/src/mavsdk_server/src/generated/mission_raw/mission_raw.pb.h +++ b/src/mavsdk_server/src/generated/mission_raw/mission_raw.pb.h @@ -3846,6 +3846,7 @@ class MissionImportData final : kMissionItemsFieldNumber = 1, kGeofenceItemsFieldNumber = 2, kRallyItemsFieldNumber = 3, + kPlannedHomePositionFieldNumber = 4, }; // repeated .mavsdk.rpc.mission_raw.MissionItem mission_items = 1; int mission_items_size() const; @@ -3901,6 +3902,24 @@ class MissionImportData final : const ::PROTOBUF_NAMESPACE_ID::RepeatedPtrField< ::mavsdk::rpc::mission_raw::MissionItem >& rally_items() const; + // .mavsdk.rpc.mission_raw.MissionItem planned_home_position = 4; + bool has_planned_home_position() const; + private: + bool _internal_has_planned_home_position() const; + public: + void clear_planned_home_position(); + const ::mavsdk::rpc::mission_raw::MissionItem& planned_home_position() const; + PROTOBUF_MUST_USE_RESULT ::mavsdk::rpc::mission_raw::MissionItem* release_planned_home_position(); + ::mavsdk::rpc::mission_raw::MissionItem* mutable_planned_home_position(); + void set_allocated_planned_home_position(::mavsdk::rpc::mission_raw::MissionItem* planned_home_position); + private: + const ::mavsdk::rpc::mission_raw::MissionItem& _internal_planned_home_position() const; + ::mavsdk::rpc::mission_raw::MissionItem* _internal_mutable_planned_home_position(); + public: + void unsafe_arena_set_allocated_planned_home_position( + ::mavsdk::rpc::mission_raw::MissionItem* planned_home_position); + ::mavsdk::rpc::mission_raw::MissionItem* unsafe_arena_release_planned_home_position(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.mission_raw.MissionImportData) private: class _Internal; @@ -3911,6 +3930,7 @@ class MissionImportData final : ::PROTOBUF_NAMESPACE_ID::RepeatedPtrField< ::mavsdk::rpc::mission_raw::MissionItem > mission_items_; ::PROTOBUF_NAMESPACE_ID::RepeatedPtrField< ::mavsdk::rpc::mission_raw::MissionItem > geofence_items_; ::PROTOBUF_NAMESPACE_ID::RepeatedPtrField< ::mavsdk::rpc::mission_raw::MissionItem > rally_items_; + ::mavsdk::rpc::mission_raw::MissionItem* planned_home_position_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; friend struct ::TableStruct_mission_5fraw_2fmission_5fraw_2eproto; }; @@ -5804,6 +5824,96 @@ MissionImportData::rally_items() const { return rally_items_; } +// .mavsdk.rpc.mission_raw.MissionItem planned_home_position = 4; +inline bool MissionImportData::_internal_has_planned_home_position() const { + return this != internal_default_instance() && planned_home_position_ != nullptr; +} +inline bool MissionImportData::has_planned_home_position() const { + return _internal_has_planned_home_position(); +} +inline void MissionImportData::clear_planned_home_position() { + if (GetArenaForAllocation() == nullptr && planned_home_position_ != nullptr) { + delete planned_home_position_; + } + planned_home_position_ = nullptr; +} +inline const ::mavsdk::rpc::mission_raw::MissionItem& MissionImportData::_internal_planned_home_position() const { + const ::mavsdk::rpc::mission_raw::MissionItem* p = planned_home_position_; + return p != nullptr ? *p : reinterpret_cast( + ::mavsdk::rpc::mission_raw::_MissionItem_default_instance_); +} +inline const ::mavsdk::rpc::mission_raw::MissionItem& MissionImportData::planned_home_position() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.mission_raw.MissionImportData.planned_home_position) + return _internal_planned_home_position(); +} +inline void MissionImportData::unsafe_arena_set_allocated_planned_home_position( + ::mavsdk::rpc::mission_raw::MissionItem* planned_home_position) { + if (GetArenaForAllocation() == nullptr) { + delete reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(planned_home_position_); + } + planned_home_position_ = planned_home_position; + if (planned_home_position) { + + } else { + + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.mission_raw.MissionImportData.planned_home_position) +} +inline ::mavsdk::rpc::mission_raw::MissionItem* MissionImportData::release_planned_home_position() { + + ::mavsdk::rpc::mission_raw::MissionItem* temp = planned_home_position_; + planned_home_position_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::PROTOBUF_NAMESPACE_ID::MessageLite*>(temp); + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + if (GetArenaForAllocation() == nullptr) { delete old; } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArenaForAllocation() != nullptr) { + temp = ::PROTOBUF_NAMESPACE_ID::internal::DuplicateIfNonNull(temp); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return temp; +} +inline ::mavsdk::rpc::mission_raw::MissionItem* MissionImportData::unsafe_arena_release_planned_home_position() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.mission_raw.MissionImportData.planned_home_position) + + ::mavsdk::rpc::mission_raw::MissionItem* temp = planned_home_position_; + planned_home_position_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::mission_raw::MissionItem* MissionImportData::_internal_mutable_planned_home_position() { + + if (planned_home_position_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::mission_raw::MissionItem>(GetArenaForAllocation()); + planned_home_position_ = p; + } + return planned_home_position_; +} +inline ::mavsdk::rpc::mission_raw::MissionItem* MissionImportData::mutable_planned_home_position() { + ::mavsdk::rpc::mission_raw::MissionItem* _msg = _internal_mutable_planned_home_position(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.mission_raw.MissionImportData.planned_home_position) + return _msg; +} +inline void MissionImportData::set_allocated_planned_home_position(::mavsdk::rpc::mission_raw::MissionItem* planned_home_position) { + ::PROTOBUF_NAMESPACE_ID::Arena* message_arena = GetArenaForAllocation(); + if (message_arena == nullptr) { + delete planned_home_position_; + } + if (planned_home_position) { + ::PROTOBUF_NAMESPACE_ID::Arena* submessage_arena = + ::PROTOBUF_NAMESPACE_ID::Arena::InternalHelper<::mavsdk::rpc::mission_raw::MissionItem>::GetOwningArena(planned_home_position); + if (message_arena != submessage_arena) { + planned_home_position = ::PROTOBUF_NAMESPACE_ID::internal::GetOwnedMessage( + message_arena, planned_home_position, submessage_arena); + } + + } else { + + } + planned_home_position_ = planned_home_position; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.mission_raw.MissionImportData.planned_home_position) +} + // ------------------------------------------------------------------- // MissionRawResult diff --git a/src/mavsdk_server/src/plugins/mission_raw/mission_raw_service_impl.h b/src/mavsdk_server/src/plugins/mission_raw/mission_raw_service_impl.h index cf9274e355..240bf000a6 100644 --- a/src/mavsdk_server/src/plugins/mission_raw/mission_raw_service_impl.h +++ b/src/mavsdk_server/src/plugins/mission_raw/mission_raw_service_impl.h @@ -150,6 +150,9 @@ class MissionRawServiceImpl final : public rpc::mission_raw::MissionRawService:: ptr->CopyFrom(*translateToRpcMissionItem(elem).release()); } + rpc_obj->set_allocated_planned_home_position( + translateToRpcMissionItem(mission_import_data.planned_home_position).release()); + return rpc_obj; } @@ -173,6 +176,9 @@ class MissionRawServiceImpl final : public rpc::mission_raw::MissionRawService:: static_cast(elem))); } + obj.planned_home_position = + translateFromRpcMissionItem(mission_import_data.planned_home_position()); + return obj; }