From babfa4383d408b790e28364856910c76566c7578 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 3 Sep 2021 10:54:52 +0200 Subject: [PATCH] mission: remove VehicleAction for now This will be added again once it's ready. --- proto | 2 +- .../src/generated/mission/mission.pb.cc | 208 +++++++----------- .../src/generated/mission/mission.pb.h | 100 --------- .../plugins/mission/mission_service_impl.h | 46 ---- .../mission/include/plugins/mission/mission.h | 23 -- src/plugins/mission/mission.cpp | 23 +- 6 files changed, 76 insertions(+), 326 deletions(-) diff --git a/proto b/proto index 386f24e68b..fa81b63bb3 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 386f24e68b1b037b3c10eef9ed69b95cdc2e5f70 +Subproject commit fa81b63bb354dd791577152773990d5223bbad90 diff --git a/src/mavsdk_server/src/generated/mission/mission.pb.cc b/src/mavsdk_server/src/generated/mission/mission.pb.cc index 7dadad8eb1..3410ad0a2a 100644 --- a/src/mavsdk_server/src/generated/mission/mission.pb.cc +++ b/src/mavsdk_server/src/generated/mission/mission.pb.cc @@ -315,9 +315,7 @@ constexpr MissionItem::MissionItem( , camera_photo_interval_s_(0) , loiter_time_s_(0) , acceptance_radius_m_(0) - , yaw_deg_(0) - , vehicle_action_(0) -{} + , yaw_deg_(0){} struct MissionItemDefaultTypeInternal { constexpr MissionItemDefaultTypeInternal() : _instance(::PROTOBUF_NAMESPACE_ID::internal::ConstantInitialized{}) {} @@ -370,7 +368,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT MissionResultDefaultTypeInterna } // namespace rpc } // namespace mavsdk static ::PROTOBUF_NAMESPACE_ID::Metadata file_level_metadata_mission_2fmission_2eproto[28]; -static const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* file_level_enum_descriptors_mission_2fmission_2eproto[3]; +static const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* file_level_enum_descriptors_mission_2fmission_2eproto[2]; static constexpr ::PROTOBUF_NAMESPACE_ID::ServiceDescriptor const** file_level_service_descriptors_mission_2fmission_2eproto = nullptr; const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_mission_2fmission_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { @@ -529,7 +527,6 @@ const ::PROTOBUF_NAMESPACE_ID::uint32 TableStruct_mission_2fmission_2eproto::off PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::mission::MissionItem, camera_photo_interval_s_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::mission::MissionItem, acceptance_radius_m_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::mission::MissionItem, yaw_deg_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::mission::MissionItem, vehicle_action_), ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::mission::MissionPlan, _internal_metadata_), ~0u, // no _extensions_ @@ -577,9 +574,9 @@ static const ::PROTOBUF_NAMESPACE_ID::internal::MigrationSchema schemas[] PROTOB { 126, -1, sizeof(::mavsdk::rpc::mission::SetReturnToLaunchAfterMissionRequest)}, { 132, -1, sizeof(::mavsdk::rpc::mission::SetReturnToLaunchAfterMissionResponse)}, { 138, -1, sizeof(::mavsdk::rpc::mission::MissionItem)}, - { 156, -1, sizeof(::mavsdk::rpc::mission::MissionPlan)}, - { 162, -1, sizeof(::mavsdk::rpc::mission::MissionProgress)}, - { 169, -1, sizeof(::mavsdk::rpc::mission::MissionResult)}, + { 155, -1, sizeof(::mavsdk::rpc::mission::MissionPlan)}, + { 161, -1, sizeof(::mavsdk::rpc::mission::MissionProgress)}, + { 168, -1, sizeof(::mavsdk::rpc::mission::MissionResult)}, }; static ::PROTOBUF_NAMESPACE_ID::Message const * const file_default_instances[] = { @@ -655,7 +652,7 @@ const char descriptor_table_protodef_mission_2fmission_2eproto[] PROTOBUF_SECTIO "etReturnToLaunchAfterMissionRequest\022\016\n\006e" "nable\030\001 \001(\010\"b\n%SetReturnToLaunchAfterMis" "sionResponse\0229\n\016mission_result\030\001 \001(\0132!.m" - "avsdk.rpc.mission.MissionResult\"\264\007\n\013Miss" + "avsdk.rpc.mission.MissionResult\"\303\005\n\013Miss" "ionItem\022(\n\014latitude_deg\030\001 \001(\001B\022\202\265\030\003NaN\211\265" "\030H\257\274\232\362\327z>\022)\n\rlongitude_deg\030\002 \001(\001B\022\202\265\030\003Na" "N\211\265\030H\257\274\232\362\327z>\022$\n\023relative_altitude_m\030\003 \001(" @@ -668,77 +665,71 @@ const char descriptor_table_protodef_mission_2fmission_2eproto[] PROTOBUF_SECTIO "er_time_s\030\t \001(\002B\007\202\265\030\003NaN\022(\n\027camera_photo" "_interval_s\030\n \001(\001B\007\202\265\030\0031.0\022$\n\023acceptance" "_radius_m\030\013 \001(\002B\007\202\265\030\003NaN\022\030\n\007yaw_deg\030\014 \001(" - "\002B\007\202\265\030\003NaN\022E\n\016vehicle_action\030\r \001(\0162-.mav" - "sdk.rpc.mission.MissionItem.VehicleActio" - "n\"\320\001\n\014CameraAction\022\026\n\022CAMERA_ACTION_NONE" - "\020\000\022\034\n\030CAMERA_ACTION_TAKE_PHOTO\020\001\022&\n\"CAME" - "RA_ACTION_START_PHOTO_INTERVAL\020\002\022%\n!CAME" - "RA_ACTION_STOP_PHOTO_INTERVAL\020\003\022\035\n\031CAMER" - "A_ACTION_START_VIDEO\020\004\022\034\n\030CAMERA_ACTION_" - "STOP_VIDEO\020\005\"\247\001\n\rVehicleAction\022\027\n\023VEHICL" - "E_ACTION_NONE\020\000\022\032\n\026VEHICLE_ACTION_TAKEOF" - "F\020\001\022\027\n\023VEHICLE_ACTION_LAND\020\002\022#\n\037VEHICLE_" - "ACTION_TRANSITION_TO_FW\020\003\022#\n\037VEHICLE_ACT" - "ION_TRANSITION_TO_MC\020\004\"E\n\013MissionPlan\0226\n" - "\rmission_items\030\001 \003(\0132\037.mavsdk.rpc.missio" - "n.MissionItem\"1\n\017MissionProgress\022\017\n\007curr" - "ent\030\001 \001(\005\022\r\n\005total\030\002 \001(\005\"\231\003\n\rMissionResu" - "lt\0228\n\006result\030\001 \001(\0162(.mavsdk.rpc.mission." - "MissionResult.Result\022\022\n\nresult_str\030\002 \001(\t" - "\"\271\002\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESUL" - "T_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\033RE" - "SULT_NO_MISSION_AVAILABLE\020\010\022\"\n\036RESULT_UN" - "SUPPORTED_MISSION_CMD\020\013\022\035\n\031RESULT_TRANSF" - "ER_CANCELLED\020\014\022\024\n\020RESULT_NO_SYSTEM\020\r2\315\013\n" - "\016MissionService\022f\n\rUploadMission\022(.mavsd" - "k.rpc.mission.UploadMissionRequest\032).mav" - "sdk.rpc.mission.UploadMissionResponse\"\000\022" - "|\n\023CancelMissionUpload\022..mavsdk.rpc.miss" - "ion.CancelMissionUploadRequest\032/.mavsdk." - "rpc.mission.CancelMissionUploadResponse\"" - "\004\200\265\030\001\022l\n\017DownloadMission\022*.mavsdk.rpc.mi" - "ssion.DownloadMissionRequest\032+.mavsdk.rp" - "c.mission.DownloadMissionResponse\"\000\022\202\001\n\025" - "CancelMissionDownload\0220.mavsdk.rpc.missi" - "on.CancelMissionDownloadRequest\0321.mavsdk" - ".rpc.mission.CancelMissionDownloadRespon" - "se\"\004\200\265\030\001\022c\n\014StartMission\022\'.mavsdk.rpc.mi" - "ssion.StartMissionRequest\032(.mavsdk.rpc.m" - "ission.StartMissionResponse\"\000\022c\n\014PauseMi" - "ssion\022\'.mavsdk.rpc.mission.PauseMissionR" - "equest\032(.mavsdk.rpc.mission.PauseMission" - "Response\"\000\022c\n\014ClearMission\022\'.mavsdk.rpc." - "mission.ClearMissionRequest\032(.mavsdk.rpc" - ".mission.ClearMissionResponse\"\000\022~\n\025SetCu" - "rrentMissionItem\0220.mavsdk.rpc.mission.Se" - "tCurrentMissionItemRequest\0321.mavsdk.rpc." - "mission.SetCurrentMissionItemResponse\"\000\022" - "v\n\021IsMissionFinished\022,.mavsdk.rpc.missio" - "n.IsMissionFinishedRequest\032-.mavsdk.rpc." - "mission.IsMissionFinishedResponse\"\004\200\265\030\001\022" - "\200\001\n\030SubscribeMissionProgress\0223.mavsdk.rp" - "c.mission.SubscribeMissionProgressReques" - "t\032+.mavsdk.rpc.mission.MissionProgressRe" - "sponse\"\0000\001\022\232\001\n\035GetReturnToLaunchAfterMis" - "sion\0228.mavsdk.rpc.mission.GetReturnToLau" - "nchAfterMissionRequest\0329.mavsdk.rpc.miss" - "ion.GetReturnToLaunchAfterMissionRespons" - "e\"\004\200\265\030\001\022\232\001\n\035SetReturnToLaunchAfterMissio" - "n\0228.mavsdk.rpc.mission.SetReturnToLaunch" - "AfterMissionRequest\0329.mavsdk.rpc.mission" - ".SetReturnToLaunchAfterMissionResponse\"\004" - "\200\265\030\001B!\n\021io.mavsdk.missionB\014MissionProtob" - "\006proto3" + "\002B\007\202\265\030\003NaN\"\320\001\n\014CameraAction\022\026\n\022CAMERA_AC" + "TION_NONE\020\000\022\034\n\030CAMERA_ACTION_TAKE_PHOTO\020" + "\001\022&\n\"CAMERA_ACTION_START_PHOTO_INTERVAL\020" + "\002\022%\n!CAMERA_ACTION_STOP_PHOTO_INTERVAL\020\003" + "\022\035\n\031CAMERA_ACTION_START_VIDEO\020\004\022\034\n\030CAMER" + "A_ACTION_STOP_VIDEO\020\005\"E\n\013MissionPlan\0226\n\r" + "mission_items\030\001 \003(\0132\037.mavsdk.rpc.mission" + ".MissionItem\"1\n\017MissionProgress\022\017\n\007curre" + "nt\030\001 \001(\005\022\r\n\005total\030\002 \001(\005\"\231\003\n\rMissionResul" + "t\0228\n\006result\030\001 \001(\0162(.mavsdk.rpc.mission.M" + "issionResult.Result\022\022\n\nresult_str\030\002 \001(\t\"" + "\271\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_T" + "OO_MANY_MISSION_ITEMS\020\003\022\017\n\013RESULT_BUSY\020\004" + "\022\022\n\016RESULT_TIMEOUT\020\005\022\033\n\027RESULT_INVALID_A" + "RGUMENT\020\006\022\026\n\022RESULT_UNSUPPORTED\020\007\022\037\n\033RES" + "ULT_NO_MISSION_AVAILABLE\020\010\022\"\n\036RESULT_UNS" + "UPPORTED_MISSION_CMD\020\013\022\035\n\031RESULT_TRANSFE" + "R_CANCELLED\020\014\022\024\n\020RESULT_NO_SYSTEM\020\r2\315\013\n\016" + "MissionService\022f\n\rUploadMission\022(.mavsdk" + ".rpc.mission.UploadMissionRequest\032).mavs" + "dk.rpc.mission.UploadMissionResponse\"\000\022|" + "\n\023CancelMissionUpload\022..mavsdk.rpc.missi" + "on.CancelMissionUploadRequest\032/.mavsdk.r" + "pc.mission.CancelMissionUploadResponse\"\004" + "\200\265\030\001\022l\n\017DownloadMission\022*.mavsdk.rpc.mis" + "sion.DownloadMissionRequest\032+.mavsdk.rpc" + ".mission.DownloadMissionResponse\"\000\022\202\001\n\025C" + "ancelMissionDownload\0220.mavsdk.rpc.missio" + "n.CancelMissionDownloadRequest\0321.mavsdk." + "rpc.mission.CancelMissionDownloadRespons" + "e\"\004\200\265\030\001\022c\n\014StartMission\022\'.mavsdk.rpc.mis" + "sion.StartMissionRequest\032(.mavsdk.rpc.mi" + "ssion.StartMissionResponse\"\000\022c\n\014PauseMis" + "sion\022\'.mavsdk.rpc.mission.PauseMissionRe" + "quest\032(.mavsdk.rpc.mission.PauseMissionR" + "esponse\"\000\022c\n\014ClearMission\022\'.mavsdk.rpc.m" + "ission.ClearMissionRequest\032(.mavsdk.rpc." + "mission.ClearMissionResponse\"\000\022~\n\025SetCur" + "rentMissionItem\0220.mavsdk.rpc.mission.Set" + "CurrentMissionItemRequest\0321.mavsdk.rpc.m" + "ission.SetCurrentMissionItemResponse\"\000\022v" + "\n\021IsMissionFinished\022,.mavsdk.rpc.mission" + ".IsMissionFinishedRequest\032-.mavsdk.rpc.m" + "ission.IsMissionFinishedResponse\"\004\200\265\030\001\022\200" + "\001\n\030SubscribeMissionProgress\0223.mavsdk.rpc" + ".mission.SubscribeMissionProgressRequest" + "\032+.mavsdk.rpc.mission.MissionProgressRes" + "ponse\"\0000\001\022\232\001\n\035GetReturnToLaunchAfterMiss" + "ion\0228.mavsdk.rpc.mission.GetReturnToLaun" + "chAfterMissionRequest\0329.mavsdk.rpc.missi" + "on.GetReturnToLaunchAfterMissionResponse" + "\"\004\200\265\030\001\022\232\001\n\035SetReturnToLaunchAfterMission" + "\0228.mavsdk.rpc.mission.SetReturnToLaunchA" + "fterMissionRequest\0329.mavsdk.rpc.mission." + "SetReturnToLaunchAfterMissionResponse\"\004\200" + "\265\030\001B!\n\021io.mavsdk.missionB\014MissionProtob\006" + "proto3" ; static const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable*const descriptor_table_mission_2fmission_2eproto_deps[1] = { &::descriptor_table_mavsdk_5foptions_2eproto, }; static ::PROTOBUF_NAMESPACE_ID::internal::once_flag descriptor_table_mission_2fmission_2eproto_once; const ::PROTOBUF_NAMESPACE_ID::internal::DescriptorTable descriptor_table_mission_2fmission_2eproto = { - false, false, 4687, descriptor_table_protodef_mission_2fmission_2eproto, "mission/mission.proto", + false, false, 4446, descriptor_table_protodef_mission_2fmission_2eproto, "mission/mission.proto", &descriptor_table_mission_2fmission_2eproto_once, descriptor_table_mission_2fmission_2eproto_deps, 1, 28, schemas, file_default_instances, TableStruct_mission_2fmission_2eproto::offsets, file_level_metadata_mission_2fmission_2eproto, file_level_enum_descriptors_mission_2fmission_2eproto, file_level_service_descriptors_mission_2fmission_2eproto, @@ -783,36 +774,9 @@ constexpr MissionItem_CameraAction MissionItem::CameraAction_MIN; constexpr MissionItem_CameraAction MissionItem::CameraAction_MAX; constexpr int MissionItem::CameraAction_ARRAYSIZE; #endif // (__cplusplus < 201703) && (!defined(_MSC_VER) || _MSC_VER >= 1900) -const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* MissionItem_VehicleAction_descriptor() { - ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_mission_2fmission_2eproto); - return file_level_enum_descriptors_mission_2fmission_2eproto[1]; -} -bool MissionItem_VehicleAction_IsValid(int value) { - switch (value) { - case 0: - case 1: - case 2: - case 3: - case 4: - return true; - default: - return false; - } -} - -#if (__cplusplus < 201703) && (!defined(_MSC_VER) || _MSC_VER >= 1900) -constexpr MissionItem_VehicleAction MissionItem::VEHICLE_ACTION_NONE; -constexpr MissionItem_VehicleAction MissionItem::VEHICLE_ACTION_TAKEOFF; -constexpr MissionItem_VehicleAction MissionItem::VEHICLE_ACTION_LAND; -constexpr MissionItem_VehicleAction MissionItem::VEHICLE_ACTION_TRANSITION_TO_FW; -constexpr MissionItem_VehicleAction MissionItem::VEHICLE_ACTION_TRANSITION_TO_MC; -constexpr MissionItem_VehicleAction MissionItem::VehicleAction_MIN; -constexpr MissionItem_VehicleAction MissionItem::VehicleAction_MAX; -constexpr int MissionItem::VehicleAction_ARRAYSIZE; -#endif // (__cplusplus < 201703) && (!defined(_MSC_VER) || _MSC_VER >= 1900) const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* MissionResult_Result_descriptor() { ::PROTOBUF_NAMESPACE_ID::internal::AssignDescriptors(&descriptor_table_mission_2fmission_2eproto); - return file_level_enum_descriptors_mission_2fmission_2eproto[2]; + return file_level_enum_descriptors_mission_2fmission_2eproto[1]; } bool MissionResult_Result_IsValid(int value) { switch (value) { @@ -5419,16 +5383,16 @@ MissionItem::MissionItem(const MissionItem& from) : ::PROTOBUF_NAMESPACE_ID::Message() { _internal_metadata_.MergeFrom<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(from._internal_metadata_); ::memcpy(&latitude_deg_, &from.latitude_deg_, - static_cast(reinterpret_cast(&vehicle_action_) - - reinterpret_cast(&latitude_deg_)) + sizeof(vehicle_action_)); + static_cast(reinterpret_cast(&yaw_deg_) - + reinterpret_cast(&latitude_deg_)) + sizeof(yaw_deg_)); // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.mission.MissionItem) } void MissionItem::SharedCtor() { ::memset(reinterpret_cast(this) + static_cast( reinterpret_cast(&latitude_deg_) - reinterpret_cast(this)), - 0, static_cast(reinterpret_cast(&vehicle_action_) - - reinterpret_cast(&latitude_deg_)) + sizeof(vehicle_action_)); + 0, static_cast(reinterpret_cast(&yaw_deg_) - + reinterpret_cast(&latitude_deg_)) + sizeof(yaw_deg_)); } MissionItem::~MissionItem() { @@ -5458,8 +5422,8 @@ void MissionItem::Clear() { (void) cached_has_bits; ::memset(&latitude_deg_, 0, static_cast( - reinterpret_cast(&vehicle_action_) - - reinterpret_cast(&latitude_deg_)) + sizeof(vehicle_action_)); + reinterpret_cast(&yaw_deg_) - + reinterpret_cast(&latitude_deg_)) + sizeof(yaw_deg_)); _internal_metadata_.Clear<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(); } @@ -5555,14 +5519,6 @@ const char* MissionItem::_InternalParse(const char* ptr, ::PROTOBUF_NAMESPACE_ID ptr += sizeof(float); } else goto handle_unusual; continue; - // .mavsdk.rpc.mission.MissionItem.VehicleAction vehicle_action = 13; - case 13: - if (PROTOBUF_PREDICT_TRUE(static_cast<::PROTOBUF_NAMESPACE_ID::uint8>(tag) == 104)) { - ::PROTOBUF_NAMESPACE_ID::uint64 val = ::PROTOBUF_NAMESPACE_ID::internal::ReadVarint64(&ptr); - CHK_(ptr); - _internal_set_vehicle_action(static_cast<::mavsdk::rpc::mission::MissionItem_VehicleAction>(val)); - } else goto handle_unusual; - continue; default: { handle_unusual: if ((tag & 7) == 4 || tag == 0) { @@ -5664,13 +5620,6 @@ ::PROTOBUF_NAMESPACE_ID::uint8* MissionItem::_InternalSerialize( target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteFloatToArray(12, this->_internal_yaw_deg(), target); } - // .mavsdk.rpc.mission.MissionItem.VehicleAction vehicle_action = 13; - if (this->vehicle_action() != 0) { - target = stream->EnsureSpace(target); - target = ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::WriteEnumToArray( - 13, this->_internal_vehicle_action(), target); - } - 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); @@ -5748,12 +5697,6 @@ size_t MissionItem::ByteSizeLong() const { total_size += 1 + 4; } - // .mavsdk.rpc.mission.MissionItem.VehicleAction vehicle_action = 13; - if (this->vehicle_action() != 0) { - total_size += 1 + - ::PROTOBUF_NAMESPACE_ID::internal::WireFormatLite::EnumSize(this->_internal_vehicle_action()); - } - if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { return ::PROTOBUF_NAMESPACE_ID::internal::ComputeUnknownFieldsSize( _internal_metadata_, total_size, &_cached_size_); @@ -5821,9 +5764,6 @@ void MissionItem::MergeFrom(const MissionItem& from) { if (!(from.yaw_deg() <= 0 && from.yaw_deg() >= 0)) { _internal_set_yaw_deg(from._internal_yaw_deg()); } - if (from.vehicle_action() != 0) { - _internal_set_vehicle_action(from._internal_vehicle_action()); - } } void MissionItem::CopyFrom(const ::PROTOBUF_NAMESPACE_ID::Message& from) { @@ -5848,8 +5788,8 @@ void MissionItem::InternalSwap(MissionItem* other) { using std::swap; _internal_metadata_.Swap<::PROTOBUF_NAMESPACE_ID::UnknownFieldSet>(&other->_internal_metadata_); ::PROTOBUF_NAMESPACE_ID::internal::memswap< - PROTOBUF_FIELD_OFFSET(MissionItem, vehicle_action_) - + sizeof(MissionItem::vehicle_action_) + PROTOBUF_FIELD_OFFSET(MissionItem, yaw_deg_) + + sizeof(MissionItem::yaw_deg_) - PROTOBUF_FIELD_OFFSET(MissionItem, latitude_deg_)>( reinterpret_cast(&latitude_deg_), reinterpret_cast(&other->latitude_deg_)); diff --git a/src/mavsdk_server/src/generated/mission/mission.pb.h b/src/mavsdk_server/src/generated/mission/mission.pb.h index 14e2e3598f..d5fd6ebd6f 100644 --- a/src/mavsdk_server/src/generated/mission/mission.pb.h +++ b/src/mavsdk_server/src/generated/mission/mission.pb.h @@ -209,34 +209,6 @@ inline bool MissionItem_CameraAction_Parse( return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( MissionItem_CameraAction_descriptor(), name, value); } -enum MissionItem_VehicleAction : int { - MissionItem_VehicleAction_VEHICLE_ACTION_NONE = 0, - MissionItem_VehicleAction_VEHICLE_ACTION_TAKEOFF = 1, - MissionItem_VehicleAction_VEHICLE_ACTION_LAND = 2, - MissionItem_VehicleAction_VEHICLE_ACTION_TRANSITION_TO_FW = 3, - MissionItem_VehicleAction_VEHICLE_ACTION_TRANSITION_TO_MC = 4, - MissionItem_VehicleAction_MissionItem_VehicleAction_INT_MIN_SENTINEL_DO_NOT_USE_ = std::numeric_limits<::PROTOBUF_NAMESPACE_ID::int32>::min(), - MissionItem_VehicleAction_MissionItem_VehicleAction_INT_MAX_SENTINEL_DO_NOT_USE_ = std::numeric_limits<::PROTOBUF_NAMESPACE_ID::int32>::max() -}; -bool MissionItem_VehicleAction_IsValid(int value); -constexpr MissionItem_VehicleAction MissionItem_VehicleAction_VehicleAction_MIN = MissionItem_VehicleAction_VEHICLE_ACTION_NONE; -constexpr MissionItem_VehicleAction MissionItem_VehicleAction_VehicleAction_MAX = MissionItem_VehicleAction_VEHICLE_ACTION_TRANSITION_TO_MC; -constexpr int MissionItem_VehicleAction_VehicleAction_ARRAYSIZE = MissionItem_VehicleAction_VehicleAction_MAX + 1; - -const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* MissionItem_VehicleAction_descriptor(); -template -inline const std::string& MissionItem_VehicleAction_Name(T enum_t_value) { - static_assert(::std::is_same::value || - ::std::is_integral::value, - "Incorrect type passed to function MissionItem_VehicleAction_Name."); - return ::PROTOBUF_NAMESPACE_ID::internal::NameOfEnum( - MissionItem_VehicleAction_descriptor(), enum_t_value); -} -inline bool MissionItem_VehicleAction_Parse( - ::PROTOBUF_NAMESPACE_ID::ConstStringParam name, MissionItem_VehicleAction* value) { - return ::PROTOBUF_NAMESPACE_ID::internal::ParseNamedEnum( - MissionItem_VehicleAction_descriptor(), name, value); -} enum MissionResult_Result : int { MissionResult_Result_RESULT_UNKNOWN = 0, MissionResult_Result_RESULT_SUCCESS = 1, @@ -3752,42 +3724,6 @@ class MissionItem PROTOBUF_FINAL : return MissionItem_CameraAction_Parse(name, value); } - typedef MissionItem_VehicleAction VehicleAction; - static constexpr VehicleAction VEHICLE_ACTION_NONE = - MissionItem_VehicleAction_VEHICLE_ACTION_NONE; - static constexpr VehicleAction VEHICLE_ACTION_TAKEOFF = - MissionItem_VehicleAction_VEHICLE_ACTION_TAKEOFF; - static constexpr VehicleAction VEHICLE_ACTION_LAND = - MissionItem_VehicleAction_VEHICLE_ACTION_LAND; - static constexpr VehicleAction VEHICLE_ACTION_TRANSITION_TO_FW = - MissionItem_VehicleAction_VEHICLE_ACTION_TRANSITION_TO_FW; - static constexpr VehicleAction VEHICLE_ACTION_TRANSITION_TO_MC = - MissionItem_VehicleAction_VEHICLE_ACTION_TRANSITION_TO_MC; - static inline bool VehicleAction_IsValid(int value) { - return MissionItem_VehicleAction_IsValid(value); - } - static constexpr VehicleAction VehicleAction_MIN = - MissionItem_VehicleAction_VehicleAction_MIN; - static constexpr VehicleAction VehicleAction_MAX = - MissionItem_VehicleAction_VehicleAction_MAX; - static constexpr int VehicleAction_ARRAYSIZE = - MissionItem_VehicleAction_VehicleAction_ARRAYSIZE; - static inline const ::PROTOBUF_NAMESPACE_ID::EnumDescriptor* - VehicleAction_descriptor() { - return MissionItem_VehicleAction_descriptor(); - } - template - static inline const std::string& VehicleAction_Name(T enum_t_value) { - static_assert(::std::is_same::value || - ::std::is_integral::value, - "Incorrect type passed to function VehicleAction_Name."); - return MissionItem_VehicleAction_Name(enum_t_value); - } - static inline bool VehicleAction_Parse(::PROTOBUF_NAMESPACE_ID::ConstStringParam name, - VehicleAction* value) { - return MissionItem_VehicleAction_Parse(name, value); - } - // accessors ------------------------------------------------------- enum : int { @@ -3803,7 +3739,6 @@ class MissionItem PROTOBUF_FINAL : kLoiterTimeSFieldNumber = 9, kAcceptanceRadiusMFieldNumber = 11, kYawDegFieldNumber = 12, - kVehicleActionFieldNumber = 13, }; // double latitude_deg = 1 [(.mavsdk.options.default_value) = "NaN", (.mavsdk.options.epsilon) = 1e-07]; void clear_latitude_deg(); @@ -3913,15 +3848,6 @@ class MissionItem PROTOBUF_FINAL : void _internal_set_yaw_deg(float value); public: - // .mavsdk.rpc.mission.MissionItem.VehicleAction vehicle_action = 13; - void clear_vehicle_action(); - ::mavsdk::rpc::mission::MissionItem_VehicleAction vehicle_action() const; - void set_vehicle_action(::mavsdk::rpc::mission::MissionItem_VehicleAction value); - private: - ::mavsdk::rpc::mission::MissionItem_VehicleAction _internal_vehicle_action() const; - void _internal_set_vehicle_action(::mavsdk::rpc::mission::MissionItem_VehicleAction value); - public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.mission.MissionItem) private: class _Internal; @@ -3941,7 +3867,6 @@ class MissionItem PROTOBUF_FINAL : float loiter_time_s_; float acceptance_radius_m_; float yaw_deg_; - int vehicle_action_; mutable ::PROTOBUF_NAMESPACE_ID::internal::CachedSize _cached_size_; friend struct ::TableStruct_mission_2fmission_2eproto; }; @@ -6033,26 +5958,6 @@ inline void MissionItem::set_yaw_deg(float value) { // @@protoc_insertion_point(field_set:mavsdk.rpc.mission.MissionItem.yaw_deg) } -// .mavsdk.rpc.mission.MissionItem.VehicleAction vehicle_action = 13; -inline void MissionItem::clear_vehicle_action() { - vehicle_action_ = 0; -} -inline ::mavsdk::rpc::mission::MissionItem_VehicleAction MissionItem::_internal_vehicle_action() const { - return static_cast< ::mavsdk::rpc::mission::MissionItem_VehicleAction >(vehicle_action_); -} -inline ::mavsdk::rpc::mission::MissionItem_VehicleAction MissionItem::vehicle_action() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.mission.MissionItem.vehicle_action) - return _internal_vehicle_action(); -} -inline void MissionItem::_internal_set_vehicle_action(::mavsdk::rpc::mission::MissionItem_VehicleAction value) { - - vehicle_action_ = value; -} -inline void MissionItem::set_vehicle_action(::mavsdk::rpc::mission::MissionItem_VehicleAction value) { - _internal_set_vehicle_action(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.mission.MissionItem.vehicle_action) -} - // ------------------------------------------------------------------- // MissionPlan @@ -6296,11 +6201,6 @@ template <> inline const EnumDescriptor* GetEnumDescriptor< ::mavsdk::rpc::mission::MissionItem_CameraAction>() { return ::mavsdk::rpc::mission::MissionItem_CameraAction_descriptor(); } -template <> struct is_proto_enum< ::mavsdk::rpc::mission::MissionItem_VehicleAction> : ::std::true_type {}; -template <> -inline const EnumDescriptor* GetEnumDescriptor< ::mavsdk::rpc::mission::MissionItem_VehicleAction>() { - return ::mavsdk::rpc::mission::MissionItem_VehicleAction_descriptor(); -} template <> struct is_proto_enum< ::mavsdk::rpc::mission::MissionResult_Result> : ::std::true_type {}; template <> inline const EnumDescriptor* GetEnumDescriptor< ::mavsdk::rpc::mission::MissionResult_Result>() { diff --git a/src/mavsdk_server/src/plugins/mission/mission_service_impl.h b/src/mavsdk_server/src/plugins/mission/mission_service_impl.h index 8908a76db9..6090472cb1 100644 --- a/src/mavsdk_server/src/plugins/mission/mission_service_impl.h +++ b/src/mavsdk_server/src/plugins/mission/mission_service_impl.h @@ -82,48 +82,6 @@ class MissionServiceImpl final : public rpc::mission::MissionService::Service { } } - static rpc::mission::MissionItem::VehicleAction - translateToRpcVehicleAction(const mavsdk::Mission::MissionItem::VehicleAction& vehicle_action) - { - switch (vehicle_action) { - default: - LogErr() << "Unknown vehicle_action enum value: " - << static_cast(vehicle_action); - // FALLTHROUGH - case mavsdk::Mission::MissionItem::VehicleAction::None: - return rpc::mission::MissionItem_VehicleAction_VEHICLE_ACTION_NONE; - case mavsdk::Mission::MissionItem::VehicleAction::Takeoff: - return rpc::mission::MissionItem_VehicleAction_VEHICLE_ACTION_TAKEOFF; - case mavsdk::Mission::MissionItem::VehicleAction::Land: - return rpc::mission::MissionItem_VehicleAction_VEHICLE_ACTION_LAND; - case mavsdk::Mission::MissionItem::VehicleAction::TransitionToFw: - return rpc::mission::MissionItem_VehicleAction_VEHICLE_ACTION_TRANSITION_TO_FW; - case mavsdk::Mission::MissionItem::VehicleAction::TransitionToMc: - return rpc::mission::MissionItem_VehicleAction_VEHICLE_ACTION_TRANSITION_TO_MC; - } - } - - static mavsdk::Mission::MissionItem::VehicleAction - translateFromRpcVehicleAction(const rpc::mission::MissionItem::VehicleAction vehicle_action) - { - switch (vehicle_action) { - default: - LogErr() << "Unknown vehicle_action enum value: " - << static_cast(vehicle_action); - // FALLTHROUGH - case rpc::mission::MissionItem_VehicleAction_VEHICLE_ACTION_NONE: - return mavsdk::Mission::MissionItem::VehicleAction::None; - case rpc::mission::MissionItem_VehicleAction_VEHICLE_ACTION_TAKEOFF: - return mavsdk::Mission::MissionItem::VehicleAction::Takeoff; - case rpc::mission::MissionItem_VehicleAction_VEHICLE_ACTION_LAND: - return mavsdk::Mission::MissionItem::VehicleAction::Land; - case rpc::mission::MissionItem_VehicleAction_VEHICLE_ACTION_TRANSITION_TO_FW: - return mavsdk::Mission::MissionItem::VehicleAction::TransitionToFw; - case rpc::mission::MissionItem_VehicleAction_VEHICLE_ACTION_TRANSITION_TO_MC: - return mavsdk::Mission::MissionItem::VehicleAction::TransitionToMc; - } - } - static std::unique_ptr translateToRpcMissionItem(const mavsdk::Mission::MissionItem& mission_item) { @@ -153,8 +111,6 @@ class MissionServiceImpl final : public rpc::mission::MissionService::Service { rpc_obj->set_yaw_deg(mission_item.yaw_deg); - rpc_obj->set_vehicle_action(translateToRpcVehicleAction(mission_item.vehicle_action)); - return rpc_obj; } @@ -187,8 +143,6 @@ class MissionServiceImpl final : public rpc::mission::MissionService::Service { obj.yaw_deg = mission_item.yaw_deg(); - obj.vehicle_action = translateFromRpcVehicleAction(mission_item.vehicle_action()); - return obj; } diff --git a/src/plugins/mission/include/plugins/mission/mission.h b/src/plugins/mission/include/plugins/mission/mission.h index b61d33ae2f..b40548739e 100644 --- a/src/plugins/mission/include/plugins/mission/mission.h +++ b/src/plugins/mission/include/plugins/mission/mission.h @@ -85,27 +85,6 @@ class Mission : public PluginBase { friend std::ostream& operator<<(std::ostream& str, Mission::MissionItem::CameraAction const& camera_action); - /** - * @brief Possible vehicle actions at a mission item - */ - enum class VehicleAction { - None, /**< @brief No action. */ - Takeoff, /**< @brief Vehicle will takeoff and go to defined waypoint. */ - Land, /**< @brief When a waypoint is reached vehicle will land at current position. */ - TransitionToFw, /**< @brief When a waypoint is reached vehicle will transition to - fixed-wing mode. */ - TransitionToMc, /**< @brief When a waypoint is reached vehicle will transition to - multi-copter mode. */ - }; - - /** - * @brief Stream operator to print information about a `Mission::VehicleAction`. - * - * @return A reference to the stream. - */ - friend std::ostream& - operator<<(std::ostream& str, Mission::MissionItem::VehicleAction const& vehicle_action); - double latitude_deg{double(NAN)}; /**< @brief Latitude in degrees (range: -90 to +90) */ double longitude_deg{double(NAN)}; /**< @brief Longitude in degrees (range: -180 to +180) */ float relative_altitude_m{ @@ -124,8 +103,6 @@ class Mission : public PluginBase { float acceptance_radius_m{ float(NAN)}; /**< @brief Radius for completing a mission item (in metres) */ float yaw_deg{float(NAN)}; /**< @brief Absolute yaw angle (in degrees) */ - VehicleAction - vehicle_action{}; /**< @brief Vehicle action to trigger at this mission item. */ }; /** diff --git a/src/plugins/mission/mission.cpp b/src/plugins/mission/mission.cpp index 9b391ac1c2..a79d384055 100644 --- a/src/plugins/mission/mission.cpp +++ b/src/plugins/mission/mission.cpp @@ -136,25 +136,6 @@ std::ostream& operator<<(std::ostream& str, Mission::MissionItem::CameraAction c return str << "Unknown"; } } - -std::ostream& -operator<<(std::ostream& str, Mission::MissionItem::VehicleAction const& vehicle_action) -{ - switch (vehicle_action) { - case Mission::MissionItem::VehicleAction::None: - return str << "None"; - case Mission::MissionItem::VehicleAction::Takeoff: - return str << "Takeoff"; - case Mission::MissionItem::VehicleAction::Land: - return str << "Land"; - case Mission::MissionItem::VehicleAction::TransitionToFw: - return str << "Transition To Fw"; - case Mission::MissionItem::VehicleAction::TransitionToMc: - return str << "Transition To Mc"; - default: - return str << "Unknown"; - } -} bool operator==(const Mission::MissionItem& lhs, const Mission::MissionItem& rhs) { return ((std::isnan(rhs.latitude_deg) && std::isnan(lhs.latitude_deg)) || @@ -177,8 +158,7 @@ bool operator==(const Mission::MissionItem& lhs, const Mission::MissionItem& rhs rhs.camera_photo_interval_s == lhs.camera_photo_interval_s) && ((std::isnan(rhs.acceptance_radius_m) && std::isnan(lhs.acceptance_radius_m)) || rhs.acceptance_radius_m == lhs.acceptance_radius_m) && - ((std::isnan(rhs.yaw_deg) && std::isnan(lhs.yaw_deg)) || rhs.yaw_deg == lhs.yaw_deg) && - (rhs.vehicle_action == lhs.vehicle_action); + ((std::isnan(rhs.yaw_deg) && std::isnan(lhs.yaw_deg)) || rhs.yaw_deg == lhs.yaw_deg); } std::ostream& operator<<(std::ostream& str, Mission::MissionItem const& mission_item) @@ -197,7 +177,6 @@ std::ostream& operator<<(std::ostream& str, Mission::MissionItem const& mission_ str << " camera_photo_interval_s: " << mission_item.camera_photo_interval_s << '\n'; str << " acceptance_radius_m: " << mission_item.acceptance_radius_m << '\n'; str << " yaw_deg: " << mission_item.yaw_deg << '\n'; - str << " vehicle_action: " << mission_item.vehicle_action << '\n'; str << '}'; return str; }