diff --git a/proto b/proto index 218d2397c2..4d2e9c4c1f 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 218d2397c236bd0c27eb8bd81a2f27eb03364608 +Subproject commit 4d2e9c4c1fef56e4d954fbfd9c550ee945cb50e7 diff --git a/src/integration_tests/telemetry_async.cpp b/src/integration_tests/telemetry_async.cpp index 6a21d4c498..95ef9827e4 100644 --- a/src/integration_tests/telemetry_async.cpp +++ b/src/integration_tests/telemetry_async.cpp @@ -264,7 +264,10 @@ void print_angular_velocity_body(Telemetry::AngularVelocityBody angular_velocity void print_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics) { std::cout << "async Airspeed: " << fixedwing_metrics.airspeed_m_s << " m/s, " + << "Groundspeed: " << fixedwing_metrics.groundspeed_m_s << " m/s, " + << "Heading: " << fixedwing_metrics.heading_deg << " deg, " << "Throttle: " << fixedwing_metrics.throttle_percentage << " %, " + << "Altitude: " << fixedwing_metrics.absolute_altitude_m << " m (MSL), " << "Climb: " << fixedwing_metrics.climb_rate_m_s << " m/s" << '\n'; _received_fixedwing_metrics = true; } diff --git a/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h b/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h index 07b1addabe..d4ea624ddd 100644 --- a/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h +++ b/src/mavsdk/plugins/telemetry/include/plugins/telemetry/telemetry.h @@ -813,6 +813,10 @@ class Telemetry : public PluginBase { float(NAN)}; /**< @brief Current indicated airspeed (IAS) in metres per second */ float throttle_percentage{float(NAN)}; /**< @brief Current throttle setting (0 to 100) */ float climb_rate_m_s{float(NAN)}; /**< @brief Current climb rate in metres per second */ + float groundspeed_m_s{float(NAN)}; /**< @brief Current groundspeed metres per second */ + float heading_deg{ + float(NAN)}; /**< @brief Current heading in compass units (0-360, 0=north) */ + float absolute_altitude_m{float(NAN)}; /**< @brief Current altitude in metres (MSL) */ }; /** diff --git a/src/mavsdk/plugins/telemetry/telemetry.cpp b/src/mavsdk/plugins/telemetry/telemetry.cpp index f8b04f79f2..76be2949d7 100644 --- a/src/mavsdk/plugins/telemetry/telemetry.cpp +++ b/src/mavsdk/plugins/telemetry/telemetry.cpp @@ -1322,7 +1322,13 @@ bool operator==(const Telemetry::FixedwingMetrics& lhs, const Telemetry::Fixedwi ((std::isnan(rhs.throttle_percentage) && std::isnan(lhs.throttle_percentage)) || rhs.throttle_percentage == lhs.throttle_percentage) && ((std::isnan(rhs.climb_rate_m_s) && std::isnan(lhs.climb_rate_m_s)) || - rhs.climb_rate_m_s == lhs.climb_rate_m_s); + rhs.climb_rate_m_s == lhs.climb_rate_m_s) && + ((std::isnan(rhs.groundspeed_m_s) && std::isnan(lhs.groundspeed_m_s)) || + rhs.groundspeed_m_s == lhs.groundspeed_m_s) && + ((std::isnan(rhs.heading_deg) && std::isnan(lhs.heading_deg)) || + rhs.heading_deg == lhs.heading_deg) && + ((std::isnan(rhs.absolute_altitude_m) && std::isnan(lhs.absolute_altitude_m)) || + rhs.absolute_altitude_m == lhs.absolute_altitude_m); } std::ostream& operator<<(std::ostream& str, Telemetry::FixedwingMetrics const& fixedwing_metrics) @@ -1332,6 +1338,9 @@ std::ostream& operator<<(std::ostream& str, Telemetry::FixedwingMetrics const& f str << " airspeed_m_s: " << fixedwing_metrics.airspeed_m_s << '\n'; str << " throttle_percentage: " << fixedwing_metrics.throttle_percentage << '\n'; str << " climb_rate_m_s: " << fixedwing_metrics.climb_rate_m_s << '\n'; + str << " groundspeed_m_s: " << fixedwing_metrics.groundspeed_m_s << '\n'; + str << " heading_deg: " << fixedwing_metrics.heading_deg << '\n'; + str << " absolute_altitude_m: " << fixedwing_metrics.absolute_altitude_m << '\n'; str << '}'; return str; } diff --git a/src/mavsdk/plugins/telemetry/telemetry_impl.cpp b/src/mavsdk/plugins/telemetry/telemetry_impl.cpp index 554678e439..bf052d4490 100644 --- a/src/mavsdk/plugins/telemetry/telemetry_impl.cpp +++ b/src/mavsdk/plugins/telemetry/telemetry_impl.cpp @@ -994,7 +994,10 @@ void TelemetryImpl::process_fixedwing_metrics(const mavlink_message_t& message) Telemetry::FixedwingMetrics new_fixedwing_metrics; new_fixedwing_metrics.airspeed_m_s = vfr_hud.airspeed; + new_fixedwing_metrics.groundspeed_m_s = vfr_hud.groundspeed; + new_fixedwing_metrics.heading_deg = vfr_hud.heading; new_fixedwing_metrics.throttle_percentage = vfr_hud.throttle * 1e-2f; + new_fixedwing_metrics.absolute_altitude_m = vfr_hud.alt; new_fixedwing_metrics.climb_rate_m_s = vfr_hud.climb; set_fixedwing_metrics(new_fixedwing_metrics); diff --git a/src/mavsdk/plugins/telemetry_server/include/plugins/telemetry_server/telemetry_server.h b/src/mavsdk/plugins/telemetry_server/include/plugins/telemetry_server/telemetry_server.h index 1a23aa2965..7ffd54e84f 100644 --- a/src/mavsdk/plugins/telemetry_server/include/plugins/telemetry_server/telemetry_server.h +++ b/src/mavsdk/plugins/telemetry_server/include/plugins/telemetry_server/telemetry_server.h @@ -757,6 +757,10 @@ class TelemetryServer : public ServerPluginBase { float(NAN)}; /**< @brief Current indicated airspeed (IAS) in metres per second */ float throttle_percentage{float(NAN)}; /**< @brief Current throttle setting (0 to 100) */ float climb_rate_m_s{float(NAN)}; /**< @brief Current climb rate in metres per second */ + float groundspeed_m_s{float(NAN)}; /**< @brief Current groundspeed metres per second */ + float heading_deg{ + float(NAN)}; /**< @brief Current heading in compass units (0-360, 0=north) */ + float absolute_altitude_m{float(NAN)}; /**< @brief Current altitude in metres (MSL) */ }; /** @@ -1052,6 +1056,24 @@ class TelemetryServer : public ServerPluginBase { */ Result publish_distance_sensor(DistanceSensor distance_sensor) const; + /** + * @brief Publish to "attitude" updates. + * + * This function is blocking. + * + * @return Result of request. + */ + Result publish_attitude(EulerAngle angle, AngularVelocityBody angular_velocity) const; + + /** + * @brief Publish to "Visual Flight Rules HUD" updates. + * + * This function is blocking. + * + * @return Result of request. + */ + Result publish_visual_flight_rules_hud(FixedwingMetrics fixed_wing_metrics) const; + /** * @brief Copy constructor. */ diff --git a/src/mavsdk/plugins/telemetry_server/telemetry_server.cpp b/src/mavsdk/plugins/telemetry_server/telemetry_server.cpp index ae4a34dd38..7c714a61b7 100644 --- a/src/mavsdk/plugins/telemetry_server/telemetry_server.cpp +++ b/src/mavsdk/plugins/telemetry_server/telemetry_server.cpp @@ -131,6 +131,18 @@ TelemetryServer::publish_distance_sensor(DistanceSensor distance_sensor) const return _impl->publish_distance_sensor(distance_sensor); } +TelemetryServer::Result +TelemetryServer::publish_attitude(EulerAngle angle, AngularVelocityBody angular_velocity) const +{ + return _impl->publish_attitude(angle, angular_velocity); +} + +TelemetryServer::Result +TelemetryServer::publish_visual_flight_rules_hud(FixedwingMetrics fixed_wing_metrics) const +{ + return _impl->publish_visual_flight_rules_hud(fixed_wing_metrics); +} + bool operator==(const TelemetryServer::Position& lhs, const TelemetryServer::Position& rhs) { return ((std::isnan(rhs.latitude_deg) && std::isnan(lhs.latitude_deg)) || @@ -639,7 +651,13 @@ bool operator==( ((std::isnan(rhs.throttle_percentage) && std::isnan(lhs.throttle_percentage)) || rhs.throttle_percentage == lhs.throttle_percentage) && ((std::isnan(rhs.climb_rate_m_s) && std::isnan(lhs.climb_rate_m_s)) || - rhs.climb_rate_m_s == lhs.climb_rate_m_s); + rhs.climb_rate_m_s == lhs.climb_rate_m_s) && + ((std::isnan(rhs.groundspeed_m_s) && std::isnan(lhs.groundspeed_m_s)) || + rhs.groundspeed_m_s == lhs.groundspeed_m_s) && + ((std::isnan(rhs.heading_deg) && std::isnan(lhs.heading_deg)) || + rhs.heading_deg == lhs.heading_deg) && + ((std::isnan(rhs.absolute_altitude_m) && std::isnan(lhs.absolute_altitude_m)) || + rhs.absolute_altitude_m == lhs.absolute_altitude_m); } std::ostream& @@ -650,6 +668,9 @@ operator<<(std::ostream& str, TelemetryServer::FixedwingMetrics const& fixedwing str << " airspeed_m_s: " << fixedwing_metrics.airspeed_m_s << '\n'; str << " throttle_percentage: " << fixedwing_metrics.throttle_percentage << '\n'; str << " climb_rate_m_s: " << fixedwing_metrics.climb_rate_m_s << '\n'; + str << " groundspeed_m_s: " << fixedwing_metrics.groundspeed_m_s << '\n'; + str << " heading_deg: " << fixedwing_metrics.heading_deg << '\n'; + str << " absolute_altitude_m: " << fixedwing_metrics.absolute_altitude_m << '\n'; str << '}'; return str; } diff --git a/src/mavsdk/plugins/telemetry_server/telemetry_server_impl.cpp b/src/mavsdk/plugins/telemetry_server/telemetry_server_impl.cpp index f68d04772e..f7dca5d3d8 100644 --- a/src/mavsdk/plugins/telemetry_server/telemetry_server_impl.cpp +++ b/src/mavsdk/plugins/telemetry_server/telemetry_server_impl.cpp @@ -524,4 +524,51 @@ TelemetryServer::Result TelemetryServerImpl::publish_extended_sys_state( TelemetryServer::Result::Unsupported; } +TelemetryServer::Result TelemetryServerImpl::publish_attitude( + TelemetryServer::EulerAngle attitude, TelemetryServer::AngularVelocityBody angular_velocity) +{ + return _server_component_impl->queue_message( + [&](MavlinkAddress mavlink_address, uint8_t channel) { + mavlink_message_t message; + mavlink_msg_attitude_pack_chan( + mavlink_address.system_id, + mavlink_address.component_id, + channel, + &message, + static_cast(attitude.timestamp_us / 1000.F), + attitude.roll_deg * M_PI / 180.F, + attitude.pitch_deg * M_PI / 180.F, + attitude.yaw_deg * M_PI / 180.F, + angular_velocity.roll_rad_s, + angular_velocity.pitch_rad_s, + angular_velocity.yaw_rad_s); + return message; + }) ? + TelemetryServer::Result::Success : + TelemetryServer::Result::Unsupported; +} + +TelemetryServer::Result TelemetryServerImpl::publish_visual_flight_rules_hud( + TelemetryServer::FixedwingMetrics fixed_wing_metrics) +{ + return _server_component_impl->queue_message( + [&](MavlinkAddress mavlink_address, uint8_t channel) { + mavlink_message_t message; + mavlink_msg_vfr_hud_pack_chan( + mavlink_address.system_id, + mavlink_address.component_id, + channel, + &message, + fixed_wing_metrics.airspeed_m_s, + fixed_wing_metrics.groundspeed_m_s, + static_cast(std::round(fixed_wing_metrics.heading_deg)), + static_cast(std::round(fixed_wing_metrics.throttle_percentage)), + fixed_wing_metrics.absolute_altitude_m, + fixed_wing_metrics.climb_rate_m_s); + return message; + }) ? + TelemetryServer::Result::Success : + TelemetryServer::Result::Unsupported; +} + } // namespace mavsdk diff --git a/src/mavsdk/plugins/telemetry_server/telemetry_server_impl.h b/src/mavsdk/plugins/telemetry_server/telemetry_server_impl.h index b1f561ec9f..9afd9ff74f 100644 --- a/src/mavsdk/plugins/telemetry_server/telemetry_server_impl.h +++ b/src/mavsdk/plugins/telemetry_server/telemetry_server_impl.h @@ -76,6 +76,13 @@ class TelemetryServerImpl : public ServerPluginImplBase { TelemetryServer::Result publish_extended_sys_state( TelemetryServer::VtolState vtol_state, TelemetryServer::LandedState landed_state); + TelemetryServer::Result publish_attitude( + TelemetryServer::EulerAngle attitude, + TelemetryServer::AngularVelocityBody angular_velocity); + + TelemetryServer::Result + publish_visual_flight_rules_hud(TelemetryServer::FixedwingMetrics fixed_wing_metrics); + private: bool _send_home(); diff --git a/src/mavsdk_server/src/generated/telemetry/telemetry.pb.cc b/src/mavsdk_server/src/generated/telemetry/telemetry.pb.cc index 4a0ae51ad8..c5668bb277 100644 --- a/src/mavsdk_server/src/generated/telemetry/telemetry.pb.cc +++ b/src/mavsdk_server/src/generated/telemetry/telemetry.pb.cc @@ -1880,6 +1880,9 @@ inline constexpr FixedwingMetrics::Impl_::Impl_( : airspeed_m_s_{0}, throttle_percentage_{0}, climb_rate_m_s_{0}, + groundspeed_m_s_{0}, + heading_deg_{0}, + absolute_altitude_m_{0}, _cached_size_{0} {} template @@ -4903,6 +4906,9 @@ const ::uint32_t PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::FixedwingMetrics, _impl_.airspeed_m_s_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::FixedwingMetrics, _impl_.throttle_percentage_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::FixedwingMetrics, _impl_.climb_rate_m_s_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::FixedwingMetrics, _impl_.groundspeed_m_s_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::FixedwingMetrics, _impl_.heading_deg_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::FixedwingMetrics, _impl_.absolute_altitude_m_), ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::AccelerationFrd, _internal_metadata_), ~0u, // no _extensions_ @@ -5132,13 +5138,13 @@ static const ::_pbi::MigrationSchema {1321, 1331, -1, sizeof(::mavsdk::rpc::telemetry::PositionVelocityNed)}, {1333, -1, -1, sizeof(::mavsdk::rpc::telemetry::GroundTruth)}, {1344, -1, -1, sizeof(::mavsdk::rpc::telemetry::FixedwingMetrics)}, - {1355, -1, -1, sizeof(::mavsdk::rpc::telemetry::AccelerationFrd)}, - {1366, -1, -1, sizeof(::mavsdk::rpc::telemetry::AngularVelocityFrd)}, - {1377, -1, -1, sizeof(::mavsdk::rpc::telemetry::MagneticFieldFrd)}, - {1388, 1401, -1, sizeof(::mavsdk::rpc::telemetry::Imu)}, - {1406, -1, -1, sizeof(::mavsdk::rpc::telemetry::GpsGlobalOrigin)}, - {1417, -1, -1, sizeof(::mavsdk::rpc::telemetry::Altitude)}, - {1431, -1, -1, sizeof(::mavsdk::rpc::telemetry::TelemetryResult)}, + {1358, -1, -1, sizeof(::mavsdk::rpc::telemetry::AccelerationFrd)}, + {1369, -1, -1, sizeof(::mavsdk::rpc::telemetry::AngularVelocityFrd)}, + {1380, -1, -1, sizeof(::mavsdk::rpc::telemetry::MagneticFieldFrd)}, + {1391, 1404, -1, sizeof(::mavsdk::rpc::telemetry::Imu)}, + {1409, -1, -1, sizeof(::mavsdk::rpc::telemetry::GpsGlobalOrigin)}, + {1420, -1, -1, sizeof(::mavsdk::rpc::telemetry::Altitude)}, + {1434, -1, -1, sizeof(::mavsdk::rpc::telemetry::TelemetryResult)}, }; static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::telemetry::_SubscribePositionRequest_default_instance_._instance, @@ -5551,241 +5557,244 @@ const char descriptor_table_protodef_telemetry_2ftelemetry_2eproto[] ABSL_ATTRIB "rpc.telemetry.VelocityNed\"r\n\013GroundTruth" "\022\035\n\014latitude_deg\030\001 \001(\001B\007\202\265\030\003NaN\022\036\n\rlongi" "tude_deg\030\002 \001(\001B\007\202\265\030\003NaN\022$\n\023absolute_alti" - "tude_m\030\003 \001(\002B\007\202\265\030\003NaN\"x\n\020FixedwingMetric" - "s\022\035\n\014airspeed_m_s\030\001 \001(\002B\007\202\265\030\003NaN\022$\n\023thro" - "ttle_percentage\030\002 \001(\002B\007\202\265\030\003NaN\022\037\n\016climb_" - "rate_m_s\030\003 \001(\002B\007\202\265\030\003NaN\"i\n\017AccelerationF" - "rd\022\035\n\014forward_m_s2\030\001 \001(\002B\007\202\265\030\003NaN\022\033\n\nrig" - "ht_m_s2\030\002 \001(\002B\007\202\265\030\003NaN\022\032\n\tdown_m_s2\030\003 \001(" - "\002B\007\202\265\030\003NaN\"o\n\022AngularVelocityFrd\022\036\n\rforw" - "ard_rad_s\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013right_rad_s\030" - "\002 \001(\002B\007\202\265\030\003NaN\022\033\n\ndown_rad_s\030\003 \001(\002B\007\202\265\030\003" - "NaN\"m\n\020MagneticFieldFrd\022\036\n\rforward_gauss" - "\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013right_gauss\030\002 \001(\002B\007\202\265" - "\030\003NaN\022\033\n\ndown_gauss\030\003 \001(\002B\007\202\265\030\003NaN\"\213\002\n\003I" - "mu\022\?\n\020acceleration_frd\030\001 \001(\0132%.mavsdk.rp" - "c.telemetry.AccelerationFrd\022F\n\024angular_v" - "elocity_frd\030\002 \001(\0132(.mavsdk.rpc.telemetry" - ".AngularVelocityFrd\022B\n\022magnetic_field_fr" - "d\030\003 \001(\0132&.mavsdk.rpc.telemetry.MagneticF" - "ieldFrd\022!\n\020temperature_degc\030\004 \001(\002B\007\202\265\030\003N" - "aN\022\024\n\014timestamp_us\030\005 \001(\004\"m\n\017GpsGlobalOri" - "gin\022\035\n\014latitude_deg\030\001 \001(\001B\007\202\265\030\003NaN\022\036\n\rlo" - "ngitude_deg\030\002 \001(\001B\007\202\265\030\003NaN\022\033\n\naltitude_m" - "\030\003 \001(\002B\007\202\265\030\003NaN\"\346\001\n\010Altitude\022%\n\024altitude" - "_monotonic_m\030\001 \001(\002B\007\202\265\030\003NaN\022 \n\017altitude_" - "amsl_m\030\002 \001(\002B\007\202\265\030\003NaN\022!\n\020altitude_local_" - "m\030\003 \001(\002B\007\202\265\030\003NaN\022$\n\023altitude_relative_m\030" - "\004 \001(\002B\007\202\265\030\003NaN\022#\n\022altitude_terrain_m\030\005 \001" - "(\002B\007\202\265\030\003NaN\022#\n\022bottom_clearance_m\030\006 \001(\002B" - "\007\202\265\030\003NaN\"\241\002\n\017TelemetryResult\022<\n\006result\030\001" - " \001(\0162,.mavsdk.rpc.telemetry.TelemetryRes" - "ult.Result\022\022\n\nresult_str\030\002 \001(\t\"\273\001\n\006Resul" - "t\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020" - "\001\022\024\n\020RESULT_NO_SYSTEM\020\002\022\033\n\027RESULT_CONNEC" - "TION_ERROR\020\003\022\017\n\013RESULT_BUSY\020\004\022\031\n\025RESULT_" - "COMMAND_DENIED\020\005\022\022\n\016RESULT_TIMEOUT\020\006\022\026\n\022" - "RESULT_UNSUPPORTED\020\007*\244\001\n\007FixType\022\023\n\017FIX_" - "TYPE_NO_GPS\020\000\022\023\n\017FIX_TYPE_NO_FIX\020\001\022\023\n\017FI" - "X_TYPE_FIX_2D\020\002\022\023\n\017FIX_TYPE_FIX_3D\020\003\022\025\n\021" - "FIX_TYPE_FIX_DGPS\020\004\022\026\n\022FIX_TYPE_RTK_FLOA" - "T\020\005\022\026\n\022FIX_TYPE_RTK_FIXED\020\006*\206\003\n\nFlightMo" - "de\022\027\n\023FLIGHT_MODE_UNKNOWN\020\000\022\025\n\021FLIGHT_MO" - "DE_READY\020\001\022\027\n\023FLIGHT_MODE_TAKEOFF\020\002\022\024\n\020F" - "LIGHT_MODE_HOLD\020\003\022\027\n\023FLIGHT_MODE_MISSION" - "\020\004\022 \n\034FLIGHT_MODE_RETURN_TO_LAUNCH\020\005\022\024\n\020" - "FLIGHT_MODE_LAND\020\006\022\030\n\024FLIGHT_MODE_OFFBOA" - "RD\020\007\022\031\n\025FLIGHT_MODE_FOLLOW_ME\020\010\022\026\n\022FLIGH" - "T_MODE_MANUAL\020\t\022\026\n\022FLIGHT_MODE_ALTCTL\020\n\022" - "\026\n\022FLIGHT_MODE_POSCTL\020\013\022\024\n\020FLIGHT_MODE_A" - "CRO\020\014\022\032\n\026FLIGHT_MODE_STABILIZED\020\r\022\031\n\025FLI" - "GHT_MODE_RATTITUDE\020\016*\371\001\n\016StatusTextType\022" - "\032\n\026STATUS_TEXT_TYPE_DEBUG\020\000\022\031\n\025STATUS_TE" - "XT_TYPE_INFO\020\001\022\033\n\027STATUS_TEXT_TYPE_NOTIC" - "E\020\002\022\034\n\030STATUS_TEXT_TYPE_WARNING\020\003\022\032\n\026STA" - "TUS_TEXT_TYPE_ERROR\020\004\022\035\n\031STATUS_TEXT_TYP" - "E_CRITICAL\020\005\022\032\n\026STATUS_TEXT_TYPE_ALERT\020\006" - "\022\036\n\032STATUS_TEXT_TYPE_EMERGENCY\020\007*\223\001\n\013Lan" - "dedState\022\030\n\024LANDED_STATE_UNKNOWN\020\000\022\032\n\026LA" - "NDED_STATE_ON_GROUND\020\001\022\027\n\023LANDED_STATE_I" - "N_AIR\020\002\022\033\n\027LANDED_STATE_TAKING_OFF\020\003\022\030\n\024" - "LANDED_STATE_LANDING\020\004*\215\001\n\tVtolState\022\030\n\024" - "VTOL_STATE_UNDEFINED\020\000\022\037\n\033VTOL_STATE_TRA" - "NSITION_TO_FW\020\001\022\037\n\033VTOL_STATE_TRANSITION" - "_TO_MC\020\002\022\021\n\rVTOL_STATE_MC\020\003\022\021\n\rVTOL_STAT" - "E_FW\020\0042\3075\n\020TelemetryService\022o\n\021Subscribe" - "Position\022..mavsdk.rpc.telemetry.Subscrib" - "ePositionRequest\032&.mavsdk.rpc.telemetry." - "PositionResponse\"\0000\001\022c\n\rSubscribeHome\022*." - "mavsdk.rpc.telemetry.SubscribeHomeReques" - "t\032\".mavsdk.rpc.telemetry.HomeResponse\"\0000" - "\001\022f\n\016SubscribeInAir\022+.mavsdk.rpc.telemet" - "ry.SubscribeInAirRequest\032#.mavsdk.rpc.te" - "lemetry.InAirResponse\"\0000\001\022x\n\024SubscribeLa" - "ndedState\0221.mavsdk.rpc.telemetry.Subscri" - "beLandedStateRequest\032).mavsdk.rpc.teleme" - "try.LandedStateResponse\"\0000\001\022f\n\016Subscribe" - "Armed\022+.mavsdk.rpc.telemetry.SubscribeAr" - "medRequest\032#.mavsdk.rpc.telemetry.ArmedR" - "esponse\"\0000\001\022r\n\022SubscribeVtolState\022/.mavs" - "dk.rpc.telemetry.SubscribeVtolStateReque" - "st\032\'.mavsdk.rpc.telemetry.VtolStateRespo" - "nse\"\0000\001\022\215\001\n\033SubscribeAttitudeQuaternion\022" - "8.mavsdk.rpc.telemetry.SubscribeAttitude" - "QuaternionRequest\0320.mavsdk.rpc.telemetry" - ".AttitudeQuaternionResponse\"\0000\001\022~\n\026Subsc" - "ribeAttitudeEuler\0223.mavsdk.rpc.telemetry" - ".SubscribeAttitudeEulerRequest\032+.mavsdk." - "rpc.telemetry.AttitudeEulerResponse\"\0000\001\022" - "\250\001\n$SubscribeAttitudeAngularVelocityBody" - "\022A.mavsdk.rpc.telemetry.SubscribeAttitud" - "eAngularVelocityBodyRequest\0329.mavsdk.rpc" - ".telemetry.AttitudeAngularVelocityBodyRe" - "sponse\"\0000\001\022x\n\024SubscribeVelocityNed\0221.mav" - "sdk.rpc.telemetry.SubscribeVelocityNedRe" - "quest\032).mavsdk.rpc.telemetry.VelocityNed" - "Response\"\0000\001\022l\n\020SubscribeGpsInfo\022-.mavsd" - "k.rpc.telemetry.SubscribeGpsInfoRequest\032" - "%.mavsdk.rpc.telemetry.GpsInfoResponse\"\000" - "0\001\022i\n\017SubscribeRawGps\022,.mavsdk.rpc.telem" - "etry.SubscribeRawGpsRequest\032$.mavsdk.rpc" - ".telemetry.RawGpsResponse\"\0000\001\022l\n\020Subscri" - "beBattery\022-.mavsdk.rpc.telemetry.Subscri" - "beBatteryRequest\032%.mavsdk.rpc.telemetry." - "BatteryResponse\"\0000\001\022u\n\023SubscribeFlightMo" - "de\0220.mavsdk.rpc.telemetry.SubscribeFligh" - "tModeRequest\032(.mavsdk.rpc.telemetry.Flig" - "htModeResponse\"\0000\001\022i\n\017SubscribeHealth\022,." - "mavsdk.rpc.telemetry.SubscribeHealthRequ" - "est\032$.mavsdk.rpc.telemetry.HealthRespons" - "e\"\0000\001\022o\n\021SubscribeRcStatus\022..mavsdk.rpc." - "telemetry.SubscribeRcStatusRequest\032&.mav" - "sdk.rpc.telemetry.RcStatusResponse\"\0000\001\022u" - "\n\023SubscribeStatusText\0220.mavsdk.rpc.telem" - "etry.SubscribeStatusTextRequest\032(.mavsdk" - ".rpc.telemetry.StatusTextResponse\"\0000\001\022\226\001" - "\n\036SubscribeActuatorControlTarget\022;.mavsd" - "k.rpc.telemetry.SubscribeActuatorControl" - "TargetRequest\0323.mavsdk.rpc.telemetry.Act" - "uatorControlTargetResponse\"\0000\001\022\223\001\n\035Subsc" - "ribeActuatorOutputStatus\022:.mavsdk.rpc.te" - "lemetry.SubscribeActuatorOutputStatusReq" - "uest\0322.mavsdk.rpc.telemetry.ActuatorOutp" - "utStatusResponse\"\0000\001\022o\n\021SubscribeOdometr" - "y\022..mavsdk.rpc.telemetry.SubscribeOdomet" - "ryRequest\032&.mavsdk.rpc.telemetry.Odometr" - "yResponse\"\0000\001\022\220\001\n\034SubscribePositionVeloc" - "ityNed\0229.mavsdk.rpc.telemetry.SubscribeP" - "ositionVelocityNedRequest\0321.mavsdk.rpc.t" - "elemetry.PositionVelocityNedResponse\"\0000\001" - "\022x\n\024SubscribeGroundTruth\0221.mavsdk.rpc.te" - "lemetry.SubscribeGroundTruthRequest\032).ma" - "vsdk.rpc.telemetry.GroundTruthResponse\"\000" - "0\001\022\207\001\n\031SubscribeFixedwingMetrics\0226.mavsd" - "k.rpc.telemetry.SubscribeFixedwingMetric" - "sRequest\032..mavsdk.rpc.telemetry.Fixedwin" - "gMetricsResponse\"\0000\001\022`\n\014SubscribeImu\022).m" - "avsdk.rpc.telemetry.SubscribeImuRequest\032" - "!.mavsdk.rpc.telemetry.ImuResponse\"\0000\001\022r" - "\n\022SubscribeScaledImu\022/.mavsdk.rpc.teleme" - "try.SubscribeScaledImuRequest\032\'.mavsdk.r" - "pc.telemetry.ScaledImuResponse\"\0000\001\022i\n\017Su" - "bscribeRawImu\022,.mavsdk.rpc.telemetry.Sub" - "scribeRawImuRequest\032$.mavsdk.rpc.telemet" - "ry.RawImuResponse\"\0000\001\022x\n\024SubscribeHealth" - "AllOk\0221.mavsdk.rpc.telemetry.SubscribeHe" - "althAllOkRequest\032).mavsdk.rpc.telemetry." - "HealthAllOkResponse\"\0000\001\022~\n\026SubscribeUnix" - "EpochTime\0223.mavsdk.rpc.telemetry.Subscri" - "beUnixEpochTimeRequest\032+.mavsdk.rpc.tele" - "metry.UnixEpochTimeResponse\"\0000\001\022\201\001\n\027Subs" - "cribeDistanceSensor\0224.mavsdk.rpc.telemet" - "ry.SubscribeDistanceSensorRequest\032,.mavs" - "dk.rpc.telemetry.DistanceSensorResponse\"" - "\0000\001\022\201\001\n\027SubscribeScaledPressure\0224.mavsdk" - ".rpc.telemetry.SubscribeScaledPressureRe" - "quest\032,.mavsdk.rpc.telemetry.ScaledPress" - "ureResponse\"\0000\001\022l\n\020SubscribeHeading\022-.ma" - "vsdk.rpc.telemetry.SubscribeHeadingReque" - "st\032%.mavsdk.rpc.telemetry.HeadingRespons" - "e\"\0000\001\022o\n\021SubscribeAltitude\022..mavsdk.rpc." - "telemetry.SubscribeAltitudeRequest\032&.mav" - "sdk.rpc.telemetry.AltitudeResponse\"\0000\001\022p" - "\n\017SetRatePosition\022,.mavsdk.rpc.telemetry" - ".SetRatePositionRequest\032-.mavsdk.rpc.tel" - "emetry.SetRatePositionResponse\"\000\022d\n\013SetR" - "ateHome\022(.mavsdk.rpc.telemetry.SetRateHo" - "meRequest\032).mavsdk.rpc.telemetry.SetRate" - "HomeResponse\"\000\022g\n\014SetRateInAir\022).mavsdk." - "rpc.telemetry.SetRateInAirRequest\032*.mavs" - "dk.rpc.telemetry.SetRateInAirResponse\"\000\022" - "y\n\022SetRateLandedState\022/.mavsdk.rpc.telem" - "etry.SetRateLandedStateRequest\0320.mavsdk." - "rpc.telemetry.SetRateLandedStateResponse" - "\"\000\022s\n\020SetRateVtolState\022-.mavsdk.rpc.tele" - "metry.SetRateVtolStateRequest\032..mavsdk.r" - "pc.telemetry.SetRateVtolStateResponse\"\000\022" - "\216\001\n\031SetRateAttitudeQuaternion\0226.mavsdk.r" - "pc.telemetry.SetRateAttitudeQuaternionRe" - "quest\0327.mavsdk.rpc.telemetry.SetRateAtti" - "tudeQuaternionResponse\"\000\022\177\n\024SetRateAttit" - "udeEuler\0221.mavsdk.rpc.telemetry.SetRateA" - "ttitudeEulerRequest\0322.mavsdk.rpc.telemet" - "ry.SetRateAttitudeEulerResponse\"\000\022y\n\022Set" - "RateVelocityNed\022/.mavsdk.rpc.telemetry.S" - "etRateVelocityNedRequest\0320.mavsdk.rpc.te" - "lemetry.SetRateVelocityNedResponse\"\000\022m\n\016" - "SetRateGpsInfo\022+.mavsdk.rpc.telemetry.Se" - "tRateGpsInfoRequest\032,.mavsdk.rpc.telemet" - "ry.SetRateGpsInfoResponse\"\000\022m\n\016SetRateBa" - "ttery\022+.mavsdk.rpc.telemetry.SetRateBatt" - "eryRequest\032,.mavsdk.rpc.telemetry.SetRat" - "eBatteryResponse\"\000\022p\n\017SetRateRcStatus\022,." - "mavsdk.rpc.telemetry.SetRateRcStatusRequ" - "est\032-.mavsdk.rpc.telemetry.SetRateRcStat" - "usResponse\"\000\022\227\001\n\034SetRateActuatorControlT" - "arget\0229.mavsdk.rpc.telemetry.SetRateActu" - "atorControlTargetRequest\032:.mavsdk.rpc.te" - "lemetry.SetRateActuatorControlTargetResp" - "onse\"\000\022\224\001\n\033SetRateActuatorOutputStatus\0228" - ".mavsdk.rpc.telemetry.SetRateActuatorOut" - "putStatusRequest\0329.mavsdk.rpc.telemetry." - "SetRateActuatorOutputStatusResponse\"\000\022p\n" - "\017SetRateOdometry\022,.mavsdk.rpc.telemetry." - "SetRateOdometryRequest\032-.mavsdk.rpc.tele" - "metry.SetRateOdometryResponse\"\000\022\221\001\n\032SetR" - "atePositionVelocityNed\0227.mavsdk.rpc.tele" - "metry.SetRatePositionVelocityNedRequest\032" - "8.mavsdk.rpc.telemetry.SetRatePositionVe" - "locityNedResponse\"\000\022y\n\022SetRateGroundTrut" - "h\022/.mavsdk.rpc.telemetry.SetRateGroundTr" - "uthRequest\0320.mavsdk.rpc.telemetry.SetRat" - "eGroundTruthResponse\"\000\022\210\001\n\027SetRateFixedw" - "ingMetrics\0224.mavsdk.rpc.telemetry.SetRat" - "eFixedwingMetricsRequest\0325.mavsdk.rpc.te" - "lemetry.SetRateFixedwingMetricsResponse\"" - "\000\022a\n\nSetRateImu\022\'.mavsdk.rpc.telemetry.S" - "etRateImuRequest\032(.mavsdk.rpc.telemetry." - "SetRateImuResponse\"\000\022s\n\020SetRateScaledImu" - "\022-.mavsdk.rpc.telemetry.SetRateScaledImu" - "Request\032..mavsdk.rpc.telemetry.SetRateSc" - "aledImuResponse\"\000\022j\n\rSetRateRawImu\022*.mav" - "sdk.rpc.telemetry.SetRateRawImuRequest\032+" - ".mavsdk.rpc.telemetry.SetRateRawImuRespo" - "nse\"\000\022\177\n\024SetRateUnixEpochTime\0221.mavsdk.r" - "pc.telemetry.SetRateUnixEpochTimeRequest" - "\0322.mavsdk.rpc.telemetry.SetRateUnixEpoch" - "TimeResponse\"\000\022\202\001\n\025SetRateDistanceSensor" - "\0222.mavsdk.rpc.telemetry.SetRateDistanceS" - "ensorRequest\0323.mavsdk.rpc.telemetry.SetR" - "ateDistanceSensorResponse\"\000\022p\n\017SetRateAl" - "titude\022,.mavsdk.rpc.telemetry.SetRateAlt" - "itudeRequest\032-.mavsdk.rpc.telemetry.SetR" - "ateAltitudeResponse\"\000\022y\n\022GetGpsGlobalOri" - "gin\022/.mavsdk.rpc.telemetry.GetGpsGlobalO" - "riginRequest\0320.mavsdk.rpc.telemetry.GetG" - "psGlobalOriginResponse\"\000B%\n\023io.mavsdk.te" - "lemetryB\016TelemetryProtob\006proto3" + "tude_m\030\003 \001(\002B\007\202\265\030\003NaN\"\336\001\n\020FixedwingMetri" + "cs\022\035\n\014airspeed_m_s\030\001 \001(\002B\007\202\265\030\003NaN\022$\n\023thr" + "ottle_percentage\030\002 \001(\002B\007\202\265\030\003NaN\022\037\n\016climb" + "_rate_m_s\030\003 \001(\002B\007\202\265\030\003NaN\022 \n\017groundspeed_" + "m_s\030\004 \001(\002B\007\202\265\030\003NaN\022\034\n\013heading_deg\030\005 \001(\002B" + "\007\202\265\030\003NaN\022$\n\023absolute_altitude_m\030\006 \001(\002B\007\202" + "\265\030\003NaN\"i\n\017AccelerationFrd\022\035\n\014forward_m_s" + "2\030\001 \001(\002B\007\202\265\030\003NaN\022\033\n\nright_m_s2\030\002 \001(\002B\007\202\265" + "\030\003NaN\022\032\n\tdown_m_s2\030\003 \001(\002B\007\202\265\030\003NaN\"o\n\022Ang" + "ularVelocityFrd\022\036\n\rforward_rad_s\030\001 \001(\002B\007" + "\202\265\030\003NaN\022\034\n\013right_rad_s\030\002 \001(\002B\007\202\265\030\003NaN\022\033\n" + "\ndown_rad_s\030\003 \001(\002B\007\202\265\030\003NaN\"m\n\020MagneticFi" + "eldFrd\022\036\n\rforward_gauss\030\001 \001(\002B\007\202\265\030\003NaN\022\034" + "\n\013right_gauss\030\002 \001(\002B\007\202\265\030\003NaN\022\033\n\ndown_gau" + "ss\030\003 \001(\002B\007\202\265\030\003NaN\"\213\002\n\003Imu\022\?\n\020acceleratio" + "n_frd\030\001 \001(\0132%.mavsdk.rpc.telemetry.Accel" + "erationFrd\022F\n\024angular_velocity_frd\030\002 \001(\013" + "2(.mavsdk.rpc.telemetry.AngularVelocityF" + "rd\022B\n\022magnetic_field_frd\030\003 \001(\0132&.mavsdk." + "rpc.telemetry.MagneticFieldFrd\022!\n\020temper" + "ature_degc\030\004 \001(\002B\007\202\265\030\003NaN\022\024\n\014timestamp_u" + "s\030\005 \001(\004\"m\n\017GpsGlobalOrigin\022\035\n\014latitude_d" + "eg\030\001 \001(\001B\007\202\265\030\003NaN\022\036\n\rlongitude_deg\030\002 \001(\001" + "B\007\202\265\030\003NaN\022\033\n\naltitude_m\030\003 \001(\002B\007\202\265\030\003NaN\"\346" + "\001\n\010Altitude\022%\n\024altitude_monotonic_m\030\001 \001(" + "\002B\007\202\265\030\003NaN\022 \n\017altitude_amsl_m\030\002 \001(\002B\007\202\265\030" + "\003NaN\022!\n\020altitude_local_m\030\003 \001(\002B\007\202\265\030\003NaN\022" + "$\n\023altitude_relative_m\030\004 \001(\002B\007\202\265\030\003NaN\022#\n" + "\022altitude_terrain_m\030\005 \001(\002B\007\202\265\030\003NaN\022#\n\022bo" + "ttom_clearance_m\030\006 \001(\002B\007\202\265\030\003NaN\"\241\002\n\017Tele" + "metryResult\022<\n\006result\030\001 \001(\0162,.mavsdk.rpc" + ".telemetry.TelemetryResult.Result\022\022\n\nres" + "ult_str\030\002 \001(\t\"\273\001\n\006Result\022\022\n\016RESULT_UNKNO" + "WN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\024\n\020RESULT_NO_SY" + "STEM\020\002\022\033\n\027RESULT_CONNECTION_ERROR\020\003\022\017\n\013R" + "ESULT_BUSY\020\004\022\031\n\025RESULT_COMMAND_DENIED\020\005\022" + "\022\n\016RESULT_TIMEOUT\020\006\022\026\n\022RESULT_UNSUPPORTE" + "D\020\007*\244\001\n\007FixType\022\023\n\017FIX_TYPE_NO_GPS\020\000\022\023\n\017" + "FIX_TYPE_NO_FIX\020\001\022\023\n\017FIX_TYPE_FIX_2D\020\002\022\023" + "\n\017FIX_TYPE_FIX_3D\020\003\022\025\n\021FIX_TYPE_FIX_DGPS" + "\020\004\022\026\n\022FIX_TYPE_RTK_FLOAT\020\005\022\026\n\022FIX_TYPE_R" + "TK_FIXED\020\006*\206\003\n\nFlightMode\022\027\n\023FLIGHT_MODE" + "_UNKNOWN\020\000\022\025\n\021FLIGHT_MODE_READY\020\001\022\027\n\023FLI" + "GHT_MODE_TAKEOFF\020\002\022\024\n\020FLIGHT_MODE_HOLD\020\003" + "\022\027\n\023FLIGHT_MODE_MISSION\020\004\022 \n\034FLIGHT_MODE" + "_RETURN_TO_LAUNCH\020\005\022\024\n\020FLIGHT_MODE_LAND\020" + "\006\022\030\n\024FLIGHT_MODE_OFFBOARD\020\007\022\031\n\025FLIGHT_MO" + "DE_FOLLOW_ME\020\010\022\026\n\022FLIGHT_MODE_MANUAL\020\t\022\026" + "\n\022FLIGHT_MODE_ALTCTL\020\n\022\026\n\022FLIGHT_MODE_PO" + "SCTL\020\013\022\024\n\020FLIGHT_MODE_ACRO\020\014\022\032\n\026FLIGHT_M" + "ODE_STABILIZED\020\r\022\031\n\025FLIGHT_MODE_RATTITUD" + "E\020\016*\371\001\n\016StatusTextType\022\032\n\026STATUS_TEXT_TY" + "PE_DEBUG\020\000\022\031\n\025STATUS_TEXT_TYPE_INFO\020\001\022\033\n" + "\027STATUS_TEXT_TYPE_NOTICE\020\002\022\034\n\030STATUS_TEX" + "T_TYPE_WARNING\020\003\022\032\n\026STATUS_TEXT_TYPE_ERR" + "OR\020\004\022\035\n\031STATUS_TEXT_TYPE_CRITICAL\020\005\022\032\n\026S" + "TATUS_TEXT_TYPE_ALERT\020\006\022\036\n\032STATUS_TEXT_T" + "YPE_EMERGENCY\020\007*\223\001\n\013LandedState\022\030\n\024LANDE" + "D_STATE_UNKNOWN\020\000\022\032\n\026LANDED_STATE_ON_GRO" + "UND\020\001\022\027\n\023LANDED_STATE_IN_AIR\020\002\022\033\n\027LANDED" + "_STATE_TAKING_OFF\020\003\022\030\n\024LANDED_STATE_LAND" + "ING\020\004*\215\001\n\tVtolState\022\030\n\024VTOL_STATE_UNDEFI" + "NED\020\000\022\037\n\033VTOL_STATE_TRANSITION_TO_FW\020\001\022\037" + "\n\033VTOL_STATE_TRANSITION_TO_MC\020\002\022\021\n\rVTOL_" + "STATE_MC\020\003\022\021\n\rVTOL_STATE_FW\020\0042\3075\n\020Teleme" + "tryService\022o\n\021SubscribePosition\022..mavsdk" + ".rpc.telemetry.SubscribePositionRequest\032" + "&.mavsdk.rpc.telemetry.PositionResponse\"" + "\0000\001\022c\n\rSubscribeHome\022*.mavsdk.rpc.teleme" + "try.SubscribeHomeRequest\032\".mavsdk.rpc.te" + "lemetry.HomeResponse\"\0000\001\022f\n\016SubscribeInA" + "ir\022+.mavsdk.rpc.telemetry.SubscribeInAir" + "Request\032#.mavsdk.rpc.telemetry.InAirResp" + "onse\"\0000\001\022x\n\024SubscribeLandedState\0221.mavsd" + "k.rpc.telemetry.SubscribeLandedStateRequ" + "est\032).mavsdk.rpc.telemetry.LandedStateRe" + "sponse\"\0000\001\022f\n\016SubscribeArmed\022+.mavsdk.rp" + "c.telemetry.SubscribeArmedRequest\032#.mavs" + "dk.rpc.telemetry.ArmedResponse\"\0000\001\022r\n\022Su" + "bscribeVtolState\022/.mavsdk.rpc.telemetry." + "SubscribeVtolStateRequest\032\'.mavsdk.rpc.t" + "elemetry.VtolStateResponse\"\0000\001\022\215\001\n\033Subsc" + "ribeAttitudeQuaternion\0228.mavsdk.rpc.tele" + "metry.SubscribeAttitudeQuaternionRequest" + "\0320.mavsdk.rpc.telemetry.AttitudeQuaterni" + "onResponse\"\0000\001\022~\n\026SubscribeAttitudeEuler" + "\0223.mavsdk.rpc.telemetry.SubscribeAttitud" + "eEulerRequest\032+.mavsdk.rpc.telemetry.Att" + "itudeEulerResponse\"\0000\001\022\250\001\n$SubscribeAtti" + "tudeAngularVelocityBody\022A.mavsdk.rpc.tel" + "emetry.SubscribeAttitudeAngularVelocityB" + "odyRequest\0329.mavsdk.rpc.telemetry.Attitu" + "deAngularVelocityBodyResponse\"\0000\001\022x\n\024Sub" + "scribeVelocityNed\0221.mavsdk.rpc.telemetry" + ".SubscribeVelocityNedRequest\032).mavsdk.rp" + "c.telemetry.VelocityNedResponse\"\0000\001\022l\n\020S" + "ubscribeGpsInfo\022-.mavsdk.rpc.telemetry.S" + "ubscribeGpsInfoRequest\032%.mavsdk.rpc.tele" + "metry.GpsInfoResponse\"\0000\001\022i\n\017SubscribeRa" + "wGps\022,.mavsdk.rpc.telemetry.SubscribeRaw" + "GpsRequest\032$.mavsdk.rpc.telemetry.RawGps" + "Response\"\0000\001\022l\n\020SubscribeBattery\022-.mavsd" + "k.rpc.telemetry.SubscribeBatteryRequest\032" + "%.mavsdk.rpc.telemetry.BatteryResponse\"\000" + "0\001\022u\n\023SubscribeFlightMode\0220.mavsdk.rpc.t" + "elemetry.SubscribeFlightModeRequest\032(.ma" + "vsdk.rpc.telemetry.FlightModeResponse\"\0000" + "\001\022i\n\017SubscribeHealth\022,.mavsdk.rpc.teleme" + "try.SubscribeHealthRequest\032$.mavsdk.rpc." + "telemetry.HealthResponse\"\0000\001\022o\n\021Subscrib" + "eRcStatus\022..mavsdk.rpc.telemetry.Subscri" + "beRcStatusRequest\032&.mavsdk.rpc.telemetry" + ".RcStatusResponse\"\0000\001\022u\n\023SubscribeStatus" + "Text\0220.mavsdk.rpc.telemetry.SubscribeSta" + "tusTextRequest\032(.mavsdk.rpc.telemetry.St" + "atusTextResponse\"\0000\001\022\226\001\n\036SubscribeActuat" + "orControlTarget\022;.mavsdk.rpc.telemetry.S" + "ubscribeActuatorControlTargetRequest\0323.m" + "avsdk.rpc.telemetry.ActuatorControlTarge" + "tResponse\"\0000\001\022\223\001\n\035SubscribeActuatorOutpu" + "tStatus\022:.mavsdk.rpc.telemetry.Subscribe" + "ActuatorOutputStatusRequest\0322.mavsdk.rpc" + ".telemetry.ActuatorOutputStatusResponse\"" + "\0000\001\022o\n\021SubscribeOdometry\022..mavsdk.rpc.te" + "lemetry.SubscribeOdometryRequest\032&.mavsd" + "k.rpc.telemetry.OdometryResponse\"\0000\001\022\220\001\n" + "\034SubscribePositionVelocityNed\0229.mavsdk.r" + "pc.telemetry.SubscribePositionVelocityNe" + "dRequest\0321.mavsdk.rpc.telemetry.Position" + "VelocityNedResponse\"\0000\001\022x\n\024SubscribeGrou" + "ndTruth\0221.mavsdk.rpc.telemetry.Subscribe" + "GroundTruthRequest\032).mavsdk.rpc.telemetr" + "y.GroundTruthResponse\"\0000\001\022\207\001\n\031SubscribeF" + "ixedwingMetrics\0226.mavsdk.rpc.telemetry.S" + "ubscribeFixedwingMetricsRequest\032..mavsdk" + ".rpc.telemetry.FixedwingMetricsResponse\"" + "\0000\001\022`\n\014SubscribeImu\022).mavsdk.rpc.telemet" + "ry.SubscribeImuRequest\032!.mavsdk.rpc.tele" + "metry.ImuResponse\"\0000\001\022r\n\022SubscribeScaled" + "Imu\022/.mavsdk.rpc.telemetry.SubscribeScal" + "edImuRequest\032\'.mavsdk.rpc.telemetry.Scal" + "edImuResponse\"\0000\001\022i\n\017SubscribeRawImu\022,.m" + "avsdk.rpc.telemetry.SubscribeRawImuReque" + "st\032$.mavsdk.rpc.telemetry.RawImuResponse" + "\"\0000\001\022x\n\024SubscribeHealthAllOk\0221.mavsdk.rp" + "c.telemetry.SubscribeHealthAllOkRequest\032" + ").mavsdk.rpc.telemetry.HealthAllOkRespon" + "se\"\0000\001\022~\n\026SubscribeUnixEpochTime\0223.mavsd" + "k.rpc.telemetry.SubscribeUnixEpochTimeRe" + "quest\032+.mavsdk.rpc.telemetry.UnixEpochTi" + "meResponse\"\0000\001\022\201\001\n\027SubscribeDistanceSens" + "or\0224.mavsdk.rpc.telemetry.SubscribeDista" + "nceSensorRequest\032,.mavsdk.rpc.telemetry." + "DistanceSensorResponse\"\0000\001\022\201\001\n\027Subscribe" + "ScaledPressure\0224.mavsdk.rpc.telemetry.Su" + "bscribeScaledPressureRequest\032,.mavsdk.rp" + "c.telemetry.ScaledPressureResponse\"\0000\001\022l" + "\n\020SubscribeHeading\022-.mavsdk.rpc.telemetr" + "y.SubscribeHeadingRequest\032%.mavsdk.rpc.t" + "elemetry.HeadingResponse\"\0000\001\022o\n\021Subscrib" + "eAltitude\022..mavsdk.rpc.telemetry.Subscri" + "beAltitudeRequest\032&.mavsdk.rpc.telemetry" + ".AltitudeResponse\"\0000\001\022p\n\017SetRatePosition" + "\022,.mavsdk.rpc.telemetry.SetRatePositionR" + "equest\032-.mavsdk.rpc.telemetry.SetRatePos" + "itionResponse\"\000\022d\n\013SetRateHome\022(.mavsdk." + "rpc.telemetry.SetRateHomeRequest\032).mavsd" + "k.rpc.telemetry.SetRateHomeResponse\"\000\022g\n" + "\014SetRateInAir\022).mavsdk.rpc.telemetry.Set" + "RateInAirRequest\032*.mavsdk.rpc.telemetry." + "SetRateInAirResponse\"\000\022y\n\022SetRateLandedS" + "tate\022/.mavsdk.rpc.telemetry.SetRateLande" + "dStateRequest\0320.mavsdk.rpc.telemetry.Set" + "RateLandedStateResponse\"\000\022s\n\020SetRateVtol" + "State\022-.mavsdk.rpc.telemetry.SetRateVtol" + "StateRequest\032..mavsdk.rpc.telemetry.SetR" + "ateVtolStateResponse\"\000\022\216\001\n\031SetRateAttitu" + "deQuaternion\0226.mavsdk.rpc.telemetry.SetR" + "ateAttitudeQuaternionRequest\0327.mavsdk.rp" + "c.telemetry.SetRateAttitudeQuaternionRes" + "ponse\"\000\022\177\n\024SetRateAttitudeEuler\0221.mavsdk" + ".rpc.telemetry.SetRateAttitudeEulerReque" + "st\0322.mavsdk.rpc.telemetry.SetRateAttitud" + "eEulerResponse\"\000\022y\n\022SetRateVelocityNed\022/" + ".mavsdk.rpc.telemetry.SetRateVelocityNed" + "Request\0320.mavsdk.rpc.telemetry.SetRateVe" + "locityNedResponse\"\000\022m\n\016SetRateGpsInfo\022+." + "mavsdk.rpc.telemetry.SetRateGpsInfoReque" + "st\032,.mavsdk.rpc.telemetry.SetRateGpsInfo" + "Response\"\000\022m\n\016SetRateBattery\022+.mavsdk.rp" + "c.telemetry.SetRateBatteryRequest\032,.mavs" + "dk.rpc.telemetry.SetRateBatteryResponse\"" + "\000\022p\n\017SetRateRcStatus\022,.mavsdk.rpc.teleme" + "try.SetRateRcStatusRequest\032-.mavsdk.rpc." + "telemetry.SetRateRcStatusResponse\"\000\022\227\001\n\034" + "SetRateActuatorControlTarget\0229.mavsdk.rp" + "c.telemetry.SetRateActuatorControlTarget" + "Request\032:.mavsdk.rpc.telemetry.SetRateAc" + "tuatorControlTargetResponse\"\000\022\224\001\n\033SetRat" + "eActuatorOutputStatus\0228.mavsdk.rpc.telem" + "etry.SetRateActuatorOutputStatusRequest\032" + "9.mavsdk.rpc.telemetry.SetRateActuatorOu" + "tputStatusResponse\"\000\022p\n\017SetRateOdometry\022" + ",.mavsdk.rpc.telemetry.SetRateOdometryRe" + "quest\032-.mavsdk.rpc.telemetry.SetRateOdom" + "etryResponse\"\000\022\221\001\n\032SetRatePositionVeloci" + "tyNed\0227.mavsdk.rpc.telemetry.SetRatePosi" + "tionVelocityNedRequest\0328.mavsdk.rpc.tele" + "metry.SetRatePositionVelocityNedResponse" + "\"\000\022y\n\022SetRateGroundTruth\022/.mavsdk.rpc.te" + "lemetry.SetRateGroundTruthRequest\0320.mavs" + "dk.rpc.telemetry.SetRateGroundTruthRespo" + "nse\"\000\022\210\001\n\027SetRateFixedwingMetrics\0224.mavs" + "dk.rpc.telemetry.SetRateFixedwingMetrics" + "Request\0325.mavsdk.rpc.telemetry.SetRateFi" + "xedwingMetricsResponse\"\000\022a\n\nSetRateImu\022\'" + ".mavsdk.rpc.telemetry.SetRateImuRequest\032" + "(.mavsdk.rpc.telemetry.SetRateImuRespons" + "e\"\000\022s\n\020SetRateScaledImu\022-.mavsdk.rpc.tel" + "emetry.SetRateScaledImuRequest\032..mavsdk." + "rpc.telemetry.SetRateScaledImuResponse\"\000" + "\022j\n\rSetRateRawImu\022*.mavsdk.rpc.telemetry" + ".SetRateRawImuRequest\032+.mavsdk.rpc.telem" + "etry.SetRateRawImuResponse\"\000\022\177\n\024SetRateU" + "nixEpochTime\0221.mavsdk.rpc.telemetry.SetR" + "ateUnixEpochTimeRequest\0322.mavsdk.rpc.tel" + "emetry.SetRateUnixEpochTimeResponse\"\000\022\202\001" + "\n\025SetRateDistanceSensor\0222.mavsdk.rpc.tel" + "emetry.SetRateDistanceSensorRequest\0323.ma" + "vsdk.rpc.telemetry.SetRateDistanceSensor" + "Response\"\000\022p\n\017SetRateAltitude\022,.mavsdk.r" + "pc.telemetry.SetRateAltitudeRequest\032-.ma" + "vsdk.rpc.telemetry.SetRateAltitudeRespon" + "se\"\000\022y\n\022GetGpsGlobalOrigin\022/.mavsdk.rpc." + "telemetry.GetGpsGlobalOriginRequest\0320.ma" + "vsdk.rpc.telemetry.GetGpsGlobalOriginRes" + "ponse\"\000B%\n\023io.mavsdk.telemetryB\016Telemetr" + "yProtob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_telemetry_2ftelemetry_2eproto_deps[1] = { @@ -5795,7 +5804,7 @@ static ::absl::once_flag descriptor_table_telemetry_2ftelemetry_2eproto_once; PROTOBUF_CONSTINIT const ::_pbi::DescriptorTable descriptor_table_telemetry_2ftelemetry_2eproto = { false, false, - 19831, + 19934, descriptor_table_protodef_telemetry_2ftelemetry_2eproto, "telemetry/telemetry.proto", &descriptor_table_telemetry_2ftelemetry_2eproto_once, @@ -35242,9 +35251,9 @@ inline void FixedwingMetrics::SharedCtor(::_pb::Arena* arena) { ::memset(reinterpret_cast(&_impl_) + offsetof(Impl_, airspeed_m_s_), 0, - offsetof(Impl_, climb_rate_m_s_) - + offsetof(Impl_, absolute_altitude_m_) - offsetof(Impl_, airspeed_m_s_) + - sizeof(Impl_::climb_rate_m_s_)); + sizeof(Impl_::absolute_altitude_m_)); } FixedwingMetrics::~FixedwingMetrics() { // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.FixedwingMetrics) @@ -35293,15 +35302,15 @@ const ::google::protobuf::internal::ClassData* FixedwingMetrics::GetClassData() return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<2, 3, 0, 0, 2> FixedwingMetrics::_table_ = { +const ::_pbi::TcParseTable<3, 6, 0, 0, 2> FixedwingMetrics::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 3, 24, // max_field_number, fast_idx_mask + 6, 56, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967288, // skipmap + 4294967232, // skipmap offsetof(decltype(_table_), field_entries), - 3, // num_field_entries + 6, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries _class_data_.base(), @@ -35321,6 +35330,16 @@ const ::_pbi::TcParseTable<2, 3, 0, 0, 2> FixedwingMetrics::_table_ = { // float climb_rate_m_s = 3 [(.mavsdk.options.default_value) = "NaN"]; {::_pbi::TcParser::FastF32S1, {29, 63, 0, PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.climb_rate_m_s_)}}, + // float groundspeed_m_s = 4 [(.mavsdk.options.default_value) = "NaN"]; + {::_pbi::TcParser::FastF32S1, + {37, 63, 0, PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.groundspeed_m_s_)}}, + // float heading_deg = 5 [(.mavsdk.options.default_value) = "NaN"]; + {::_pbi::TcParser::FastF32S1, + {45, 63, 0, PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.heading_deg_)}}, + // float absolute_altitude_m = 6 [(.mavsdk.options.default_value) = "NaN"]; + {::_pbi::TcParser::FastF32S1, + {53, 63, 0, PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.absolute_altitude_m_)}}, + {::_pbi::TcParser::MiniParse, {}}, }}, {{ 65535, 65535 }}, {{ @@ -35333,6 +35352,15 @@ const ::_pbi::TcParseTable<2, 3, 0, 0, 2> FixedwingMetrics::_table_ = { // float climb_rate_m_s = 3 [(.mavsdk.options.default_value) = "NaN"]; {PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.climb_rate_m_s_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float groundspeed_m_s = 4 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.groundspeed_m_s_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float heading_deg = 5 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.heading_deg_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float absolute_altitude_m = 6 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.absolute_altitude_m_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, }}, // no aux_entries {{ @@ -35347,8 +35375,8 @@ PROTOBUF_NOINLINE void FixedwingMetrics::Clear() { (void) cached_has_bits; ::memset(&_impl_.airspeed_m_s_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.climb_rate_m_s_) - - reinterpret_cast(&_impl_.airspeed_m_s_)) + sizeof(_impl_.climb_rate_m_s_)); + reinterpret_cast(&_impl_.absolute_altitude_m_) - + reinterpret_cast(&_impl_.airspeed_m_s_)) + sizeof(_impl_.absolute_altitude_m_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -35388,6 +35416,27 @@ PROTOBUF_NOINLINE void FixedwingMetrics::Clear() { 3, this_._internal_climb_rate_m_s(), target); } + // float groundspeed_m_s = 4 [(.mavsdk.options.default_value) = "NaN"]; + if (::absl::bit_cast<::uint32_t>(this_._internal_groundspeed_m_s()) != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 4, this_._internal_groundspeed_m_s(), target); + } + + // float heading_deg = 5 [(.mavsdk.options.default_value) = "NaN"]; + if (::absl::bit_cast<::uint32_t>(this_._internal_heading_deg()) != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 5, this_._internal_heading_deg(), target); + } + + // float absolute_altitude_m = 6 [(.mavsdk.options.default_value) = "NaN"]; + if (::absl::bit_cast<::uint32_t>(this_._internal_absolute_altitude_m()) != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 6, this_._internal_absolute_altitude_m(), target); + } + if (PROTOBUF_PREDICT_FALSE(this_._internal_metadata_.have_unknown_fields())) { target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( @@ -35425,6 +35474,18 @@ PROTOBUF_NOINLINE void FixedwingMetrics::Clear() { if (::absl::bit_cast<::uint32_t>(this_._internal_climb_rate_m_s()) != 0) { total_size += 5; } + // float groundspeed_m_s = 4 [(.mavsdk.options.default_value) = "NaN"]; + if (::absl::bit_cast<::uint32_t>(this_._internal_groundspeed_m_s()) != 0) { + total_size += 5; + } + // float heading_deg = 5 [(.mavsdk.options.default_value) = "NaN"]; + if (::absl::bit_cast<::uint32_t>(this_._internal_heading_deg()) != 0) { + total_size += 5; + } + // float absolute_altitude_m = 6 [(.mavsdk.options.default_value) = "NaN"]; + if (::absl::bit_cast<::uint32_t>(this_._internal_absolute_altitude_m()) != 0) { + total_size += 5; + } } return this_.MaybeComputeUnknownFieldsSize(total_size, &this_._impl_._cached_size_); @@ -35447,6 +35508,15 @@ void FixedwingMetrics::MergeImpl(::google::protobuf::MessageLite& to_msg, const if (::absl::bit_cast<::uint32_t>(from._internal_climb_rate_m_s()) != 0) { _this->_impl_.climb_rate_m_s_ = from._impl_.climb_rate_m_s_; } + if (::absl::bit_cast<::uint32_t>(from._internal_groundspeed_m_s()) != 0) { + _this->_impl_.groundspeed_m_s_ = from._impl_.groundspeed_m_s_; + } + if (::absl::bit_cast<::uint32_t>(from._internal_heading_deg()) != 0) { + _this->_impl_.heading_deg_ = from._impl_.heading_deg_; + } + if (::absl::bit_cast<::uint32_t>(from._internal_absolute_altitude_m()) != 0) { + _this->_impl_.absolute_altitude_m_ = from._impl_.absolute_altitude_m_; + } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } @@ -35462,8 +35532,8 @@ void FixedwingMetrics::InternalSwap(FixedwingMetrics* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); ::google::protobuf::internal::memswap< - PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.climb_rate_m_s_) - + sizeof(FixedwingMetrics::_impl_.climb_rate_m_s_) + PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.absolute_altitude_m_) + + sizeof(FixedwingMetrics::_impl_.absolute_altitude_m_) - PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.airspeed_m_s_)>( reinterpret_cast(&_impl_.airspeed_m_s_), reinterpret_cast(&other->_impl_.airspeed_m_s_)); diff --git a/src/mavsdk_server/src/generated/telemetry/telemetry.pb.h b/src/mavsdk_server/src/generated/telemetry/telemetry.pb.h index 3fde0ea794..b713360c97 100644 --- a/src/mavsdk_server/src/generated/telemetry/telemetry.pb.h +++ b/src/mavsdk_server/src/generated/telemetry/telemetry.pb.h @@ -15536,6 +15536,9 @@ class FixedwingMetrics final kAirspeedMSFieldNumber = 1, kThrottlePercentageFieldNumber = 2, kClimbRateMSFieldNumber = 3, + kGroundspeedMSFieldNumber = 4, + kHeadingDegFieldNumber = 5, + kAbsoluteAltitudeMFieldNumber = 6, }; // float airspeed_m_s = 1 [(.mavsdk.options.default_value) = "NaN"]; void clear_airspeed_m_s() ; @@ -15566,13 +15569,43 @@ class FixedwingMetrics final float _internal_climb_rate_m_s() const; void _internal_set_climb_rate_m_s(float value); + public: + // float groundspeed_m_s = 4 [(.mavsdk.options.default_value) = "NaN"]; + void clear_groundspeed_m_s() ; + float groundspeed_m_s() const; + void set_groundspeed_m_s(float value); + + private: + float _internal_groundspeed_m_s() const; + void _internal_set_groundspeed_m_s(float value); + + public: + // float heading_deg = 5 [(.mavsdk.options.default_value) = "NaN"]; + void clear_heading_deg() ; + float heading_deg() const; + void set_heading_deg(float value); + + private: + float _internal_heading_deg() const; + void _internal_set_heading_deg(float value); + + public: + // float absolute_altitude_m = 6 [(.mavsdk.options.default_value) = "NaN"]; + void clear_absolute_altitude_m() ; + float absolute_altitude_m() const; + void set_absolute_altitude_m(float value); + + private: + float _internal_absolute_altitude_m() const; + void _internal_set_absolute_altitude_m(float value); + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.FixedwingMetrics) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 0, + 3, 6, 0, 0, 2> _table_; @@ -15593,6 +15626,9 @@ class FixedwingMetrics final float airspeed_m_s_; float throttle_percentage_; float climb_rate_m_s_; + float groundspeed_m_s_; + float heading_deg_; + float absolute_altitude_m_; ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -37691,6 +37727,72 @@ inline void FixedwingMetrics::_internal_set_climb_rate_m_s(float value) { _impl_.climb_rate_m_s_ = value; } +// float groundspeed_m_s = 4 [(.mavsdk.options.default_value) = "NaN"]; +inline void FixedwingMetrics::clear_groundspeed_m_s() { + ::google::protobuf::internal::TSanWrite(&_impl_); + _impl_.groundspeed_m_s_ = 0; +} +inline float FixedwingMetrics::groundspeed_m_s() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.FixedwingMetrics.groundspeed_m_s) + return _internal_groundspeed_m_s(); +} +inline void FixedwingMetrics::set_groundspeed_m_s(float value) { + _internal_set_groundspeed_m_s(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.FixedwingMetrics.groundspeed_m_s) +} +inline float FixedwingMetrics::_internal_groundspeed_m_s() const { + ::google::protobuf::internal::TSanRead(&_impl_); + return _impl_.groundspeed_m_s_; +} +inline void FixedwingMetrics::_internal_set_groundspeed_m_s(float value) { + ::google::protobuf::internal::TSanWrite(&_impl_); + _impl_.groundspeed_m_s_ = value; +} + +// float heading_deg = 5 [(.mavsdk.options.default_value) = "NaN"]; +inline void FixedwingMetrics::clear_heading_deg() { + ::google::protobuf::internal::TSanWrite(&_impl_); + _impl_.heading_deg_ = 0; +} +inline float FixedwingMetrics::heading_deg() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.FixedwingMetrics.heading_deg) + return _internal_heading_deg(); +} +inline void FixedwingMetrics::set_heading_deg(float value) { + _internal_set_heading_deg(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.FixedwingMetrics.heading_deg) +} +inline float FixedwingMetrics::_internal_heading_deg() const { + ::google::protobuf::internal::TSanRead(&_impl_); + return _impl_.heading_deg_; +} +inline void FixedwingMetrics::_internal_set_heading_deg(float value) { + ::google::protobuf::internal::TSanWrite(&_impl_); + _impl_.heading_deg_ = value; +} + +// float absolute_altitude_m = 6 [(.mavsdk.options.default_value) = "NaN"]; +inline void FixedwingMetrics::clear_absolute_altitude_m() { + ::google::protobuf::internal::TSanWrite(&_impl_); + _impl_.absolute_altitude_m_ = 0; +} +inline float FixedwingMetrics::absolute_altitude_m() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.FixedwingMetrics.absolute_altitude_m) + return _internal_absolute_altitude_m(); +} +inline void FixedwingMetrics::set_absolute_altitude_m(float value) { + _internal_set_absolute_altitude_m(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.FixedwingMetrics.absolute_altitude_m) +} +inline float FixedwingMetrics::_internal_absolute_altitude_m() const { + ::google::protobuf::internal::TSanRead(&_impl_); + return _impl_.absolute_altitude_m_; +} +inline void FixedwingMetrics::_internal_set_absolute_altitude_m(float value) { + ::google::protobuf::internal::TSanWrite(&_impl_); + _impl_.absolute_altitude_m_ = value; +} + // ------------------------------------------------------------------- // AccelerationFrd diff --git a/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.grpc.pb.cc b/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.grpc.pb.cc index db090ff234..82341980fe 100644 --- a/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.grpc.pb.cc @@ -39,6 +39,8 @@ static const char* TelemetryServerService_method_names[] = { "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishRawImu", "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishUnixEpochTime", "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishDistanceSensor", + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishAttitude", + "/mavsdk.rpc.telemetry_server.TelemetryServerService/PublishVisualFlightRulesHud", }; std::unique_ptr< TelemetryServerService::Stub> TelemetryServerService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -63,6 +65,8 @@ TelemetryServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterfa , rpcmethod_PublishRawImu_(TelemetryServerService_method_names[12], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_PublishUnixEpochTime_(TelemetryServerService_method_names[13], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_PublishDistanceSensor_(TelemetryServerService_method_names[14], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_PublishAttitude_(TelemetryServerService_method_names[15], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_PublishVisualFlightRulesHud_(TelemetryServerService_method_names[16], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) {} ::grpc::Status TelemetryServerService::Stub::PublishPosition(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishPositionRequest& request, ::mavsdk::rpc::telemetry_server::PublishPositionResponse* response) { @@ -410,6 +414,52 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishDista return result; } +::grpc::Status TelemetryServerService::Stub::PublishAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest& request, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_PublishAttitude_, context, request, response); +} + +void TelemetryServerService::Stub::async::PublishAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* request, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_PublishAttitude_, context, request, response, std::move(f)); +} + +void TelemetryServerService::Stub::async::PublishAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* request, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_PublishAttitude_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>* TelemetryServerService::Stub::PrepareAsyncPublishAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse, ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_PublishAttitude_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>* TelemetryServerService::Stub::AsyncPublishAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncPublishAttitudeRaw(context, request, cq); + result->StartCall(); + return result; +} + +::grpc::Status TelemetryServerService::Stub::PublishVisualFlightRulesHud(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest& request, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_PublishVisualFlightRulesHud_, context, request, response); +} + +void TelemetryServerService::Stub::async::PublishVisualFlightRulesHud(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* request, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_PublishVisualFlightRulesHud_, context, request, response, std::move(f)); +} + +void TelemetryServerService::Stub::async::PublishVisualFlightRulesHud(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* request, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_PublishVisualFlightRulesHud_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>* TelemetryServerService::Stub::PrepareAsyncPublishVisualFlightRulesHudRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_PublishVisualFlightRulesHud_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>* TelemetryServerService::Stub::AsyncPublishVisualFlightRulesHudRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncPublishVisualFlightRulesHudRaw(context, request, cq); + result->StartCall(); + return result; +} + TelemetryServerService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( TelemetryServerService_method_names[0], @@ -561,6 +611,26 @@ TelemetryServerService::Service::Service() { ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse* resp) { return service->PublishDistanceSensor(ctx, req, resp); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + TelemetryServerService_method_names[15], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< TelemetryServerService::Service, ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](TelemetryServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* req, + ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* resp) { + return service->PublishAttitude(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + TelemetryServerService_method_names[16], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< TelemetryServerService::Service, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](TelemetryServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* req, + ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* resp) { + return service->PublishVisualFlightRulesHud(ctx, req, resp); + }, this))); } TelemetryServerService::Service::~Service() { @@ -671,6 +741,20 @@ ::grpc::Status TelemetryServerService::Service::PublishDistanceSensor(::grpc::Se return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status TelemetryServerService::Service::PublishAttitude(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* request, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status TelemetryServerService::Service::PublishVisualFlightRulesHud(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* request, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + } // namespace mavsdk } // namespace rpc diff --git a/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.grpc.pb.h b/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.grpc.pb.h index 6012a78095..4043570908 100644 --- a/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.grpc.pb.h @@ -160,6 +160,22 @@ class TelemetryServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse>> PrepareAsyncPublishDistanceSensor(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse>>(PrepareAsyncPublishDistanceSensorRaw(context, request, cq)); } + // Publish to "attitude" updates. + virtual ::grpc::Status PublishAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest& request, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>> AsyncPublishAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>>(AsyncPublishAttitudeRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>> PrepareAsyncPublishAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>>(PrepareAsyncPublishAttitudeRaw(context, request, cq)); + } + // Publish to "Visual Flight Rules HUD" updates. + virtual ::grpc::Status PublishVisualFlightRulesHud(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest& request, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>> AsyncPublishVisualFlightRulesHud(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>>(AsyncPublishVisualFlightRulesHudRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>> PrepareAsyncPublishVisualFlightRulesHud(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>>(PrepareAsyncPublishVisualFlightRulesHudRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -208,6 +224,12 @@ class TelemetryServerService final { // Publish to "distance sensor" updates. virtual void PublishDistanceSensor(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest* request, ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse* response, std::function) = 0; virtual void PublishDistanceSensor(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest* request, ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Publish to "attitude" updates. + virtual void PublishAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* request, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* response, std::function) = 0; + virtual void PublishAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* request, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // Publish to "Visual Flight Rules HUD" updates. + virtual void PublishVisualFlightRulesHud(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* request, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* response, std::function) = 0; + virtual void PublishVisualFlightRulesHud(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* request, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -243,6 +265,10 @@ class TelemetryServerService final { virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeResponse>* PrepareAsyncPublishUnixEpochTimeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse>* AsyncPublishDistanceSensorRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse>* PrepareAsyncPublishDistanceSensorRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>* AsyncPublishAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>* PrepareAsyncPublishAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>* AsyncPublishVisualFlightRulesHudRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>* PrepareAsyncPublishVisualFlightRulesHudRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -352,6 +378,20 @@ class TelemetryServerService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse>> PrepareAsyncPublishDistanceSensor(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse>>(PrepareAsyncPublishDistanceSensorRaw(context, request, cq)); } + ::grpc::Status PublishAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest& request, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>> AsyncPublishAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>>(AsyncPublishAttitudeRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>> PrepareAsyncPublishAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>>(PrepareAsyncPublishAttitudeRaw(context, request, cq)); + } + ::grpc::Status PublishVisualFlightRulesHud(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest& request, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>> AsyncPublishVisualFlightRulesHud(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>>(AsyncPublishVisualFlightRulesHudRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>> PrepareAsyncPublishVisualFlightRulesHud(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>>(PrepareAsyncPublishVisualFlightRulesHudRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: @@ -385,6 +425,10 @@ class TelemetryServerService final { void PublishUnixEpochTime(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeRequest* request, ::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void PublishDistanceSensor(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest* request, ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse* response, std::function) override; void PublishDistanceSensor(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest* request, ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void PublishAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* request, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* response, std::function) override; + void PublishAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* request, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) override; + void PublishVisualFlightRulesHud(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* request, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* response, std::function) override; + void PublishVisualFlightRulesHud(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* request, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* response, ::grpc::ClientUnaryReactor* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -426,6 +470,10 @@ class TelemetryServerService final { ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeResponse>* PrepareAsyncPublishUnixEpochTimeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse>* AsyncPublishDistanceSensorRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse>* PrepareAsyncPublishDistanceSensorRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>* AsyncPublishAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>* PrepareAsyncPublishAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>* AsyncPublishVisualFlightRulesHudRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>* PrepareAsyncPublishVisualFlightRulesHudRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_PublishPosition_; const ::grpc::internal::RpcMethod rpcmethod_PublishHome_; const ::grpc::internal::RpcMethod rpcmethod_PublishSysStatus_; @@ -441,6 +489,8 @@ class TelemetryServerService final { const ::grpc::internal::RpcMethod rpcmethod_PublishRawImu_; const ::grpc::internal::RpcMethod rpcmethod_PublishUnixEpochTime_; const ::grpc::internal::RpcMethod rpcmethod_PublishDistanceSensor_; + const ::grpc::internal::RpcMethod rpcmethod_PublishAttitude_; + const ::grpc::internal::RpcMethod rpcmethod_PublishVisualFlightRulesHud_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -478,6 +528,10 @@ class TelemetryServerService final { virtual ::grpc::Status PublishUnixEpochTime(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeRequest* request, ::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeResponse* response); // Publish to "distance sensor" updates. virtual ::grpc::Status PublishDistanceSensor(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest* request, ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse* response); + // Publish to "attitude" updates. + virtual ::grpc::Status PublishAttitude(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* request, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* response); + // Publish to "Visual Flight Rules HUD" updates. + virtual ::grpc::Status PublishVisualFlightRulesHud(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* request, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* response); }; template class WithAsyncMethod_PublishPosition : public BaseClass { @@ -779,7 +833,47 @@ class TelemetryServerService final { ::grpc::Service::RequestAsyncUnary(14, context, request, response, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_PublishPosition > > > > > > > > > > > > > > AsyncService; + template + class WithAsyncMethod_PublishAttitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_PublishAttitude() { + ::grpc::Service::MarkMethodAsync(15); + } + ~WithAsyncMethod_PublishAttitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestPublishAttitude(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(15, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_PublishVisualFlightRulesHud : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_PublishVisualFlightRulesHud() { + ::grpc::Service::MarkMethodAsync(16); + } + ~WithAsyncMethod_PublishVisualFlightRulesHud() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishVisualFlightRulesHud(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestPublishVisualFlightRulesHud(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(16, context, request, response, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_PublishPosition > > > > > > > > > > > > > > > > AsyncService; template class WithCallbackMethod_PublishPosition : public BaseClass { private: @@ -1185,7 +1279,61 @@ class TelemetryServerService final { virtual ::grpc::ServerUnaryReactor* PublishDistanceSensor( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse* /*response*/) { return nullptr; } }; - typedef WithCallbackMethod_PublishPosition > > > > > > > > > > > > > > CallbackService; + template + class WithCallbackMethod_PublishAttitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_PublishAttitude() { + ::grpc::Service::MarkMethodCallback(15, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* request, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* response) { return this->PublishAttitude(context, request, response); }));} + void SetMessageAllocatorFor_PublishAttitude( + ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(15); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_PublishAttitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* PublishAttitude( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* /*response*/) { return nullptr; } + }; + template + class WithCallbackMethod_PublishVisualFlightRulesHud : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_PublishVisualFlightRulesHud() { + ::grpc::Service::MarkMethodCallback(16, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* request, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* response) { return this->PublishVisualFlightRulesHud(context, request, response); }));} + void SetMessageAllocatorFor_PublishVisualFlightRulesHud( + ::grpc::MessageAllocator< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(16); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_PublishVisualFlightRulesHud() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishVisualFlightRulesHud(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* PublishVisualFlightRulesHud( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_PublishPosition > > > > > > > > > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_PublishPosition : public BaseClass { @@ -1443,6 +1591,40 @@ class TelemetryServerService final { } }; template + class WithGenericMethod_PublishAttitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_PublishAttitude() { + ::grpc::Service::MarkMethodGeneric(15); + } + ~WithGenericMethod_PublishAttitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_PublishVisualFlightRulesHud : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_PublishVisualFlightRulesHud() { + ::grpc::Service::MarkMethodGeneric(16); + } + ~WithGenericMethod_PublishVisualFlightRulesHud() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishVisualFlightRulesHud(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithRawMethod_PublishPosition : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -1743,6 +1925,46 @@ class TelemetryServerService final { } }; template + class WithRawMethod_PublishAttitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_PublishAttitude() { + ::grpc::Service::MarkMethodRaw(15); + } + ~WithRawMethod_PublishAttitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestPublishAttitude(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(15, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_PublishVisualFlightRulesHud : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_PublishVisualFlightRulesHud() { + ::grpc::Service::MarkMethodRaw(16); + } + ~WithRawMethod_PublishVisualFlightRulesHud() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishVisualFlightRulesHud(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestPublishVisualFlightRulesHud(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(16, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithRawCallbackMethod_PublishPosition : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -2073,6 +2295,50 @@ class TelemetryServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template + class WithRawCallbackMethod_PublishAttitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_PublishAttitude() { + ::grpc::Service::MarkMethodRawCallback(15, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->PublishAttitude(context, request, response); })); + } + ~WithRawCallbackMethod_PublishAttitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* PublishAttitude( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_PublishVisualFlightRulesHud : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_PublishVisualFlightRulesHud() { + ::grpc::Service::MarkMethodRawCallback(16, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->PublishVisualFlightRulesHud(context, request, response); })); + } + ~WithRawCallbackMethod_PublishVisualFlightRulesHud() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status PublishVisualFlightRulesHud(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* PublishVisualFlightRulesHud( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithStreamedUnaryMethod_PublishPosition : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -2477,9 +2743,63 @@ class TelemetryServerService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedPublishDistanceSensor(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest,::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_PublishPosition > > > > > > > > > > > > > > StreamedUnaryService; + template + class WithStreamedUnaryMethod_PublishAttitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_PublishAttitude() { + ::grpc::Service::MarkMethodStreamed(15, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>* streamer) { + return this->StreamedPublishAttitude(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_PublishAttitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status PublishAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedPublishAttitude(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest,::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_PublishVisualFlightRulesHud : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_PublishVisualFlightRulesHud() { + ::grpc::Service::MarkMethodStreamed(16, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>* streamer) { + return this->StreamedPublishVisualFlightRulesHud(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_PublishVisualFlightRulesHud() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status PublishVisualFlightRulesHud(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest* /*request*/, ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedPublishVisualFlightRulesHud(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest,::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_PublishPosition > > > > > > > > > > > > > > > > StreamedUnaryService; typedef Service SplitStreamedService; - typedef WithStreamedUnaryMethod_PublishPosition > > > > > > > > > > > > > > StreamedService; + typedef WithStreamedUnaryMethod_PublishPosition > > > > > > > > > > > > > > > > StreamedService; }; } // namespace telemetry_server diff --git a/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.pb.cc b/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.pb.cc index 9147b7a06e..bb735b869f 100644 --- a/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.pb.cc +++ b/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.pb.cc @@ -554,6 +554,9 @@ inline constexpr FixedwingMetrics::Impl_::Impl_( : airspeed_m_s_{0}, throttle_percentage_{0}, climb_rate_m_s_{0}, + groundspeed_m_s_{0}, + heading_deg_{0}, + absolute_altitude_m_{0}, _cached_size_{0} {} template @@ -815,6 +818,56 @@ struct AccelerationFrdDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 AccelerationFrdDefaultTypeInternal _AccelerationFrd_default_instance_; +inline constexpr PublishVisualFlightRulesHudResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + telemetry_server_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR PublishVisualFlightRulesHudResponse::PublishVisualFlightRulesHudResponse(::_pbi::ConstantInitialized) +#if defined(PROTOBUF_CUSTOM_VTABLE) + : ::google::protobuf::Message(_class_data_.base()), +#else // PROTOBUF_CUSTOM_VTABLE + : ::google::protobuf::Message(), +#endif // PROTOBUF_CUSTOM_VTABLE + _impl_(::_pbi::ConstantInitialized()) { +} +struct PublishVisualFlightRulesHudResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR PublishVisualFlightRulesHudResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~PublishVisualFlightRulesHudResponseDefaultTypeInternal() {} + union { + PublishVisualFlightRulesHudResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 PublishVisualFlightRulesHudResponseDefaultTypeInternal _PublishVisualFlightRulesHudResponse_default_instance_; + +inline constexpr PublishVisualFlightRulesHudRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + fixed_wing_metrics_{nullptr} {} + +template +PROTOBUF_CONSTEXPR PublishVisualFlightRulesHudRequest::PublishVisualFlightRulesHudRequest(::_pbi::ConstantInitialized) +#if defined(PROTOBUF_CUSTOM_VTABLE) + : ::google::protobuf::Message(_class_data_.base()), +#else // PROTOBUF_CUSTOM_VTABLE + : ::google::protobuf::Message(), +#endif // PROTOBUF_CUSTOM_VTABLE + _impl_(::_pbi::ConstantInitialized()) { +} +struct PublishVisualFlightRulesHudRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR PublishVisualFlightRulesHudRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~PublishVisualFlightRulesHudRequestDefaultTypeInternal() {} + union { + PublishVisualFlightRulesHudRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 PublishVisualFlightRulesHudRequestDefaultTypeInternal _PublishVisualFlightRulesHudRequest_default_instance_; + inline constexpr PublishUnixEpochTimeResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -1423,6 +1476,57 @@ struct PublishBatteryRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 PublishBatteryRequestDefaultTypeInternal _PublishBatteryRequest_default_instance_; +inline constexpr PublishAttitudeResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + telemetry_server_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR PublishAttitudeResponse::PublishAttitudeResponse(::_pbi::ConstantInitialized) +#if defined(PROTOBUF_CUSTOM_VTABLE) + : ::google::protobuf::Message(_class_data_.base()), +#else // PROTOBUF_CUSTOM_VTABLE + : ::google::protobuf::Message(), +#endif // PROTOBUF_CUSTOM_VTABLE + _impl_(::_pbi::ConstantInitialized()) { +} +struct PublishAttitudeResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR PublishAttitudeResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~PublishAttitudeResponseDefaultTypeInternal() {} + union { + PublishAttitudeResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 PublishAttitudeResponseDefaultTypeInternal _PublishAttitudeResponse_default_instance_; + +inline constexpr PublishAttitudeRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + angle_{nullptr}, + angular_velocity_{nullptr} {} + +template +PROTOBUF_CONSTEXPR PublishAttitudeRequest::PublishAttitudeRequest(::_pbi::ConstantInitialized) +#if defined(PROTOBUF_CUSTOM_VTABLE) + : ::google::protobuf::Message(_class_data_.base()), +#else // PROTOBUF_CUSTOM_VTABLE + : ::google::protobuf::Message(), +#endif // PROTOBUF_CUSTOM_VTABLE + _impl_(::_pbi::ConstantInitialized()) { +} +struct PublishAttitudeRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR PublishAttitudeRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~PublishAttitudeRequestDefaultTypeInternal() {} + union { + PublishAttitudeRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 PublishAttitudeRequestDefaultTypeInternal _PublishAttitudeRequest_default_instance_; + inline constexpr PositionVelocityNed::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -1837,6 +1941,28 @@ const ::uint32_t ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest, _impl_.distance_sensor_), 0, + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishAttitudeRequest, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishAttitudeRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishAttitudeRequest, _impl_.angle_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishAttitudeRequest, _impl_.angular_velocity_), + 0, + 1, + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest, _impl_.fixed_wing_metrics_), + 0, PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishPositionResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishPositionResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -1987,6 +2113,26 @@ const ::uint32_t ~0u, // no sizeof(Split) PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse, _impl_.telemetry_server_result_), 0, + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishAttitudeResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishAttitudeResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishAttitudeResponse, _impl_.telemetry_server_result_), + 0, + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse, _impl_.telemetry_server_result_), + 0, ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::Position, _internal_metadata_), ~0u, // no _extensions_ @@ -2264,6 +2410,9 @@ const ::uint32_t PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::FixedwingMetrics, _impl_.airspeed_m_s_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::FixedwingMetrics, _impl_.throttle_percentage_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::FixedwingMetrics, _impl_.climb_rate_m_s_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::FixedwingMetrics, _impl_.groundspeed_m_s_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::FixedwingMetrics, _impl_.heading_deg_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::FixedwingMetrics, _impl_.absolute_altitude_m_), ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry_server::AccelerationFrd, _internal_metadata_), ~0u, // no _extensions_ @@ -2347,49 +2496,53 @@ static const ::_pbi::MigrationSchema {164, 173, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishRawImuRequest)}, {174, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeRequest)}, {183, 192, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishDistanceSensorRequest)}, - {193, 202, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishPositionResponse)}, - {203, 212, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishHomeResponse)}, - {213, 222, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishSysStatusResponse)}, - {223, 232, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishExtendedSysStateResponse)}, - {233, 242, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishRawGpsResponse)}, - {243, 252, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishBatteryResponse)}, - {253, 262, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishStatusTextResponse)}, - {263, 272, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishOdometryResponse)}, - {273, 282, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishPositionVelocityNedResponse)}, - {283, 292, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishGroundTruthResponse)}, - {293, 302, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishImuResponse)}, - {303, 312, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishScaledImuResponse)}, - {313, 322, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishRawImuResponse)}, - {323, 332, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeResponse)}, - {333, 342, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse)}, - {343, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::Position)}, - {355, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::Heading)}, - {364, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::Quaternion)}, - {377, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::EulerAngle)}, - {389, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::AngularVelocityBody)}, - {400, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::GpsInfo)}, - {410, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::RawGps)}, - {432, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::Battery)}, - {442, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::RcStatus)}, - {453, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::StatusText)}, - {463, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::ActuatorControlTarget)}, - {473, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::ActuatorOutputStatus)}, - {483, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::Covariance)}, - {492, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::VelocityBody)}, - {503, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::PositionBody)}, - {514, 531, -1, sizeof(::mavsdk::rpc::telemetry_server::Odometry)}, - {540, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::DistanceSensor)}, - {551, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::ScaledPressure)}, - {564, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::PositionNed)}, - {575, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::VelocityNed)}, - {586, 596, -1, sizeof(::mavsdk::rpc::telemetry_server::PositionVelocityNed)}, - {598, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::GroundTruth)}, - {609, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::FixedwingMetrics)}, - {620, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::AccelerationFrd)}, - {631, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::AngularVelocityFrd)}, - {642, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::MagneticFieldFrd)}, - {653, 666, -1, sizeof(::mavsdk::rpc::telemetry_server::Imu)}, - {671, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::TelemetryServerResult)}, + {193, 203, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishAttitudeRequest)}, + {205, 214, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest)}, + {215, 224, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishPositionResponse)}, + {225, 234, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishHomeResponse)}, + {235, 244, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishSysStatusResponse)}, + {245, 254, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishExtendedSysStateResponse)}, + {255, 264, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishRawGpsResponse)}, + {265, 274, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishBatteryResponse)}, + {275, 284, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishStatusTextResponse)}, + {285, 294, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishOdometryResponse)}, + {295, 304, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishPositionVelocityNedResponse)}, + {305, 314, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishGroundTruthResponse)}, + {315, 324, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishImuResponse)}, + {325, 334, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishScaledImuResponse)}, + {335, 344, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishRawImuResponse)}, + {345, 354, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeResponse)}, + {355, 364, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse)}, + {365, 374, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishAttitudeResponse)}, + {375, 384, -1, sizeof(::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse)}, + {385, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::Position)}, + {397, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::Heading)}, + {406, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::Quaternion)}, + {419, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::EulerAngle)}, + {431, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::AngularVelocityBody)}, + {442, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::GpsInfo)}, + {452, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::RawGps)}, + {474, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::Battery)}, + {484, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::RcStatus)}, + {495, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::StatusText)}, + {505, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::ActuatorControlTarget)}, + {515, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::ActuatorOutputStatus)}, + {525, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::Covariance)}, + {534, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::VelocityBody)}, + {545, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::PositionBody)}, + {556, 573, -1, sizeof(::mavsdk::rpc::telemetry_server::Odometry)}, + {582, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::DistanceSensor)}, + {593, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::ScaledPressure)}, + {606, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::PositionNed)}, + {617, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::VelocityNed)}, + {628, 638, -1, sizeof(::mavsdk::rpc::telemetry_server::PositionVelocityNed)}, + {640, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::GroundTruth)}, + {651, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::FixedwingMetrics)}, + {665, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::AccelerationFrd)}, + {676, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::AngularVelocityFrd)}, + {687, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::MagneticFieldFrd)}, + {698, 711, -1, sizeof(::mavsdk::rpc::telemetry_server::Imu)}, + {716, -1, -1, sizeof(::mavsdk::rpc::telemetry_server::TelemetryServerResult)}, }; static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::telemetry_server::_PublishPositionRequest_default_instance_._instance, @@ -2410,6 +2563,8 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::telemetry_server::_PublishRawImuRequest_default_instance_._instance, &::mavsdk::rpc::telemetry_server::_PublishUnixEpochTimeRequest_default_instance_._instance, &::mavsdk::rpc::telemetry_server::_PublishDistanceSensorRequest_default_instance_._instance, + &::mavsdk::rpc::telemetry_server::_PublishAttitudeRequest_default_instance_._instance, + &::mavsdk::rpc::telemetry_server::_PublishVisualFlightRulesHudRequest_default_instance_._instance, &::mavsdk::rpc::telemetry_server::_PublishPositionResponse_default_instance_._instance, &::mavsdk::rpc::telemetry_server::_PublishHomeResponse_default_instance_._instance, &::mavsdk::rpc::telemetry_server::_PublishSysStatusResponse_default_instance_._instance, @@ -2425,6 +2580,8 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::telemetry_server::_PublishRawImuResponse_default_instance_._instance, &::mavsdk::rpc::telemetry_server::_PublishUnixEpochTimeResponse_default_instance_._instance, &::mavsdk::rpc::telemetry_server::_PublishDistanceSensorResponse_default_instance_._instance, + &::mavsdk::rpc::telemetry_server::_PublishAttitudeResponse_default_instance_._instance, + &::mavsdk::rpc::telemetry_server::_PublishVisualFlightRulesHudResponse_default_instance_._instance, &::mavsdk::rpc::telemetry_server::_Position_default_instance_._instance, &::mavsdk::rpc::telemetry_server::_Heading_default_instance_._instance, &::mavsdk::rpc::telemetry_server::_Quaternion_default_instance_._instance, @@ -2503,222 +2660,245 @@ const char descriptor_table_protodef_telemetry_5fserver_2ftelemetry_5fserver_2ep "blishUnixEpochTimeRequest\022\017\n\007time_us\030\001 \001" "(\004\"d\n\034PublishDistanceSensorRequest\022D\n\017di" "stance_sensor\030\001 \001(\0132+.mavsdk.rpc.telemet" - "ry_server.DistanceSensor\"n\n\027PublishPosit" - "ionResponse\022S\n\027telemetry_server_result\030\001" - " \001(\01322.mavsdk.rpc.telemetry_server.Telem" - "etryServerResult\"j\n\023PublishHomeResponse\022" + "ry_server.DistanceSensor\"\234\001\n\026PublishAtti" + "tudeRequest\0226\n\005angle\030\001 \001(\0132\'.mavsdk.rpc." + "telemetry_server.EulerAngle\022J\n\020angular_v" + "elocity\030\002 \001(\01320.mavsdk.rpc.telemetry_ser" + "ver.AngularVelocityBody\"o\n\"PublishVisual" + "FlightRulesHudRequest\022I\n\022fixed_wing_metr" + "ics\030\001 \001(\0132-.mavsdk.rpc.telemetry_server." + "FixedwingMetrics\"n\n\027PublishPositionRespo" + "nse\022S\n\027telemetry_server_result\030\001 \001(\01322.m" + "avsdk.rpc.telemetry_server.TelemetryServ" + "erResult\"j\n\023PublishHomeResponse\022S\n\027telem" + "etry_server_result\030\001 \001(\01322.mavsdk.rpc.te" + "lemetry_server.TelemetryServerResult\"o\n\030" + "PublishSysStatusResponse\022S\n\027telemetry_se" + "rver_result\030\001 \001(\01322.mavsdk.rpc.telemetry" + "_server.TelemetryServerResult\"v\n\037Publish" + "ExtendedSysStateResponse\022S\n\027telemetry_se" + "rver_result\030\001 \001(\01322.mavsdk.rpc.telemetry" + "_server.TelemetryServerResult\"l\n\025Publish" + "RawGpsResponse\022S\n\027telemetry_server_resul" + "t\030\001 \001(\01322.mavsdk.rpc.telemetry_server.Te" + "lemetryServerResult\"m\n\026PublishBatteryRes" + "ponse\022S\n\027telemetry_server_result\030\001 \001(\01322" + ".mavsdk.rpc.telemetry_server.TelemetrySe" + "rverResult\"p\n\031PublishStatusTextResponse\022" "S\n\027telemetry_server_result\030\001 \001(\01322.mavsd" "k.rpc.telemetry_server.TelemetryServerRe" - "sult\"o\n\030PublishSysStatusResponse\022S\n\027tele" - "metry_server_result\030\001 \001(\01322.mavsdk.rpc.t" - "elemetry_server.TelemetryServerResult\"v\n" - "\037PublishExtendedSysStateResponse\022S\n\027tele" - "metry_server_result\030\001 \001(\01322.mavsdk.rpc.t" - "elemetry_server.TelemetryServerResult\"l\n" - "\025PublishRawGpsResponse\022S\n\027telemetry_serv" - "er_result\030\001 \001(\01322.mavsdk.rpc.telemetry_s" - "erver.TelemetryServerResult\"m\n\026PublishBa" - "tteryResponse\022S\n\027telemetry_server_result" - "\030\001 \001(\01322.mavsdk.rpc.telemetry_server.Tel" - "emetryServerResult\"p\n\031PublishStatusTextR" - "esponse\022S\n\027telemetry_server_result\030\001 \001(\013" - "22.mavsdk.rpc.telemetry_server.Telemetry" - "ServerResult\"n\n\027PublishOdometryResponse\022" + "sult\"n\n\027PublishOdometryResponse\022S\n\027telem" + "etry_server_result\030\001 \001(\01322.mavsdk.rpc.te" + "lemetry_server.TelemetryServerResult\"y\n\"" + "PublishPositionVelocityNedResponse\022S\n\027te" + "lemetry_server_result\030\001 \001(\01322.mavsdk.rpc" + ".telemetry_server.TelemetryServerResult\"" + "q\n\032PublishGroundTruthResponse\022S\n\027telemet" + "ry_server_result\030\001 \001(\01322.mavsdk.rpc.tele" + "metry_server.TelemetryServerResult\"i\n\022Pu" + "blishImuResponse\022S\n\027telemetry_server_res" + "ult\030\001 \001(\01322.mavsdk.rpc.telemetry_server." + "TelemetryServerResult\"o\n\030PublishScaledIm" + "uResponse\022S\n\027telemetry_server_result\030\001 \001" + "(\01322.mavsdk.rpc.telemetry_server.Telemet" + "ryServerResult\"l\n\025PublishRawImuResponse\022" "S\n\027telemetry_server_result\030\001 \001(\01322.mavsd" "k.rpc.telemetry_server.TelemetryServerRe" - "sult\"y\n\"PublishPositionVelocityNedRespon" - "se\022S\n\027telemetry_server_result\030\001 \001(\01322.ma" - "vsdk.rpc.telemetry_server.TelemetryServe" - "rResult\"q\n\032PublishGroundTruthResponse\022S\n" - "\027telemetry_server_result\030\001 \001(\01322.mavsdk." - "rpc.telemetry_server.TelemetryServerResu" - "lt\"i\n\022PublishImuResponse\022S\n\027telemetry_se" - "rver_result\030\001 \001(\01322.mavsdk.rpc.telemetry" - "_server.TelemetryServerResult\"o\n\030Publish" - "ScaledImuResponse\022S\n\027telemetry_server_re" - "sult\030\001 \001(\01322.mavsdk.rpc.telemetry_server" - ".TelemetryServerResult\"l\n\025PublishRawImuR" - "esponse\022S\n\027telemetry_server_result\030\001 \001(\013" - "22.mavsdk.rpc.telemetry_server.Telemetry" - "ServerResult\"s\n\034PublishUnixEpochTimeResp" - "onse\022S\n\027telemetry_server_result\030\001 \001(\01322." - "mavsdk.rpc.telemetry_server.TelemetrySer" - "verResult\"t\n\035PublishDistanceSensorRespon" - "se\022S\n\027telemetry_server_result\030\001 \001(\01322.ma" - "vsdk.rpc.telemetry_server.TelemetryServe" - "rResult\"\225\001\n\010Position\022\035\n\014latitude_deg\030\001 \001" - "(\001B\007\202\265\030\003NaN\022\036\n\rlongitude_deg\030\002 \001(\001B\007\202\265\030\003" - "NaN\022$\n\023absolute_altitude_m\030\003 \001(\002B\007\202\265\030\003Na" - "N\022$\n\023relative_altitude_m\030\004 \001(\002B\007\202\265\030\003NaN\"" - "\'\n\007Heading\022\034\n\013heading_deg\030\001 \001(\001B\007\202\265\030\003NaN" - "\"r\n\nQuaternion\022\022\n\001w\030\001 \001(\002B\007\202\265\030\003NaN\022\022\n\001x\030" - "\002 \001(\002B\007\202\265\030\003NaN\022\022\n\001y\030\003 \001(\002B\007\202\265\030\003NaN\022\022\n\001z\030" - "\004 \001(\002B\007\202\265\030\003NaN\022\024\n\014timestamp_us\030\005 \001(\004\"s\n\n" - "EulerAngle\022\031\n\010roll_deg\030\001 \001(\002B\007\202\265\030\003NaN\022\032\n" - "\tpitch_deg\030\002 \001(\002B\007\202\265\030\003NaN\022\030\n\007yaw_deg\030\003 \001" - "(\002B\007\202\265\030\003NaN\022\024\n\014timestamp_us\030\004 \001(\004\"l\n\023Ang" - "ularVelocityBody\022\033\n\nroll_rad_s\030\001 \001(\002B\007\202\265" - "\030\003NaN\022\034\n\013pitch_rad_s\030\002 \001(\002B\007\202\265\030\003NaN\022\032\n\ty" - "aw_rad_s\030\003 \001(\002B\007\202\265\030\003NaN\"`\n\007GpsInfo\022\035\n\016nu" - "m_satellites\030\001 \001(\005B\005\202\265\030\0010\0226\n\010fix_type\030\002 " - "\001(\0162$.mavsdk.rpc.telemetry_server.FixTyp" - "e\"\337\002\n\006RawGps\022\024\n\014timestamp_us\030\001 \001(\004\022\024\n\014la" - "titude_deg\030\002 \001(\001\022\025\n\rlongitude_deg\030\003 \001(\001\022" - "\033\n\023absolute_altitude_m\030\004 \001(\002\022\014\n\004hdop\030\005 \001" - "(\002\022\014\n\004vdop\030\006 \001(\002\022\024\n\014velocity_m_s\030\007 \001(\002\022\017" - "\n\007cog_deg\030\010 \001(\002\022\034\n\024altitude_ellipsoid_m\030" - "\t \001(\002\022 \n\030horizontal_uncertainty_m\030\n \001(\002\022" - "\036\n\026vertical_uncertainty_m\030\013 \001(\002\022 \n\030veloc" - "ity_uncertainty_m_s\030\014 \001(\002\022\037\n\027heading_unc" - "ertainty_deg\030\r \001(\002\022\017\n\007yaw_deg\030\016 \001(\002\"I\n\007B" - "attery\022\032\n\tvoltage_v\030\001 \001(\002B\007\202\265\030\003NaN\022\"\n\021re" - "maining_percent\030\002 \001(\002B\007\202\265\030\003NaN\"|\n\010RcStat" - "us\022%\n\022was_available_once\030\001 \001(\010B\t\202\265\030\005fals" - "e\022\037\n\014is_available\030\002 \001(\010B\t\202\265\030\005false\022(\n\027si" - "gnal_strength_percent\030\003 \001(\002B\007\202\265\030\003NaN\"U\n\n" - "StatusText\0229\n\004type\030\001 \001(\0162+.mavsdk.rpc.te" - "lemetry_server.StatusTextType\022\014\n\004text\030\002 " - "\001(\t\"\?\n\025ActuatorControlTarget\022\024\n\005group\030\001 " - "\001(\005B\005\202\265\030\0010\022\020\n\010controls\030\002 \003(\002\"\?\n\024Actuator" - "OutputStatus\022\025\n\006active\030\001 \001(\rB\005\202\265\030\0010\022\020\n\010a" - "ctuator\030\002 \003(\002\"\'\n\nCovariance\022\031\n\021covarianc" - "e_matrix\030\001 \003(\002\";\n\014VelocityBody\022\r\n\005x_m_s\030" - "\001 \001(\002\022\r\n\005y_m_s\030\002 \001(\002\022\r\n\005z_m_s\030\003 \001(\002\"5\n\014P" - "ositionBody\022\013\n\003x_m\030\001 \001(\002\022\013\n\003y_m\030\002 \001(\002\022\013\n" - "\003z_m\030\003 \001(\002\"\244\005\n\010Odometry\022\021\n\ttime_usec\030\001 \001" - "(\004\022@\n\010frame_id\030\002 \001(\0162..mavsdk.rpc.teleme" - "try_server.Odometry.MavFrame\022F\n\016child_fr" - "ame_id\030\003 \001(\0162..mavsdk.rpc.telemetry_serv" - "er.Odometry.MavFrame\022@\n\rposition_body\030\004 " - "\001(\0132).mavsdk.rpc.telemetry_server.Positi" - "onBody\0222\n\001q\030\005 \001(\0132\'.mavsdk.rpc.telemetry" - "_server.Quaternion\022@\n\rvelocity_body\030\006 \001(" - "\0132).mavsdk.rpc.telemetry_server.Velocity" - "Body\022O\n\025angular_velocity_body\030\007 \001(\01320.ma" - "vsdk.rpc.telemetry_server.AngularVelocit" - "yBody\022@\n\017pose_covariance\030\010 \001(\0132\'.mavsdk." - "rpc.telemetry_server.Covariance\022D\n\023veloc" - "ity_covariance\030\t \001(\0132\'.mavsdk.rpc.teleme" - "try_server.Covariance\"j\n\010MavFrame\022\023\n\017MAV" - "_FRAME_UNDEF\020\000\022\026\n\022MAV_FRAME_BODY_NED\020\010\022\030" - "\n\024MAV_FRAME_VISION_NED\020\020\022\027\n\023MAV_FRAME_ES" - "TIM_NED\020\022\"\177\n\016DistanceSensor\022#\n\022minimum_d" - "istance_m\030\001 \001(\002B\007\202\265\030\003NaN\022#\n\022maximum_dist" - "ance_m\030\002 \001(\002B\007\202\265\030\003NaN\022#\n\022current_distanc" - "e_m\030\003 \001(\002B\007\202\265\030\003NaN\"\260\001\n\016ScaledPressure\022\024\n" - "\014timestamp_us\030\001 \001(\004\022\035\n\025absolute_pressure" - "_hpa\030\002 \001(\002\022!\n\031differential_pressure_hpa\030" - "\003 \001(\002\022\027\n\017temperature_deg\030\004 \001(\002\022-\n%differ" - "ential_pressure_temperature_deg\030\005 \001(\002\"Y\n" - "\013PositionNed\022\030\n\007north_m\030\001 \001(\002B\007\202\265\030\003NaN\022\027" - "\n\006east_m\030\002 \001(\002B\007\202\265\030\003NaN\022\027\n\006down_m\030\003 \001(\002B" - "\007\202\265\030\003NaN\"D\n\013VelocityNed\022\021\n\tnorth_m_s\030\001 \001" - "(\002\022\020\n\010east_m_s\030\002 \001(\002\022\020\n\010down_m_s\030\003 \001(\002\"\215" - "\001\n\023PositionVelocityNed\022:\n\010position\030\001 \001(\013" - "2(.mavsdk.rpc.telemetry_server.PositionN" - "ed\022:\n\010velocity\030\002 \001(\0132(.mavsdk.rpc.teleme" - "try_server.VelocityNed\"r\n\013GroundTruth\022\035\n" - "\014latitude_deg\030\001 \001(\001B\007\202\265\030\003NaN\022\036\n\rlongitud" - "e_deg\030\002 \001(\001B\007\202\265\030\003NaN\022$\n\023absolute_altitud" - "e_m\030\003 \001(\002B\007\202\265\030\003NaN\"x\n\020FixedwingMetrics\022\035" - "\n\014airspeed_m_s\030\001 \001(\002B\007\202\265\030\003NaN\022$\n\023throttl" - "e_percentage\030\002 \001(\002B\007\202\265\030\003NaN\022\037\n\016climb_rat" - "e_m_s\030\003 \001(\002B\007\202\265\030\003NaN\"i\n\017AccelerationFrd\022" - "\035\n\014forward_m_s2\030\001 \001(\002B\007\202\265\030\003NaN\022\033\n\nright_" - "m_s2\030\002 \001(\002B\007\202\265\030\003NaN\022\032\n\tdown_m_s2\030\003 \001(\002B\007" - "\202\265\030\003NaN\"o\n\022AngularVelocityFrd\022\036\n\rforward" - "_rad_s\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013right_rad_s\030\002 \001" - "(\002B\007\202\265\030\003NaN\022\033\n\ndown_rad_s\030\003 \001(\002B\007\202\265\030\003NaN" - "\"m\n\020MagneticFieldFrd\022\036\n\rforward_gauss\030\001 " - "\001(\002B\007\202\265\030\003NaN\022\034\n\013right_gauss\030\002 \001(\002B\007\202\265\030\003N" - "aN\022\033\n\ndown_gauss\030\003 \001(\002B\007\202\265\030\003NaN\"\240\002\n\003Imu\022" - "F\n\020acceleration_frd\030\001 \001(\0132,.mavsdk.rpc.t" - "elemetry_server.AccelerationFrd\022M\n\024angul" - "ar_velocity_frd\030\002 \001(\0132/.mavsdk.rpc.telem" - "etry_server.AngularVelocityFrd\022I\n\022magnet" - "ic_field_frd\030\003 \001(\0132-.mavsdk.rpc.telemetr" - "y_server.MagneticFieldFrd\022!\n\020temperature" - "_degc\030\004 \001(\002B\007\202\265\030\003NaN\022\024\n\014timestamp_us\030\005 \001" - "(\004\"\264\002\n\025TelemetryServerResult\022I\n\006result\030\001" - " \001(\01629.mavsdk.rpc.telemetry_server.Telem" - "etryServerResult.Result\022\022\n\nresult_str\030\002 " - "\001(\t\"\273\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RE" - "SULT_SUCCESS\020\001\022\024\n\020RESULT_NO_SYSTEM\020\002\022\033\n\027" - "RESULT_CONNECTION_ERROR\020\003\022\017\n\013RESULT_BUSY" - "\020\004\022\031\n\025RESULT_COMMAND_DENIED\020\005\022\022\n\016RESULT_" - "TIMEOUT\020\006\022\026\n\022RESULT_UNSUPPORTED\020\007*\244\001\n\007Fi" - "xType\022\023\n\017FIX_TYPE_NO_GPS\020\000\022\023\n\017FIX_TYPE_N" - "O_FIX\020\001\022\023\n\017FIX_TYPE_FIX_2D\020\002\022\023\n\017FIX_TYPE" - "_FIX_3D\020\003\022\025\n\021FIX_TYPE_FIX_DGPS\020\004\022\026\n\022FIX_" - "TYPE_RTK_FLOAT\020\005\022\026\n\022FIX_TYPE_RTK_FIXED\020\006" - "*\215\001\n\tVtolState\022\030\n\024VTOL_STATE_UNDEFINED\020\000" - "\022\037\n\033VTOL_STATE_TRANSITION_TO_FW\020\001\022\037\n\033VTO" - "L_STATE_TRANSITION_TO_MC\020\002\022\021\n\rVTOL_STATE" - "_MC\020\003\022\021\n\rVTOL_STATE_FW\020\004*\371\001\n\016StatusTextT" - "ype\022\032\n\026STATUS_TEXT_TYPE_DEBUG\020\000\022\031\n\025STATU" - "S_TEXT_TYPE_INFO\020\001\022\033\n\027STATUS_TEXT_TYPE_N" - "OTICE\020\002\022\034\n\030STATUS_TEXT_TYPE_WARNING\020\003\022\032\n" - "\026STATUS_TEXT_TYPE_ERROR\020\004\022\035\n\031STATUS_TEXT" - "_TYPE_CRITICAL\020\005\022\032\n\026STATUS_TEXT_TYPE_ALE" - "RT\020\006\022\036\n\032STATUS_TEXT_TYPE_EMERGENCY\020\007*\223\001\n" - "\013LandedState\022\030\n\024LANDED_STATE_UNKNOWN\020\000\022\032" - "\n\026LANDED_STATE_ON_GROUND\020\001\022\027\n\023LANDED_STA" - "TE_IN_AIR\020\002\022\033\n\027LANDED_STATE_TAKING_OFF\020\003" - "\022\030\n\024LANDED_STATE_LANDING\020\0042\243\020\n\026Telemetry" - "ServerService\022\202\001\n\017PublishPosition\0223.mavs" - "dk.rpc.telemetry_server.PublishPositionR" - "equest\0324.mavsdk.rpc.telemetry_server.Pub" - "lishPositionResponse\"\004\200\265\030\001\022v\n\013PublishHom" - "e\022/.mavsdk.rpc.telemetry_server.PublishH" - "omeRequest\0320.mavsdk.rpc.telemetry_server" - ".PublishHomeResponse\"\004\200\265\030\001\022\205\001\n\020PublishSy" - "sStatus\0224.mavsdk.rpc.telemetry_server.Pu" - "blishSysStatusRequest\0325.mavsdk.rpc.telem" - "etry_server.PublishSysStatusResponse\"\004\200\265" - "\030\001\022\232\001\n\027PublishExtendedSysState\022;.mavsdk." - "rpc.telemetry_server.PublishExtendedSysS" - "tateRequest\032<.mavsdk.rpc.telemetry_serve" - "r.PublishExtendedSysStateResponse\"\004\200\265\030\001\022" - "|\n\rPublishRawGps\0221.mavsdk.rpc.telemetry_" - "server.PublishRawGpsRequest\0322.mavsdk.rpc" - ".telemetry_server.PublishRawGpsResponse\"" - "\004\200\265\030\001\022\177\n\016PublishBattery\0222.mavsdk.rpc.tel" - "emetry_server.PublishBatteryRequest\0323.ma" - "vsdk.rpc.telemetry_server.PublishBattery" - "Response\"\004\200\265\030\001\022\210\001\n\021PublishStatusText\0225.m" - "avsdk.rpc.telemetry_server.PublishStatus" - "TextRequest\0326.mavsdk.rpc.telemetry_serve" - "r.PublishStatusTextResponse\"\004\200\265\030\001\022\202\001\n\017Pu" - "blishOdometry\0223.mavsdk.rpc.telemetry_ser" - "ver.PublishOdometryRequest\0324.mavsdk.rpc." - "telemetry_server.PublishOdometryResponse" - "\"\004\200\265\030\001\022\243\001\n\032PublishPositionVelocityNed\022>." - "mavsdk.rpc.telemetry_server.PublishPosit" - "ionVelocityNedRequest\032\?.mavsdk.rpc.telem" - "etry_server.PublishPositionVelocityNedRe" - "sponse\"\004\200\265\030\001\022\213\001\n\022PublishGroundTruth\0226.ma" - "vsdk.rpc.telemetry_server.PublishGroundT" - "ruthRequest\0327.mavsdk.rpc.telemetry_serve" - "r.PublishGroundTruthResponse\"\004\200\265\030\001\022s\n\nPu" - "blishImu\022..mavsdk.rpc.telemetry_server.P" - "ublishImuRequest\032/.mavsdk.rpc.telemetry_" - "server.PublishImuResponse\"\004\200\265\030\001\022\205\001\n\020Publ" - "ishScaledImu\0224.mavsdk.rpc.telemetry_serv" - "er.PublishScaledImuRequest\0325.mavsdk.rpc." - "telemetry_server.PublishScaledImuRespons" - "e\"\004\200\265\030\001\022|\n\rPublishRawImu\0221.mavsdk.rpc.te" - "lemetry_server.PublishRawImuRequest\0322.ma" + "sult\"s\n\034PublishUnixEpochTimeResponse\022S\n\027" + "telemetry_server_result\030\001 \001(\01322.mavsdk.r" + "pc.telemetry_server.TelemetryServerResul" + "t\"t\n\035PublishDistanceSensorResponse\022S\n\027te" + "lemetry_server_result\030\001 \001(\01322.mavsdk.rpc" + ".telemetry_server.TelemetryServerResult\"" + "n\n\027PublishAttitudeResponse\022S\n\027telemetry_" + "server_result\030\001 \001(\01322.mavsdk.rpc.telemet" + "ry_server.TelemetryServerResult\"z\n#Publi" + "shVisualFlightRulesHudResponse\022S\n\027teleme" + "try_server_result\030\001 \001(\01322.mavsdk.rpc.tel" + "emetry_server.TelemetryServerResult\"\225\001\n\010" + "Position\022\035\n\014latitude_deg\030\001 \001(\001B\007\202\265\030\003NaN\022" + "\036\n\rlongitude_deg\030\002 \001(\001B\007\202\265\030\003NaN\022$\n\023absol" + "ute_altitude_m\030\003 \001(\002B\007\202\265\030\003NaN\022$\n\023relativ" + "e_altitude_m\030\004 \001(\002B\007\202\265\030\003NaN\"\'\n\007Heading\022\034" + "\n\013heading_deg\030\001 \001(\001B\007\202\265\030\003NaN\"r\n\nQuaterni" + "on\022\022\n\001w\030\001 \001(\002B\007\202\265\030\003NaN\022\022\n\001x\030\002 \001(\002B\007\202\265\030\003N" + "aN\022\022\n\001y\030\003 \001(\002B\007\202\265\030\003NaN\022\022\n\001z\030\004 \001(\002B\007\202\265\030\003N" + "aN\022\024\n\014timestamp_us\030\005 \001(\004\"s\n\nEulerAngle\022\031" + "\n\010roll_deg\030\001 \001(\002B\007\202\265\030\003NaN\022\032\n\tpitch_deg\030\002" + " \001(\002B\007\202\265\030\003NaN\022\030\n\007yaw_deg\030\003 \001(\002B\007\202\265\030\003NaN\022" + "\024\n\014timestamp_us\030\004 \001(\004\"l\n\023AngularVelocity" + "Body\022\033\n\nroll_rad_s\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013pit" + "ch_rad_s\030\002 \001(\002B\007\202\265\030\003NaN\022\032\n\tyaw_rad_s\030\003 \001" + "(\002B\007\202\265\030\003NaN\"`\n\007GpsInfo\022\035\n\016num_satellites" + "\030\001 \001(\005B\005\202\265\030\0010\0226\n\010fix_type\030\002 \001(\0162$.mavsdk" + ".rpc.telemetry_server.FixType\"\337\002\n\006RawGps" + "\022\024\n\014timestamp_us\030\001 \001(\004\022\024\n\014latitude_deg\030\002" + " \001(\001\022\025\n\rlongitude_deg\030\003 \001(\001\022\033\n\023absolute_" + "altitude_m\030\004 \001(\002\022\014\n\004hdop\030\005 \001(\002\022\014\n\004vdop\030\006" + " \001(\002\022\024\n\014velocity_m_s\030\007 \001(\002\022\017\n\007cog_deg\030\010 " + "\001(\002\022\034\n\024altitude_ellipsoid_m\030\t \001(\002\022 \n\030hor" + "izontal_uncertainty_m\030\n \001(\002\022\036\n\026vertical_" + "uncertainty_m\030\013 \001(\002\022 \n\030velocity_uncertai" + "nty_m_s\030\014 \001(\002\022\037\n\027heading_uncertainty_deg" + "\030\r \001(\002\022\017\n\007yaw_deg\030\016 \001(\002\"I\n\007Battery\022\032\n\tvo" + "ltage_v\030\001 \001(\002B\007\202\265\030\003NaN\022\"\n\021remaining_perc" + "ent\030\002 \001(\002B\007\202\265\030\003NaN\"|\n\010RcStatus\022%\n\022was_av" + "ailable_once\030\001 \001(\010B\t\202\265\030\005false\022\037\n\014is_avai" + "lable\030\002 \001(\010B\t\202\265\030\005false\022(\n\027signal_strengt" + "h_percent\030\003 \001(\002B\007\202\265\030\003NaN\"U\n\nStatusText\0229" + "\n\004type\030\001 \001(\0162+.mavsdk.rpc.telemetry_serv" + "er.StatusTextType\022\014\n\004text\030\002 \001(\t\"\?\n\025Actua" + "torControlTarget\022\024\n\005group\030\001 \001(\005B\005\202\265\030\0010\022\020" + "\n\010controls\030\002 \003(\002\"\?\n\024ActuatorOutputStatus" + "\022\025\n\006active\030\001 \001(\rB\005\202\265\030\0010\022\020\n\010actuator\030\002 \003(" + "\002\"\'\n\nCovariance\022\031\n\021covariance_matrix\030\001 \003" + "(\002\";\n\014VelocityBody\022\r\n\005x_m_s\030\001 \001(\002\022\r\n\005y_m" + "_s\030\002 \001(\002\022\r\n\005z_m_s\030\003 \001(\002\"5\n\014PositionBody\022" + "\013\n\003x_m\030\001 \001(\002\022\013\n\003y_m\030\002 \001(\002\022\013\n\003z_m\030\003 \001(\002\"\244" + "\005\n\010Odometry\022\021\n\ttime_usec\030\001 \001(\004\022@\n\010frame_" + "id\030\002 \001(\0162..mavsdk.rpc.telemetry_server.O" + "dometry.MavFrame\022F\n\016child_frame_id\030\003 \001(\016" + "2..mavsdk.rpc.telemetry_server.Odometry." + "MavFrame\022@\n\rposition_body\030\004 \001(\0132).mavsdk" + ".rpc.telemetry_server.PositionBody\0222\n\001q\030" + "\005 \001(\0132\'.mavsdk.rpc.telemetry_server.Quat" + "ernion\022@\n\rvelocity_body\030\006 \001(\0132).mavsdk.r" + "pc.telemetry_server.VelocityBody\022O\n\025angu" + "lar_velocity_body\030\007 \001(\01320.mavsdk.rpc.tel" + "emetry_server.AngularVelocityBody\022@\n\017pos" + "e_covariance\030\010 \001(\0132\'.mavsdk.rpc.telemetr" + "y_server.Covariance\022D\n\023velocity_covarian" + "ce\030\t \001(\0132\'.mavsdk.rpc.telemetry_server.C" + "ovariance\"j\n\010MavFrame\022\023\n\017MAV_FRAME_UNDEF" + "\020\000\022\026\n\022MAV_FRAME_BODY_NED\020\010\022\030\n\024MAV_FRAME_" + "VISION_NED\020\020\022\027\n\023MAV_FRAME_ESTIM_NED\020\022\"\177\n" + "\016DistanceSensor\022#\n\022minimum_distance_m\030\001 " + "\001(\002B\007\202\265\030\003NaN\022#\n\022maximum_distance_m\030\002 \001(\002" + "B\007\202\265\030\003NaN\022#\n\022current_distance_m\030\003 \001(\002B\007\202" + "\265\030\003NaN\"\260\001\n\016ScaledPressure\022\024\n\014timestamp_u" + "s\030\001 \001(\004\022\035\n\025absolute_pressure_hpa\030\002 \001(\002\022!" + "\n\031differential_pressure_hpa\030\003 \001(\002\022\027\n\017tem" + "perature_deg\030\004 \001(\002\022-\n%differential_press" + "ure_temperature_deg\030\005 \001(\002\"Y\n\013PositionNed" + "\022\030\n\007north_m\030\001 \001(\002B\007\202\265\030\003NaN\022\027\n\006east_m\030\002 \001" + "(\002B\007\202\265\030\003NaN\022\027\n\006down_m\030\003 \001(\002B\007\202\265\030\003NaN\"D\n\013" + "VelocityNed\022\021\n\tnorth_m_s\030\001 \001(\002\022\020\n\010east_m" + "_s\030\002 \001(\002\022\020\n\010down_m_s\030\003 \001(\002\"\215\001\n\023PositionV" + "elocityNed\022:\n\010position\030\001 \001(\0132(.mavsdk.rp" + "c.telemetry_server.PositionNed\022:\n\010veloci" + "ty\030\002 \001(\0132(.mavsdk.rpc.telemetry_server.V" + "elocityNed\"r\n\013GroundTruth\022\035\n\014latitude_de" + "g\030\001 \001(\001B\007\202\265\030\003NaN\022\036\n\rlongitude_deg\030\002 \001(\001B" + "\007\202\265\030\003NaN\022$\n\023absolute_altitude_m\030\003 \001(\002B\007\202" + "\265\030\003NaN\"\336\001\n\020FixedwingMetrics\022\035\n\014airspeed_" + "m_s\030\001 \001(\002B\007\202\265\030\003NaN\022$\n\023throttle_percentag" + "e\030\002 \001(\002B\007\202\265\030\003NaN\022\037\n\016climb_rate_m_s\030\003 \001(\002" + "B\007\202\265\030\003NaN\022 \n\017groundspeed_m_s\030\004 \001(\002B\007\202\265\030\003" + "NaN\022\034\n\013heading_deg\030\005 \001(\002B\007\202\265\030\003NaN\022$\n\023abs" + "olute_altitude_m\030\006 \001(\002B\007\202\265\030\003NaN\"i\n\017Accel" + "erationFrd\022\035\n\014forward_m_s2\030\001 \001(\002B\007\202\265\030\003Na" + "N\022\033\n\nright_m_s2\030\002 \001(\002B\007\202\265\030\003NaN\022\032\n\tdown_m" + "_s2\030\003 \001(\002B\007\202\265\030\003NaN\"o\n\022AngularVelocityFrd" + "\022\036\n\rforward_rad_s\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013righ" + "t_rad_s\030\002 \001(\002B\007\202\265\030\003NaN\022\033\n\ndown_rad_s\030\003 \001" + "(\002B\007\202\265\030\003NaN\"m\n\020MagneticFieldFrd\022\036\n\rforwa" + "rd_gauss\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013right_gauss\030\002" + " \001(\002B\007\202\265\030\003NaN\022\033\n\ndown_gauss\030\003 \001(\002B\007\202\265\030\003N" + "aN\"\240\002\n\003Imu\022F\n\020acceleration_frd\030\001 \001(\0132,.m" + "avsdk.rpc.telemetry_server.AccelerationF" + "rd\022M\n\024angular_velocity_frd\030\002 \001(\0132/.mavsd" + "k.rpc.telemetry_server.AngularVelocityFr" + "d\022I\n\022magnetic_field_frd\030\003 \001(\0132-.mavsdk.r" + "pc.telemetry_server.MagneticFieldFrd\022!\n\020" + "temperature_degc\030\004 \001(\002B\007\202\265\030\003NaN\022\024\n\014times" + "tamp_us\030\005 \001(\004\"\264\002\n\025TelemetryServerResult\022" + "I\n\006result\030\001 \001(\01629.mavsdk.rpc.telemetry_s" + "erver.TelemetryServerResult.Result\022\022\n\nre" + "sult_str\030\002 \001(\t\"\273\001\n\006Result\022\022\n\016RESULT_UNKN" + "OWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\024\n\020RESULT_NO_S" + "YSTEM\020\002\022\033\n\027RESULT_CONNECTION_ERROR\020\003\022\017\n\013" + "RESULT_BUSY\020\004\022\031\n\025RESULT_COMMAND_DENIED\020\005" + "\022\022\n\016RESULT_TIMEOUT\020\006\022\026\n\022RESULT_UNSUPPORT" + "ED\020\007*\244\001\n\007FixType\022\023\n\017FIX_TYPE_NO_GPS\020\000\022\023\n" + "\017FIX_TYPE_NO_FIX\020\001\022\023\n\017FIX_TYPE_FIX_2D\020\002\022" + "\023\n\017FIX_TYPE_FIX_3D\020\003\022\025\n\021FIX_TYPE_FIX_DGP" + "S\020\004\022\026\n\022FIX_TYPE_RTK_FLOAT\020\005\022\026\n\022FIX_TYPE_" + "RTK_FIXED\020\006*\215\001\n\tVtolState\022\030\n\024VTOL_STATE_" + "UNDEFINED\020\000\022\037\n\033VTOL_STATE_TRANSITION_TO_" + "FW\020\001\022\037\n\033VTOL_STATE_TRANSITION_TO_MC\020\002\022\021\n" + "\rVTOL_STATE_MC\020\003\022\021\n\rVTOL_STATE_FW\020\004*\371\001\n\016" + "StatusTextType\022\032\n\026STATUS_TEXT_TYPE_DEBUG" + "\020\000\022\031\n\025STATUS_TEXT_TYPE_INFO\020\001\022\033\n\027STATUS_" + "TEXT_TYPE_NOTICE\020\002\022\034\n\030STATUS_TEXT_TYPE_W" + "ARNING\020\003\022\032\n\026STATUS_TEXT_TYPE_ERROR\020\004\022\035\n\031" + "STATUS_TEXT_TYPE_CRITICAL\020\005\022\032\n\026STATUS_TE" + "XT_TYPE_ALERT\020\006\022\036\n\032STATUS_TEXT_TYPE_EMER" + "GENCY\020\007*\223\001\n\013LandedState\022\030\n\024LANDED_STATE_" + "UNKNOWN\020\000\022\032\n\026LANDED_STATE_ON_GROUND\020\001\022\027\n" + "\023LANDED_STATE_IN_AIR\020\002\022\033\n\027LANDED_STATE_T" + "AKING_OFF\020\003\022\030\n\024LANDED_STATE_LANDING\020\0042\321\022" + "\n\026TelemetryServerService\022\202\001\n\017PublishPosi" + "tion\0223.mavsdk.rpc.telemetry_server.Publi" + "shPositionRequest\0324.mavsdk.rpc.telemetry" + "_server.PublishPositionResponse\"\004\200\265\030\001\022v\n" + "\013PublishHome\022/.mavsdk.rpc.telemetry_serv" + "er.PublishHomeRequest\0320.mavsdk.rpc.telem" + "etry_server.PublishHomeResponse\"\004\200\265\030\001\022\205\001" + "\n\020PublishSysStatus\0224.mavsdk.rpc.telemetr" + "y_server.PublishSysStatusRequest\0325.mavsd" + "k.rpc.telemetry_server.PublishSysStatusR" + "esponse\"\004\200\265\030\001\022\232\001\n\027PublishExtendedSysStat" + "e\022;.mavsdk.rpc.telemetry_server.PublishE" + "xtendedSysStateRequest\032<.mavsdk.rpc.tele" + "metry_server.PublishExtendedSysStateResp" + "onse\"\004\200\265\030\001\022|\n\rPublishRawGps\0221.mavsdk.rpc" + ".telemetry_server.PublishRawGpsRequest\0322" + ".mavsdk.rpc.telemetry_server.PublishRawG" + "psResponse\"\004\200\265\030\001\022\177\n\016PublishBattery\0222.mav" + "sdk.rpc.telemetry_server.PublishBatteryR" + "equest\0323.mavsdk.rpc.telemetry_server.Pub" + "lishBatteryResponse\"\004\200\265\030\001\022\210\001\n\021PublishSta" + "tusText\0225.mavsdk.rpc.telemetry_server.Pu" + "blishStatusTextRequest\0326.mavsdk.rpc.tele" + "metry_server.PublishStatusTextResponse\"\004" + "\200\265\030\001\022\202\001\n\017PublishOdometry\0223.mavsdk.rpc.te" + "lemetry_server.PublishOdometryRequest\0324." + "mavsdk.rpc.telemetry_server.PublishOdome" + "tryResponse\"\004\200\265\030\001\022\243\001\n\032PublishPositionVel" + "ocityNed\022>.mavsdk.rpc.telemetry_server.P" + "ublishPositionVelocityNedRequest\032\?.mavsd" + "k.rpc.telemetry_server.PublishPositionVe" + "locityNedResponse\"\004\200\265\030\001\022\213\001\n\022PublishGroun" + "dTruth\0226.mavsdk.rpc.telemetry_server.Pub" + "lishGroundTruthRequest\0327.mavsdk.rpc.tele" + "metry_server.PublishGroundTruthResponse\"" + "\004\200\265\030\001\022s\n\nPublishImu\022..mavsdk.rpc.telemet" + "ry_server.PublishImuRequest\032/.mavsdk.rpc" + ".telemetry_server.PublishImuResponse\"\004\200\265" + "\030\001\022\205\001\n\020PublishScaledImu\0224.mavsdk.rpc.tel" + "emetry_server.PublishScaledImuRequest\0325." + "mavsdk.rpc.telemetry_server.PublishScale" + "dImuResponse\"\004\200\265\030\001\022|\n\rPublishRawImu\0221.ma" "vsdk.rpc.telemetry_server.PublishRawImuR" - "esponse\"\004\200\265\030\001\022\221\001\n\024PublishUnixEpochTime\0228" - ".mavsdk.rpc.telemetry_server.PublishUnix" - "EpochTimeRequest\0329.mavsdk.rpc.telemetry_" - "server.PublishUnixEpochTimeResponse\"\004\200\265\030" - "\001\022\224\001\n\025PublishDistanceSensor\0229.mavsdk.rpc" - ".telemetry_server.PublishDistanceSensorR" - "equest\032:.mavsdk.rpc.telemetry_server.Pub" - "lishDistanceSensorResponse\"\004\200\265\030\001B2\n\032io.m" - "avsdk.telemetry_serverB\024TelemetryServerP" - "rotob\006proto3" + "equest\0322.mavsdk.rpc.telemetry_server.Pub" + "lishRawImuResponse\"\004\200\265\030\001\022\221\001\n\024PublishUnix" + "EpochTime\0228.mavsdk.rpc.telemetry_server." + "PublishUnixEpochTimeRequest\0329.mavsdk.rpc" + ".telemetry_server.PublishUnixEpochTimeRe" + "sponse\"\004\200\265\030\001\022\224\001\n\025PublishDistanceSensor\0229" + ".mavsdk.rpc.telemetry_server.PublishDist" + "anceSensorRequest\032:.mavsdk.rpc.telemetry" + "_server.PublishDistanceSensorResponse\"\004\200" + "\265\030\001\022\202\001\n\017PublishAttitude\0223.mavsdk.rpc.tel" + "emetry_server.PublishAttitudeRequest\0324.m" + "avsdk.rpc.telemetry_server.PublishAttitu" + "deResponse\"\004\200\265\030\001\022\246\001\n\033PublishVisualFlight" + "RulesHud\022\?.mavsdk.rpc.telemetry_server.P" + "ublishVisualFlightRulesHudRequest\032@.mavs" + "dk.rpc.telemetry_server.PublishVisualFli" + "ghtRulesHudResponse\"\004\200\265\030\001B2\n\032io.mavsdk.t" + "elemetry_serverB\024TelemetryServerProtob\006p" + "roto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto_deps[1] = { @@ -2728,13 +2908,13 @@ static ::absl::once_flag descriptor_table_telemetry_5fserver_2ftelemetry_5fserve PROTOBUF_CONSTINIT const ::_pbi::DescriptorTable descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto = { false, false, - 10492, + 11405, descriptor_table_protodef_telemetry_5fserver_2ftelemetry_5fserver_2eproto, "telemetry_server/telemetry_server.proto", &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto_once, descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto_deps, 1, - 61, + 65, schemas, file_default_instances, TableStruct_telemetry_5fserver_2ftelemetry_5fserver_2eproto::offsets, @@ -7455,175 +7635,204 @@ ::google::protobuf::Metadata PublishDistanceSensorRequest::GetMetadata() const { } // =================================================================== -class PublishPositionResponse::_Internal { +class PublishAttitudeRequest::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishPositionResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishAttitudeRequest, _impl_._has_bits_); }; -PublishPositionResponse::PublishPositionResponse(::google::protobuf::Arena* arena) +PublishAttitudeRequest::PublishAttitudeRequest(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishPositionResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishAttitudeRequest) } -inline PROTOBUF_NDEBUG_INLINE PublishPositionResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishAttitudeRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishPositionResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishAttitudeRequest& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishPositionResponse::PublishPositionResponse( +PublishAttitudeRequest::PublishAttitudeRequest( ::google::protobuf::Arena* arena, - const PublishPositionResponse& from) + const PublishAttitudeRequest& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishPositionResponse* const _this = this; + PublishAttitudeRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_, from); ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.telemetry_server_result_ = (cached_has_bits & 0x00000001u) ? ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::TelemetryServerResult>( - arena, *from._impl_.telemetry_server_result_) + _impl_.angle_ = (cached_has_bits & 0x00000001u) ? ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::EulerAngle>( + arena, *from._impl_.angle_) + : nullptr; + _impl_.angular_velocity_ = (cached_has_bits & 0x00000002u) ? ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::AngularVelocityBody>( + arena, *from._impl_.angular_velocity_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishPositionResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishAttitudeRequest) } -inline PROTOBUF_NDEBUG_INLINE PublishPositionResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishAttitudeRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishPositionResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishAttitudeRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.telemetry_server_result_ = {}; + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, angle_), + 0, + offsetof(Impl_, angular_velocity_) - + offsetof(Impl_, angle_) + + sizeof(Impl_::angular_velocity_)); } -PublishPositionResponse::~PublishPositionResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishPositionResponse) +PublishAttitudeRequest::~PublishAttitudeRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishAttitudeRequest) SharedDtor(*this); } -inline void PublishPositionResponse::SharedDtor(MessageLite& self) { - PublishPositionResponse& this_ = static_cast(self); +inline void PublishAttitudeRequest::SharedDtor(MessageLite& self) { + PublishAttitudeRequest& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); - delete this_._impl_.telemetry_server_result_; + delete this_._impl_.angle_; + delete this_._impl_.angular_velocity_; this_._impl_.~Impl_(); } -inline void* PublishPositionResponse::PlacementNew_(const void*, void* mem, +inline void* PublishAttitudeRequest::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishPositionResponse(arena); + return ::new (mem) PublishAttitudeRequest(arena); } -constexpr auto PublishPositionResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishPositionResponse), - alignof(PublishPositionResponse)); +constexpr auto PublishAttitudeRequest::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishAttitudeRequest), + alignof(PublishAttitudeRequest)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishPositionResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishAttitudeRequest::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishPositionResponse_default_instance_._instance, + &_PublishAttitudeRequest_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishPositionResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishAttitudeRequest::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishPositionResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishPositionResponse::ByteSizeLong, - &PublishPositionResponse::_InternalSerialize, + &PublishAttitudeRequest::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishAttitudeRequest::ByteSizeLong, + &PublishAttitudeRequest::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishPositionResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishAttitudeRequest, _impl_._cached_size_), false, }, - &PublishPositionResponse::kDescriptorMethods, + &PublishAttitudeRequest::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishPositionResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishAttitudeRequest::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishPositionResponse::_table_ = { +const ::_pbi::TcParseTable<1, 2, 2, 0, 2> PublishAttitudeRequest::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishPositionResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishAttitudeRequest, _impl_._has_bits_), 0, // no _extensions_ - 1, 0, // max_field_number, fast_idx_mask + 2, 8, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967294, // skipmap + 4294967292, // skipmap offsetof(decltype(_table_), field_entries), - 1, // num_field_entries - 1, // num_aux_entries + 2, // num_field_entries + 2, // num_aux_entries offsetof(decltype(_table_), aux_entries), _class_data_.base(), nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishPositionResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishAttitudeRequest>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ - // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + // .mavsdk.rpc.telemetry_server.AngularVelocityBody angular_velocity = 2; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishPositionResponse, _impl_.telemetry_server_result_)}}, + {18, 1, 1, PROTOBUF_FIELD_OFFSET(PublishAttitudeRequest, _impl_.angular_velocity_)}}, + // .mavsdk.rpc.telemetry_server.EulerAngle angle = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishAttitudeRequest, _impl_.angle_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishPositionResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry_server.EulerAngle angle = 1; + {PROTOBUF_FIELD_OFFSET(PublishAttitudeRequest, _impl_.angle_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // .mavsdk.rpc.telemetry_server.AngularVelocityBody angular_velocity = 2; + {PROTOBUF_FIELD_OFFSET(PublishAttitudeRequest, _impl_.angular_velocity_), _Internal::kHasBitsOffset + 1, 1, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::EulerAngle>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::AngularVelocityBody>()}, }}, {{ }}, }; -PROTOBUF_NOINLINE void PublishPositionResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishPositionResponse) +PROTOBUF_NOINLINE void PublishAttitudeRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishAttitudeRequest) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.telemetry_server_result_ != nullptr); - _impl_.telemetry_server_result_->Clear(); + if (cached_has_bits & 0x00000003u) { + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.angle_ != nullptr); + _impl_.angle_->Clear(); + } + if (cached_has_bits & 0x00000002u) { + ABSL_DCHECK(_impl_.angular_velocity_ != nullptr); + _impl_.angular_velocity_->Clear(); + } } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishPositionResponse::_InternalSerialize( + ::uint8_t* PublishAttitudeRequest::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishPositionResponse& this_ = static_cast(base); + const PublishAttitudeRequest& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishPositionResponse::_InternalSerialize( + ::uint8_t* PublishAttitudeRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishPositionResponse& this_ = *this; + const PublishAttitudeRequest& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishPositionResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishAttitudeRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = this_._impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + // .mavsdk.rpc.telemetry_server.EulerAngle angle = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, *this_._impl_.telemetry_server_result_, this_._impl_.telemetry_server_result_->GetCachedSize(), target, + 1, *this_._impl_.angle_, this_._impl_.angle_->GetCachedSize(), target, + stream); + } + + // .mavsdk.rpc.telemetry_server.AngularVelocityBody angular_velocity = 2; + if (cached_has_bits & 0x00000002u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 2, *this_._impl_.angular_velocity_, this_._impl_.angular_velocity_->GetCachedSize(), target, stream); } @@ -7632,182 +7841,204 @@ PROTOBUF_NOINLINE void PublishPositionResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishPositionResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishAttitudeRequest) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishPositionResponse::ByteSizeLong(const MessageLite& base) { - const PublishPositionResponse& this_ = static_cast(base); + ::size_t PublishAttitudeRequest::ByteSizeLong(const MessageLite& base) { + const PublishAttitudeRequest& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishPositionResponse::ByteSizeLong() const { - const PublishPositionResponse& this_ = *this; + ::size_t PublishAttitudeRequest::ByteSizeLong() const { + const PublishAttitudeRequest& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishPositionResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishAttitudeRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void)cached_has_bits; - { - // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - cached_has_bits = this_._impl_._has_bits_[0]; + ::_pbi::Prefetch5LinesFrom7Lines(&this_); + cached_has_bits = this_._impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + // .mavsdk.rpc.telemetry_server.EulerAngle angle = 1; if (cached_has_bits & 0x00000001u) { total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSize(*this_._impl_.telemetry_server_result_); + ::google::protobuf::internal::WireFormatLite::MessageSize(*this_._impl_.angle_); + } + // .mavsdk.rpc.telemetry_server.AngularVelocityBody angular_velocity = 2; + if (cached_has_bits & 0x00000002u) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize(*this_._impl_.angular_velocity_); } } return this_.MaybeComputeUnknownFieldsSize(total_size, &this_._impl_._cached_size_); } -void PublishPositionResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishAttitudeRequest::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishPositionResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishAttitudeRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; cached_has_bits = from._impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(from._impl_.telemetry_server_result_ != nullptr); - if (_this->_impl_.telemetry_server_result_ == nullptr) { - _this->_impl_.telemetry_server_result_ = - ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::TelemetryServerResult>(arena, *from._impl_.telemetry_server_result_); - } else { - _this->_impl_.telemetry_server_result_->MergeFrom(*from._impl_.telemetry_server_result_); + if (cached_has_bits & 0x00000003u) { + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(from._impl_.angle_ != nullptr); + if (_this->_impl_.angle_ == nullptr) { + _this->_impl_.angle_ = + ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::EulerAngle>(arena, *from._impl_.angle_); + } else { + _this->_impl_.angle_->MergeFrom(*from._impl_.angle_); + } + } + if (cached_has_bits & 0x00000002u) { + ABSL_DCHECK(from._impl_.angular_velocity_ != nullptr); + if (_this->_impl_.angular_velocity_ == nullptr) { + _this->_impl_.angular_velocity_ = + ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::AngularVelocityBody>(arena, *from._impl_.angular_velocity_); + } else { + _this->_impl_.angular_velocity_->MergeFrom(*from._impl_.angular_velocity_); + } } } _this->_impl_._has_bits_[0] |= cached_has_bits; _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishPositionResponse::CopyFrom(const PublishPositionResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishPositionResponse) +void PublishAttitudeRequest::CopyFrom(const PublishAttitudeRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishAttitudeRequest) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishPositionResponse::InternalSwap(PublishPositionResponse* PROTOBUF_RESTRICT other) { +void PublishAttitudeRequest::InternalSwap(PublishAttitudeRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(PublishAttitudeRequest, _impl_.angular_velocity_) + + sizeof(PublishAttitudeRequest::_impl_.angular_velocity_) + - PROTOBUF_FIELD_OFFSET(PublishAttitudeRequest, _impl_.angle_)>( + reinterpret_cast(&_impl_.angle_), + reinterpret_cast(&other->_impl_.angle_)); } -::google::protobuf::Metadata PublishPositionResponse::GetMetadata() const { +::google::protobuf::Metadata PublishAttitudeRequest::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== -class PublishHomeResponse::_Internal { +class PublishVisualFlightRulesHudRequest::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishHomeResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishVisualFlightRulesHudRequest, _impl_._has_bits_); }; -PublishHomeResponse::PublishHomeResponse(::google::protobuf::Arena* arena) +PublishVisualFlightRulesHudRequest::PublishVisualFlightRulesHudRequest(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishHomeResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest) } -inline PROTOBUF_NDEBUG_INLINE PublishHomeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishVisualFlightRulesHudRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishHomeResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishHomeResponse::PublishHomeResponse( +PublishVisualFlightRulesHudRequest::PublishVisualFlightRulesHudRequest( ::google::protobuf::Arena* arena, - const PublishHomeResponse& from) + const PublishVisualFlightRulesHudRequest& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishHomeResponse* const _this = this; + PublishVisualFlightRulesHudRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_, from); ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.telemetry_server_result_ = (cached_has_bits & 0x00000001u) ? ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::TelemetryServerResult>( - arena, *from._impl_.telemetry_server_result_) + _impl_.fixed_wing_metrics_ = (cached_has_bits & 0x00000001u) ? ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::FixedwingMetrics>( + arena, *from._impl_.fixed_wing_metrics_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishHomeResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest) } -inline PROTOBUF_NDEBUG_INLINE PublishHomeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishVisualFlightRulesHudRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishHomeResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishVisualFlightRulesHudRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.telemetry_server_result_ = {}; + _impl_.fixed_wing_metrics_ = {}; } -PublishHomeResponse::~PublishHomeResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishHomeResponse) +PublishVisualFlightRulesHudRequest::~PublishVisualFlightRulesHudRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest) SharedDtor(*this); } -inline void PublishHomeResponse::SharedDtor(MessageLite& self) { - PublishHomeResponse& this_ = static_cast(self); +inline void PublishVisualFlightRulesHudRequest::SharedDtor(MessageLite& self) { + PublishVisualFlightRulesHudRequest& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); - delete this_._impl_.telemetry_server_result_; + delete this_._impl_.fixed_wing_metrics_; this_._impl_.~Impl_(); } -inline void* PublishHomeResponse::PlacementNew_(const void*, void* mem, +inline void* PublishVisualFlightRulesHudRequest::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishHomeResponse(arena); + return ::new (mem) PublishVisualFlightRulesHudRequest(arena); } -constexpr auto PublishHomeResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishHomeResponse), - alignof(PublishHomeResponse)); +constexpr auto PublishVisualFlightRulesHudRequest::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishVisualFlightRulesHudRequest), + alignof(PublishVisualFlightRulesHudRequest)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishHomeResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishVisualFlightRulesHudRequest::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishHomeResponse_default_instance_._instance, + &_PublishVisualFlightRulesHudRequest_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishHomeResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishVisualFlightRulesHudRequest::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishHomeResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishHomeResponse::ByteSizeLong, - &PublishHomeResponse::_InternalSerialize, + &PublishVisualFlightRulesHudRequest::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishVisualFlightRulesHudRequest::ByteSizeLong, + &PublishVisualFlightRulesHudRequest::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishHomeResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishVisualFlightRulesHudRequest, _impl_._cached_size_), false, }, - &PublishHomeResponse::kDescriptorMethods, + &PublishVisualFlightRulesHudRequest::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishHomeResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishVisualFlightRulesHudRequest::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishHomeResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishVisualFlightRulesHudRequest::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishHomeResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishVisualFlightRulesHudRequest, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -7820,26 +8051,26 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishHomeResponse::_table_ = { nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishHomeResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudRequest>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ - // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + // .mavsdk.rpc.telemetry_server.FixedwingMetrics fixed_wing_metrics = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishHomeResponse, _impl_.telemetry_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishVisualFlightRulesHudRequest, _impl_.fixed_wing_metrics_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishHomeResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.telemetry_server.FixedwingMetrics fixed_wing_metrics = 1; + {PROTOBUF_FIELD_OFFSET(PublishVisualFlightRulesHudRequest, _impl_.fixed_wing_metrics_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::FixedwingMetrics>()}, }}, {{ }}, }; -PROTOBUF_NOINLINE void PublishHomeResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishHomeResponse) +PROTOBUF_NOINLINE void PublishVisualFlightRulesHudRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -7847,33 +8078,33 @@ PROTOBUF_NOINLINE void PublishHomeResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.telemetry_server_result_ != nullptr); - _impl_.telemetry_server_result_->Clear(); + ABSL_DCHECK(_impl_.fixed_wing_metrics_ != nullptr); + _impl_.fixed_wing_metrics_->Clear(); } _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishHomeResponse::_InternalSerialize( + ::uint8_t* PublishVisualFlightRulesHudRequest::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishHomeResponse& this_ = static_cast(base); + const PublishVisualFlightRulesHudRequest& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishHomeResponse::_InternalSerialize( + ::uint8_t* PublishVisualFlightRulesHudRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishHomeResponse& this_ = *this; + const PublishVisualFlightRulesHudRequest& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishHomeResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; cached_has_bits = this_._impl_._has_bits_[0]; - // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + // .mavsdk.rpc.telemetry_server.FixedwingMetrics fixed_wing_metrics = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, *this_._impl_.telemetry_server_result_, this_._impl_.telemetry_server_result_->GetCachedSize(), target, + 1, *this_._impl_.fixed_wing_metrics_, this_._impl_.fixed_wing_metrics_->GetCachedSize(), target, stream); } @@ -7882,18 +8113,18 @@ PROTOBUF_NOINLINE void PublishHomeResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishHomeResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishHomeResponse::ByteSizeLong(const MessageLite& base) { - const PublishHomeResponse& this_ = static_cast(base); + ::size_t PublishVisualFlightRulesHudRequest::ByteSizeLong(const MessageLite& base) { + const PublishVisualFlightRulesHudRequest& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishHomeResponse::ByteSizeLong() const { - const PublishHomeResponse& this_ = *this; + ::size_t PublishVisualFlightRulesHudRequest::ByteSizeLong() const { + const PublishVisualFlightRulesHudRequest& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishHomeResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -7901,92 +8132,92 @@ PROTOBUF_NOINLINE void PublishHomeResponse::Clear() { (void)cached_has_bits; { - // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + // .mavsdk.rpc.telemetry_server.FixedwingMetrics fixed_wing_metrics = 1; cached_has_bits = this_._impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSize(*this_._impl_.telemetry_server_result_); + ::google::protobuf::internal::WireFormatLite::MessageSize(*this_._impl_.fixed_wing_metrics_); } } return this_.MaybeComputeUnknownFieldsSize(total_size, &this_._impl_._cached_size_); } -void PublishHomeResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishVisualFlightRulesHudRequest::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishHomeResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; cached_has_bits = from._impl_._has_bits_[0]; if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(from._impl_.telemetry_server_result_ != nullptr); - if (_this->_impl_.telemetry_server_result_ == nullptr) { - _this->_impl_.telemetry_server_result_ = - ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::TelemetryServerResult>(arena, *from._impl_.telemetry_server_result_); + ABSL_DCHECK(from._impl_.fixed_wing_metrics_ != nullptr); + if (_this->_impl_.fixed_wing_metrics_ == nullptr) { + _this->_impl_.fixed_wing_metrics_ = + ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::FixedwingMetrics>(arena, *from._impl_.fixed_wing_metrics_); } else { - _this->_impl_.telemetry_server_result_->MergeFrom(*from._impl_.telemetry_server_result_); + _this->_impl_.fixed_wing_metrics_->MergeFrom(*from._impl_.fixed_wing_metrics_); } } _this->_impl_._has_bits_[0] |= cached_has_bits; _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishHomeResponse::CopyFrom(const PublishHomeResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishHomeResponse) +void PublishVisualFlightRulesHudRequest::CopyFrom(const PublishVisualFlightRulesHudRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishHomeResponse::InternalSwap(PublishHomeResponse* PROTOBUF_RESTRICT other) { +void PublishVisualFlightRulesHudRequest::InternalSwap(PublishVisualFlightRulesHudRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); + swap(_impl_.fixed_wing_metrics_, other->_impl_.fixed_wing_metrics_); } -::google::protobuf::Metadata PublishHomeResponse::GetMetadata() const { +::google::protobuf::Metadata PublishVisualFlightRulesHudRequest::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== -class PublishSysStatusResponse::_Internal { +class PublishPositionResponse::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishSysStatusResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishPositionResponse, _impl_._has_bits_); }; -PublishSysStatusResponse::PublishSysStatusResponse(::google::protobuf::Arena* arena) +PublishPositionResponse::PublishPositionResponse(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishPositionResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishSysStatusResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishPositionResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishSysStatusResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishPositionResponse& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishSysStatusResponse::PublishSysStatusResponse( +PublishPositionResponse::PublishPositionResponse( ::google::protobuf::Arena* arena, - const PublishSysStatusResponse& from) + const PublishPositionResponse& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishSysStatusResponse* const _this = this; + PublishPositionResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -7996,68 +8227,68 @@ PublishSysStatusResponse::PublishSysStatusResponse( arena, *from._impl_.telemetry_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishPositionResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishSysStatusResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishPositionResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishSysStatusResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishPositionResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_server_result_ = {}; } -PublishSysStatusResponse::~PublishSysStatusResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) +PublishPositionResponse::~PublishPositionResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishPositionResponse) SharedDtor(*this); } -inline void PublishSysStatusResponse::SharedDtor(MessageLite& self) { - PublishSysStatusResponse& this_ = static_cast(self); +inline void PublishPositionResponse::SharedDtor(MessageLite& self) { + PublishPositionResponse& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); delete this_._impl_.telemetry_server_result_; this_._impl_.~Impl_(); } -inline void* PublishSysStatusResponse::PlacementNew_(const void*, void* mem, +inline void* PublishPositionResponse::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishSysStatusResponse(arena); + return ::new (mem) PublishPositionResponse(arena); } -constexpr auto PublishSysStatusResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishSysStatusResponse), - alignof(PublishSysStatusResponse)); +constexpr auto PublishPositionResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishPositionResponse), + alignof(PublishPositionResponse)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishSysStatusResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishPositionResponse::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishSysStatusResponse_default_instance_._instance, + &_PublishPositionResponse_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishSysStatusResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishPositionResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishSysStatusResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishSysStatusResponse::ByteSizeLong, - &PublishSysStatusResponse::_InternalSerialize, + &PublishPositionResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishPositionResponse::ByteSizeLong, + &PublishPositionResponse::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishSysStatusResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishPositionResponse, _impl_._cached_size_), false, }, - &PublishSysStatusResponse::kDescriptorMethods, + &PublishPositionResponse::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishSysStatusResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishPositionResponse::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishSysStatusResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishPositionResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishSysStatusResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishPositionResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -8070,17 +8301,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishSysStatusResponse::_table_ = { nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishSysStatusResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishPositionResponse>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishSysStatusResponse, _impl_.telemetry_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishPositionResponse, _impl_.telemetry_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishSysStatusResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(PublishPositionResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, @@ -8088,8 +8319,8 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishSysStatusResponse::_table_ = { }}, }; -PROTOBUF_NOINLINE void PublishSysStatusResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) +PROTOBUF_NOINLINE void PublishPositionResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishPositionResponse) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -8105,17 +8336,17 @@ PROTOBUF_NOINLINE void PublishSysStatusResponse::Clear() { } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishSysStatusResponse::_InternalSerialize( + ::uint8_t* PublishPositionResponse::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishSysStatusResponse& this_ = static_cast(base); + const PublishPositionResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishSysStatusResponse::_InternalSerialize( + ::uint8_t* PublishPositionResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishSysStatusResponse& this_ = *this; + const PublishPositionResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishPositionResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -8132,18 +8363,18 @@ PROTOBUF_NOINLINE void PublishSysStatusResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishPositionResponse) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishSysStatusResponse::ByteSizeLong(const MessageLite& base) { - const PublishSysStatusResponse& this_ = static_cast(base); + ::size_t PublishPositionResponse::ByteSizeLong(const MessageLite& base) { + const PublishPositionResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishSysStatusResponse::ByteSizeLong() const { - const PublishSysStatusResponse& this_ = *this; + ::size_t PublishPositionResponse::ByteSizeLong() const { + const PublishPositionResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishPositionResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -8162,11 +8393,11 @@ PROTOBUF_NOINLINE void PublishSysStatusResponse::Clear() { &this_._impl_._cached_size_); } -void PublishSysStatusResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishPositionResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishPositionResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -8185,58 +8416,58 @@ void PublishSysStatusResponse::MergeImpl(::google::protobuf::MessageLite& to_msg _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishSysStatusResponse::CopyFrom(const PublishSysStatusResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) +void PublishPositionResponse::CopyFrom(const PublishPositionResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishPositionResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishSysStatusResponse::InternalSwap(PublishSysStatusResponse* PROTOBUF_RESTRICT other) { +void PublishPositionResponse::InternalSwap(PublishPositionResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); } -::google::protobuf::Metadata PublishSysStatusResponse::GetMetadata() const { +::google::protobuf::Metadata PublishPositionResponse::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== -class PublishExtendedSysStateResponse::_Internal { +class PublishHomeResponse::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishExtendedSysStateResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishHomeResponse, _impl_._has_bits_); }; -PublishExtendedSysStateResponse::PublishExtendedSysStateResponse(::google::protobuf::Arena* arena) +PublishHomeResponse::PublishHomeResponse(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishHomeResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishExtendedSysStateResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishHomeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishExtendedSysStateResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishHomeResponse& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishExtendedSysStateResponse::PublishExtendedSysStateResponse( +PublishHomeResponse::PublishHomeResponse( ::google::protobuf::Arena* arena, - const PublishExtendedSysStateResponse& from) + const PublishHomeResponse& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishExtendedSysStateResponse* const _this = this; + PublishHomeResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -8246,68 +8477,68 @@ PublishExtendedSysStateResponse::PublishExtendedSysStateResponse( arena, *from._impl_.telemetry_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishHomeResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishExtendedSysStateResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishHomeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishExtendedSysStateResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishHomeResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_server_result_ = {}; } -PublishExtendedSysStateResponse::~PublishExtendedSysStateResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) +PublishHomeResponse::~PublishHomeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishHomeResponse) SharedDtor(*this); } -inline void PublishExtendedSysStateResponse::SharedDtor(MessageLite& self) { - PublishExtendedSysStateResponse& this_ = static_cast(self); +inline void PublishHomeResponse::SharedDtor(MessageLite& self) { + PublishHomeResponse& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); delete this_._impl_.telemetry_server_result_; this_._impl_.~Impl_(); } -inline void* PublishExtendedSysStateResponse::PlacementNew_(const void*, void* mem, +inline void* PublishHomeResponse::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishExtendedSysStateResponse(arena); + return ::new (mem) PublishHomeResponse(arena); } -constexpr auto PublishExtendedSysStateResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishExtendedSysStateResponse), - alignof(PublishExtendedSysStateResponse)); +constexpr auto PublishHomeResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishHomeResponse), + alignof(PublishHomeResponse)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishExtendedSysStateResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishHomeResponse::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishExtendedSysStateResponse_default_instance_._instance, + &_PublishHomeResponse_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishExtendedSysStateResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishHomeResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishExtendedSysStateResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishExtendedSysStateResponse::ByteSizeLong, - &PublishExtendedSysStateResponse::_InternalSerialize, + &PublishHomeResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishHomeResponse::ByteSizeLong, + &PublishHomeResponse::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishExtendedSysStateResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishHomeResponse, _impl_._cached_size_), false, }, - &PublishExtendedSysStateResponse::kDescriptorMethods, + &PublishHomeResponse::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishExtendedSysStateResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishHomeResponse::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishExtendedSysStateResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishHomeResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishExtendedSysStateResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishHomeResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -8320,17 +8551,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishExtendedSysStateResponse::_tabl nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishExtendedSysStateResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishHomeResponse>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishExtendedSysStateResponse, _impl_.telemetry_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishHomeResponse, _impl_.telemetry_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishExtendedSysStateResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(PublishHomeResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, @@ -8338,8 +8569,8 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishExtendedSysStateResponse::_tabl }}, }; -PROTOBUF_NOINLINE void PublishExtendedSysStateResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) +PROTOBUF_NOINLINE void PublishHomeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishHomeResponse) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -8355,17 +8586,17 @@ PROTOBUF_NOINLINE void PublishExtendedSysStateResponse::Clear() { } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishExtendedSysStateResponse::_InternalSerialize( + ::uint8_t* PublishHomeResponse::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishExtendedSysStateResponse& this_ = static_cast(base); + const PublishHomeResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishExtendedSysStateResponse::_InternalSerialize( + ::uint8_t* PublishHomeResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishExtendedSysStateResponse& this_ = *this; + const PublishHomeResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishHomeResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -8382,18 +8613,18 @@ PROTOBUF_NOINLINE void PublishExtendedSysStateResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishHomeResponse) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishExtendedSysStateResponse::ByteSizeLong(const MessageLite& base) { - const PublishExtendedSysStateResponse& this_ = static_cast(base); + ::size_t PublishHomeResponse::ByteSizeLong(const MessageLite& base) { + const PublishHomeResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishExtendedSysStateResponse::ByteSizeLong() const { - const PublishExtendedSysStateResponse& this_ = *this; + ::size_t PublishHomeResponse::ByteSizeLong() const { + const PublishHomeResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishHomeResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -8412,11 +8643,11 @@ PROTOBUF_NOINLINE void PublishExtendedSysStateResponse::Clear() { &this_._impl_._cached_size_); } -void PublishExtendedSysStateResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishHomeResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishHomeResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -8435,58 +8666,58 @@ void PublishExtendedSysStateResponse::MergeImpl(::google::protobuf::MessageLite& _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishExtendedSysStateResponse::CopyFrom(const PublishExtendedSysStateResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) +void PublishHomeResponse::CopyFrom(const PublishHomeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishHomeResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishExtendedSysStateResponse::InternalSwap(PublishExtendedSysStateResponse* PROTOBUF_RESTRICT other) { +void PublishHomeResponse::InternalSwap(PublishHomeResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); } -::google::protobuf::Metadata PublishExtendedSysStateResponse::GetMetadata() const { +::google::protobuf::Metadata PublishHomeResponse::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== -class PublishRawGpsResponse::_Internal { +class PublishSysStatusResponse::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishRawGpsResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishSysStatusResponse, _impl_._has_bits_); }; -PublishRawGpsResponse::PublishRawGpsResponse(::google::protobuf::Arena* arena) +PublishSysStatusResponse::PublishSysStatusResponse(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishRawGpsResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishSysStatusResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishRawGpsResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishSysStatusResponse& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishRawGpsResponse::PublishRawGpsResponse( +PublishSysStatusResponse::PublishSysStatusResponse( ::google::protobuf::Arena* arena, - const PublishRawGpsResponse& from) + const PublishSysStatusResponse& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishRawGpsResponse* const _this = this; + PublishSysStatusResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -8496,68 +8727,68 @@ PublishRawGpsResponse::PublishRawGpsResponse( arena, *from._impl_.telemetry_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishRawGpsResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishSysStatusResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishRawGpsResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishSysStatusResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_server_result_ = {}; } -PublishRawGpsResponse::~PublishRawGpsResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) +PublishSysStatusResponse::~PublishSysStatusResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) SharedDtor(*this); } -inline void PublishRawGpsResponse::SharedDtor(MessageLite& self) { - PublishRawGpsResponse& this_ = static_cast(self); +inline void PublishSysStatusResponse::SharedDtor(MessageLite& self) { + PublishSysStatusResponse& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); delete this_._impl_.telemetry_server_result_; this_._impl_.~Impl_(); } -inline void* PublishRawGpsResponse::PlacementNew_(const void*, void* mem, +inline void* PublishSysStatusResponse::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishRawGpsResponse(arena); + return ::new (mem) PublishSysStatusResponse(arena); } -constexpr auto PublishRawGpsResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishRawGpsResponse), - alignof(PublishRawGpsResponse)); +constexpr auto PublishSysStatusResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishSysStatusResponse), + alignof(PublishSysStatusResponse)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishRawGpsResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishSysStatusResponse::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishRawGpsResponse_default_instance_._instance, + &_PublishSysStatusResponse_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishRawGpsResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishSysStatusResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishRawGpsResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishRawGpsResponse::ByteSizeLong, - &PublishRawGpsResponse::_InternalSerialize, + &PublishSysStatusResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishSysStatusResponse::ByteSizeLong, + &PublishSysStatusResponse::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishRawGpsResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishSysStatusResponse, _impl_._cached_size_), false, }, - &PublishRawGpsResponse::kDescriptorMethods, + &PublishSysStatusResponse::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishRawGpsResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishSysStatusResponse::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishRawGpsResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishSysStatusResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishRawGpsResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishSysStatusResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -8570,17 +8801,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishRawGpsResponse::_table_ = { nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishRawGpsResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishSysStatusResponse>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishRawGpsResponse, _impl_.telemetry_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishSysStatusResponse, _impl_.telemetry_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishRawGpsResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(PublishSysStatusResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, @@ -8588,8 +8819,8 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishRawGpsResponse::_table_ = { }}, }; -PROTOBUF_NOINLINE void PublishRawGpsResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) +PROTOBUF_NOINLINE void PublishSysStatusResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -8605,17 +8836,17 @@ PROTOBUF_NOINLINE void PublishRawGpsResponse::Clear() { } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishRawGpsResponse::_InternalSerialize( + ::uint8_t* PublishSysStatusResponse::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishRawGpsResponse& this_ = static_cast(base); + const PublishSysStatusResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishRawGpsResponse::_InternalSerialize( + ::uint8_t* PublishSysStatusResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishRawGpsResponse& this_ = *this; + const PublishSysStatusResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -8632,18 +8863,18 @@ PROTOBUF_NOINLINE void PublishRawGpsResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishRawGpsResponse::ByteSizeLong(const MessageLite& base) { - const PublishRawGpsResponse& this_ = static_cast(base); + ::size_t PublishSysStatusResponse::ByteSizeLong(const MessageLite& base) { + const PublishSysStatusResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishRawGpsResponse::ByteSizeLong() const { - const PublishRawGpsResponse& this_ = *this; + ::size_t PublishSysStatusResponse::ByteSizeLong() const { + const PublishSysStatusResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -8662,11 +8893,11 @@ PROTOBUF_NOINLINE void PublishRawGpsResponse::Clear() { &this_._impl_._cached_size_); } -void PublishRawGpsResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishSysStatusResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -8685,58 +8916,58 @@ void PublishRawGpsResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, c _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishRawGpsResponse::CopyFrom(const PublishRawGpsResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) +void PublishSysStatusResponse::CopyFrom(const PublishSysStatusResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishRawGpsResponse::InternalSwap(PublishRawGpsResponse* PROTOBUF_RESTRICT other) { +void PublishSysStatusResponse::InternalSwap(PublishSysStatusResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); } -::google::protobuf::Metadata PublishRawGpsResponse::GetMetadata() const { +::google::protobuf::Metadata PublishSysStatusResponse::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== -class PublishBatteryResponse::_Internal { +class PublishExtendedSysStateResponse::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishBatteryResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishExtendedSysStateResponse, _impl_._has_bits_); }; -PublishBatteryResponse::PublishBatteryResponse(::google::protobuf::Arena* arena) +PublishExtendedSysStateResponse::PublishExtendedSysStateResponse(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishBatteryResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishBatteryResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishExtendedSysStateResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishBatteryResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishExtendedSysStateResponse& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishBatteryResponse::PublishBatteryResponse( +PublishExtendedSysStateResponse::PublishExtendedSysStateResponse( ::google::protobuf::Arena* arena, - const PublishBatteryResponse& from) + const PublishExtendedSysStateResponse& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishBatteryResponse* const _this = this; + PublishExtendedSysStateResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -8746,68 +8977,68 @@ PublishBatteryResponse::PublishBatteryResponse( arena, *from._impl_.telemetry_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishBatteryResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishBatteryResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishExtendedSysStateResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishBatteryResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishExtendedSysStateResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_server_result_ = {}; } -PublishBatteryResponse::~PublishBatteryResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishBatteryResponse) +PublishExtendedSysStateResponse::~PublishExtendedSysStateResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) SharedDtor(*this); } -inline void PublishBatteryResponse::SharedDtor(MessageLite& self) { - PublishBatteryResponse& this_ = static_cast(self); +inline void PublishExtendedSysStateResponse::SharedDtor(MessageLite& self) { + PublishExtendedSysStateResponse& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); delete this_._impl_.telemetry_server_result_; this_._impl_.~Impl_(); } -inline void* PublishBatteryResponse::PlacementNew_(const void*, void* mem, +inline void* PublishExtendedSysStateResponse::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishBatteryResponse(arena); + return ::new (mem) PublishExtendedSysStateResponse(arena); } -constexpr auto PublishBatteryResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishBatteryResponse), - alignof(PublishBatteryResponse)); +constexpr auto PublishExtendedSysStateResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishExtendedSysStateResponse), + alignof(PublishExtendedSysStateResponse)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishBatteryResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishExtendedSysStateResponse::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishBatteryResponse_default_instance_._instance, + &_PublishExtendedSysStateResponse_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishBatteryResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishExtendedSysStateResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishBatteryResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishBatteryResponse::ByteSizeLong, - &PublishBatteryResponse::_InternalSerialize, + &PublishExtendedSysStateResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishExtendedSysStateResponse::ByteSizeLong, + &PublishExtendedSysStateResponse::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishBatteryResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishExtendedSysStateResponse, _impl_._cached_size_), false, }, - &PublishBatteryResponse::kDescriptorMethods, + &PublishExtendedSysStateResponse::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishBatteryResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishExtendedSysStateResponse::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishBatteryResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishExtendedSysStateResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishBatteryResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishExtendedSysStateResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -8820,17 +9051,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishBatteryResponse::_table_ = { nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishBatteryResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishExtendedSysStateResponse>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishBatteryResponse, _impl_.telemetry_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishExtendedSysStateResponse, _impl_.telemetry_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishBatteryResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(PublishExtendedSysStateResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, @@ -8838,8 +9069,8 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishBatteryResponse::_table_ = { }}, }; -PROTOBUF_NOINLINE void PublishBatteryResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishBatteryResponse) +PROTOBUF_NOINLINE void PublishExtendedSysStateResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -8855,17 +9086,17 @@ PROTOBUF_NOINLINE void PublishBatteryResponse::Clear() { } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishBatteryResponse::_InternalSerialize( + ::uint8_t* PublishExtendedSysStateResponse::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishBatteryResponse& this_ = static_cast(base); + const PublishExtendedSysStateResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishBatteryResponse::_InternalSerialize( + ::uint8_t* PublishExtendedSysStateResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishBatteryResponse& this_ = *this; + const PublishExtendedSysStateResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishBatteryResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -8882,18 +9113,18 @@ PROTOBUF_NOINLINE void PublishBatteryResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishBatteryResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishBatteryResponse::ByteSizeLong(const MessageLite& base) { - const PublishBatteryResponse& this_ = static_cast(base); + ::size_t PublishExtendedSysStateResponse::ByteSizeLong(const MessageLite& base) { + const PublishExtendedSysStateResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishBatteryResponse::ByteSizeLong() const { - const PublishBatteryResponse& this_ = *this; + ::size_t PublishExtendedSysStateResponse::ByteSizeLong() const { + const PublishExtendedSysStateResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishBatteryResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -8912,11 +9143,11 @@ PROTOBUF_NOINLINE void PublishBatteryResponse::Clear() { &this_._impl_._cached_size_); } -void PublishBatteryResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishExtendedSysStateResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishBatteryResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -8935,58 +9166,58 @@ void PublishBatteryResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishBatteryResponse::CopyFrom(const PublishBatteryResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishBatteryResponse) +void PublishExtendedSysStateResponse::CopyFrom(const PublishExtendedSysStateResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishBatteryResponse::InternalSwap(PublishBatteryResponse* PROTOBUF_RESTRICT other) { +void PublishExtendedSysStateResponse::InternalSwap(PublishExtendedSysStateResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); } -::google::protobuf::Metadata PublishBatteryResponse::GetMetadata() const { +::google::protobuf::Metadata PublishExtendedSysStateResponse::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== -class PublishStatusTextResponse::_Internal { +class PublishRawGpsResponse::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishStatusTextResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishRawGpsResponse, _impl_._has_bits_); }; -PublishStatusTextResponse::PublishStatusTextResponse(::google::protobuf::Arena* arena) +PublishRawGpsResponse::PublishRawGpsResponse(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishStatusTextResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishRawGpsResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishStatusTextResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishRawGpsResponse& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishStatusTextResponse::PublishStatusTextResponse( +PublishRawGpsResponse::PublishRawGpsResponse( ::google::protobuf::Arena* arena, - const PublishStatusTextResponse& from) + const PublishRawGpsResponse& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishStatusTextResponse* const _this = this; + PublishRawGpsResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -8996,68 +9227,68 @@ PublishStatusTextResponse::PublishStatusTextResponse( arena, *from._impl_.telemetry_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishStatusTextResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishRawGpsResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishStatusTextResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishRawGpsResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_server_result_ = {}; } -PublishStatusTextResponse::~PublishStatusTextResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) +PublishRawGpsResponse::~PublishRawGpsResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) SharedDtor(*this); } -inline void PublishStatusTextResponse::SharedDtor(MessageLite& self) { - PublishStatusTextResponse& this_ = static_cast(self); +inline void PublishRawGpsResponse::SharedDtor(MessageLite& self) { + PublishRawGpsResponse& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); delete this_._impl_.telemetry_server_result_; this_._impl_.~Impl_(); } -inline void* PublishStatusTextResponse::PlacementNew_(const void*, void* mem, +inline void* PublishRawGpsResponse::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishStatusTextResponse(arena); + return ::new (mem) PublishRawGpsResponse(arena); } -constexpr auto PublishStatusTextResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishStatusTextResponse), - alignof(PublishStatusTextResponse)); +constexpr auto PublishRawGpsResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishRawGpsResponse), + alignof(PublishRawGpsResponse)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishStatusTextResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishRawGpsResponse::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishStatusTextResponse_default_instance_._instance, + &_PublishRawGpsResponse_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishStatusTextResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishRawGpsResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishStatusTextResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishStatusTextResponse::ByteSizeLong, - &PublishStatusTextResponse::_InternalSerialize, + &PublishRawGpsResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishRawGpsResponse::ByteSizeLong, + &PublishRawGpsResponse::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishStatusTextResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishRawGpsResponse, _impl_._cached_size_), false, }, - &PublishStatusTextResponse::kDescriptorMethods, + &PublishRawGpsResponse::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishStatusTextResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishRawGpsResponse::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishStatusTextResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishRawGpsResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishStatusTextResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishRawGpsResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -9070,17 +9301,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishStatusTextResponse::_table_ = { nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishStatusTextResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishRawGpsResponse>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishStatusTextResponse, _impl_.telemetry_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishRawGpsResponse, _impl_.telemetry_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishStatusTextResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(PublishRawGpsResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, @@ -9088,8 +9319,8 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishStatusTextResponse::_table_ = { }}, }; -PROTOBUF_NOINLINE void PublishStatusTextResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) +PROTOBUF_NOINLINE void PublishRawGpsResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -9105,17 +9336,17 @@ PROTOBUF_NOINLINE void PublishStatusTextResponse::Clear() { } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishStatusTextResponse::_InternalSerialize( + ::uint8_t* PublishRawGpsResponse::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishStatusTextResponse& this_ = static_cast(base); + const PublishRawGpsResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishStatusTextResponse::_InternalSerialize( + ::uint8_t* PublishRawGpsResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishStatusTextResponse& this_ = *this; + const PublishRawGpsResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -9132,18 +9363,18 @@ PROTOBUF_NOINLINE void PublishStatusTextResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishStatusTextResponse::ByteSizeLong(const MessageLite& base) { - const PublishStatusTextResponse& this_ = static_cast(base); + ::size_t PublishRawGpsResponse::ByteSizeLong(const MessageLite& base) { + const PublishRawGpsResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishStatusTextResponse::ByteSizeLong() const { - const PublishStatusTextResponse& this_ = *this; + ::size_t PublishRawGpsResponse::ByteSizeLong() const { + const PublishRawGpsResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -9162,11 +9393,11 @@ PROTOBUF_NOINLINE void PublishStatusTextResponse::Clear() { &this_._impl_._cached_size_); } -void PublishStatusTextResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishRawGpsResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -9185,58 +9416,58 @@ void PublishStatusTextResponse::MergeImpl(::google::protobuf::MessageLite& to_ms _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishStatusTextResponse::CopyFrom(const PublishStatusTextResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) +void PublishRawGpsResponse::CopyFrom(const PublishRawGpsResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishStatusTextResponse::InternalSwap(PublishStatusTextResponse* PROTOBUF_RESTRICT other) { +void PublishRawGpsResponse::InternalSwap(PublishRawGpsResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); } -::google::protobuf::Metadata PublishStatusTextResponse::GetMetadata() const { +::google::protobuf::Metadata PublishRawGpsResponse::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== -class PublishOdometryResponse::_Internal { +class PublishBatteryResponse::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishOdometryResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishBatteryResponse, _impl_._has_bits_); }; -PublishOdometryResponse::PublishOdometryResponse(::google::protobuf::Arena* arena) +PublishBatteryResponse::PublishBatteryResponse(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishOdometryResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishBatteryResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishOdometryResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishBatteryResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishOdometryResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishBatteryResponse& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishOdometryResponse::PublishOdometryResponse( +PublishBatteryResponse::PublishBatteryResponse( ::google::protobuf::Arena* arena, - const PublishOdometryResponse& from) + const PublishBatteryResponse& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishOdometryResponse* const _this = this; + PublishBatteryResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -9246,68 +9477,68 @@ PublishOdometryResponse::PublishOdometryResponse( arena, *from._impl_.telemetry_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishOdometryResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishBatteryResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishOdometryResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishBatteryResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishOdometryResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishBatteryResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_server_result_ = {}; } -PublishOdometryResponse::~PublishOdometryResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishOdometryResponse) +PublishBatteryResponse::~PublishBatteryResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishBatteryResponse) SharedDtor(*this); } -inline void PublishOdometryResponse::SharedDtor(MessageLite& self) { - PublishOdometryResponse& this_ = static_cast(self); +inline void PublishBatteryResponse::SharedDtor(MessageLite& self) { + PublishBatteryResponse& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); delete this_._impl_.telemetry_server_result_; this_._impl_.~Impl_(); } -inline void* PublishOdometryResponse::PlacementNew_(const void*, void* mem, +inline void* PublishBatteryResponse::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishOdometryResponse(arena); + return ::new (mem) PublishBatteryResponse(arena); } -constexpr auto PublishOdometryResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishOdometryResponse), - alignof(PublishOdometryResponse)); +constexpr auto PublishBatteryResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishBatteryResponse), + alignof(PublishBatteryResponse)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishOdometryResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishBatteryResponse::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishOdometryResponse_default_instance_._instance, + &_PublishBatteryResponse_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishOdometryResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishBatteryResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishOdometryResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishOdometryResponse::ByteSizeLong, - &PublishOdometryResponse::_InternalSerialize, + &PublishBatteryResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishBatteryResponse::ByteSizeLong, + &PublishBatteryResponse::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishOdometryResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishBatteryResponse, _impl_._cached_size_), false, }, - &PublishOdometryResponse::kDescriptorMethods, + &PublishBatteryResponse::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishOdometryResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishBatteryResponse::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishOdometryResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishBatteryResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishOdometryResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishBatteryResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -9320,17 +9551,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishOdometryResponse::_table_ = { nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishOdometryResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishBatteryResponse>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishOdometryResponse, _impl_.telemetry_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishBatteryResponse, _impl_.telemetry_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishOdometryResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(PublishBatteryResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, @@ -9338,8 +9569,8 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishOdometryResponse::_table_ = { }}, }; -PROTOBUF_NOINLINE void PublishOdometryResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishOdometryResponse) +PROTOBUF_NOINLINE void PublishBatteryResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishBatteryResponse) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -9355,17 +9586,17 @@ PROTOBUF_NOINLINE void PublishOdometryResponse::Clear() { } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishOdometryResponse::_InternalSerialize( + ::uint8_t* PublishBatteryResponse::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishOdometryResponse& this_ = static_cast(base); + const PublishBatteryResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishOdometryResponse::_InternalSerialize( + ::uint8_t* PublishBatteryResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishOdometryResponse& this_ = *this; + const PublishBatteryResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishOdometryResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishBatteryResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -9382,18 +9613,18 @@ PROTOBUF_NOINLINE void PublishOdometryResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishOdometryResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishBatteryResponse) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishOdometryResponse::ByteSizeLong(const MessageLite& base) { - const PublishOdometryResponse& this_ = static_cast(base); + ::size_t PublishBatteryResponse::ByteSizeLong(const MessageLite& base) { + const PublishBatteryResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishOdometryResponse::ByteSizeLong() const { - const PublishOdometryResponse& this_ = *this; + ::size_t PublishBatteryResponse::ByteSizeLong() const { + const PublishBatteryResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishOdometryResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishBatteryResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -9412,11 +9643,11 @@ PROTOBUF_NOINLINE void PublishOdometryResponse::Clear() { &this_._impl_._cached_size_); } -void PublishOdometryResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishBatteryResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishOdometryResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishBatteryResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -9435,58 +9666,58 @@ void PublishOdometryResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishOdometryResponse::CopyFrom(const PublishOdometryResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishOdometryResponse) +void PublishBatteryResponse::CopyFrom(const PublishBatteryResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishBatteryResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishOdometryResponse::InternalSwap(PublishOdometryResponse* PROTOBUF_RESTRICT other) { +void PublishBatteryResponse::InternalSwap(PublishBatteryResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); } -::google::protobuf::Metadata PublishOdometryResponse::GetMetadata() const { +::google::protobuf::Metadata PublishBatteryResponse::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== -class PublishPositionVelocityNedResponse::_Internal { +class PublishStatusTextResponse::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishPositionVelocityNedResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishStatusTextResponse, _impl_._has_bits_); }; -PublishPositionVelocityNedResponse::PublishPositionVelocityNedResponse(::google::protobuf::Arena* arena) +PublishStatusTextResponse::PublishStatusTextResponse(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishPositionVelocityNedResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishStatusTextResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishPositionVelocityNedResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishStatusTextResponse& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishPositionVelocityNedResponse::PublishPositionVelocityNedResponse( +PublishStatusTextResponse::PublishStatusTextResponse( ::google::protobuf::Arena* arena, - const PublishPositionVelocityNedResponse& from) + const PublishStatusTextResponse& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishPositionVelocityNedResponse* const _this = this; + PublishStatusTextResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -9496,68 +9727,1068 @@ PublishPositionVelocityNedResponse::PublishPositionVelocityNedResponse( arena, *from._impl_.telemetry_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishPositionVelocityNedResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishStatusTextResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishPositionVelocityNedResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishStatusTextResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_server_result_ = {}; } -PublishPositionVelocityNedResponse::~PublishPositionVelocityNedResponse() { +PublishStatusTextResponse::~PublishStatusTextResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + SharedDtor(*this); +} +inline void PublishStatusTextResponse::SharedDtor(MessageLite& self) { + PublishStatusTextResponse& this_ = static_cast(self); + this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + ABSL_DCHECK(this_.GetArena() == nullptr); + delete this_._impl_.telemetry_server_result_; + this_._impl_.~Impl_(); +} + +inline void* PublishStatusTextResponse::PlacementNew_(const void*, void* mem, + ::google::protobuf::Arena* arena) { + return ::new (mem) PublishStatusTextResponse(arena); +} +constexpr auto PublishStatusTextResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishStatusTextResponse), + alignof(PublishStatusTextResponse)); +} +PROTOBUF_CONSTINIT +PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::google::protobuf::internal::ClassDataFull PublishStatusTextResponse::_class_data_ = { + ::google::protobuf::internal::ClassData{ + &_PublishStatusTextResponse_default_instance_._instance, + &_table_.header, + nullptr, // OnDemandRegisterArenaDtor + nullptr, // IsInitialized + &PublishStatusTextResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), +#if defined(PROTOBUF_CUSTOM_VTABLE) + &PublishStatusTextResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishStatusTextResponse::ByteSizeLong, + &PublishStatusTextResponse::_InternalSerialize, +#endif // PROTOBUF_CUSTOM_VTABLE + PROTOBUF_FIELD_OFFSET(PublishStatusTextResponse, _impl_._cached_size_), + false, + }, + &PublishStatusTextResponse::kDescriptorMethods, + &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, + nullptr, // tracker +}; +const ::google::protobuf::internal::ClassData* PublishStatusTextResponse::GetClassData() const { + ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); + ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); + return _class_data_.base(); +} +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishStatusTextResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(PublishStatusTextResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + _class_data_.base(), + nullptr, // post_loop_handler + ::_pbi::TcParser::GenericFallback, // fallback + #ifdef PROTOBUF_PREFETCH_PARSE_TABLE + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishStatusTextResponse>(), // to_prefetch + #endif // PROTOBUF_PREFETCH_PARSE_TABLE + }, {{ + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishStatusTextResponse, _impl_.telemetry_server_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + {PROTOBUF_FIELD_OFFSET(PublishStatusTextResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, + }}, {{ + }}, +}; + +PROTOBUF_NOINLINE void PublishStatusTextResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + ::google::protobuf::internal::TSanWrite(&_impl_); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.telemetry_server_result_ != nullptr); + _impl_.telemetry_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +#if defined(PROTOBUF_CUSTOM_VTABLE) + ::uint8_t* PublishStatusTextResponse::_InternalSerialize( + const MessageLite& base, ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) { + const PublishStatusTextResponse& this_ = static_cast(base); +#else // PROTOBUF_CUSTOM_VTABLE + ::uint8_t* PublishStatusTextResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + const PublishStatusTextResponse& this_ = *this; +#endif // PROTOBUF_CUSTOM_VTABLE + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = this_._impl_._has_bits_[0]; + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, *this_._impl_.telemetry_server_result_, this_._impl_.telemetry_server_result_->GetCachedSize(), target, + stream); + } + + if (PROTOBUF_PREDICT_FALSE(this_._internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + return target; + } + +#if defined(PROTOBUF_CUSTOM_VTABLE) + ::size_t PublishStatusTextResponse::ByteSizeLong(const MessageLite& base) { + const PublishStatusTextResponse& this_ = static_cast(base); +#else // PROTOBUF_CUSTOM_VTABLE + ::size_t PublishStatusTextResponse::ByteSizeLong() const { + const PublishStatusTextResponse& this_ = *this; +#endif // PROTOBUF_CUSTOM_VTABLE + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void)cached_has_bits; + + { + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + cached_has_bits = this_._impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize(*this_._impl_.telemetry_server_result_); + } + } + return this_.MaybeComputeUnknownFieldsSize(total_size, + &this_._impl_._cached_size_); + } + +void PublishStatusTextResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + ::google::protobuf::Arena* arena = _this->GetArena(); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = from._impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(from._impl_.telemetry_server_result_ != nullptr); + if (_this->_impl_.telemetry_server_result_ == nullptr) { + _this->_impl_.telemetry_server_result_ = + ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::TelemetryServerResult>(arena, *from._impl_.telemetry_server_result_); + } else { + _this->_impl_.telemetry_server_result_->MergeFrom(*from._impl_.telemetry_server_result_); + } + } + _this->_impl_._has_bits_[0] |= cached_has_bits; + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void PublishStatusTextResponse::CopyFrom(const PublishStatusTextResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + + +void PublishStatusTextResponse::InternalSwap(PublishStatusTextResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); +} + +::google::protobuf::Metadata PublishStatusTextResponse::GetMetadata() const { + return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); +} +// =================================================================== + +class PublishOdometryResponse::_Internal { + public: + using HasBits = + decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(PublishOdometryResponse, _impl_._has_bits_); +}; + +PublishOdometryResponse::PublishOdometryResponse(::google::protobuf::Arena* arena) +#if defined(PROTOBUF_CUSTOM_VTABLE) + : ::google::protobuf::Message(arena, _class_data_.base()) { +#else // PROTOBUF_CUSTOM_VTABLE + : ::google::protobuf::Message(arena) { +#endif // PROTOBUF_CUSTOM_VTABLE + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishOdometryResponse) +} +inline PROTOBUF_NDEBUG_INLINE PublishOdometryResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishOdometryResponse& from_msg) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +PublishOdometryResponse::PublishOdometryResponse( + ::google::protobuf::Arena* arena, + const PublishOdometryResponse& from) +#if defined(PROTOBUF_CUSTOM_VTABLE) + : ::google::protobuf::Message(arena, _class_data_.base()) { +#else // PROTOBUF_CUSTOM_VTABLE + : ::google::protobuf::Message(arena) { +#endif // PROTOBUF_CUSTOM_VTABLE + PublishOdometryResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_, from); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.telemetry_server_result_ = (cached_has_bits & 0x00000001u) ? ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::TelemetryServerResult>( + arena, *from._impl_.telemetry_server_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishOdometryResponse) +} +inline PROTOBUF_NDEBUG_INLINE PublishOdometryResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void PublishOdometryResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.telemetry_server_result_ = {}; +} +PublishOdometryResponse::~PublishOdometryResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishOdometryResponse) + SharedDtor(*this); +} +inline void PublishOdometryResponse::SharedDtor(MessageLite& self) { + PublishOdometryResponse& this_ = static_cast(self); + this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + ABSL_DCHECK(this_.GetArena() == nullptr); + delete this_._impl_.telemetry_server_result_; + this_._impl_.~Impl_(); +} + +inline void* PublishOdometryResponse::PlacementNew_(const void*, void* mem, + ::google::protobuf::Arena* arena) { + return ::new (mem) PublishOdometryResponse(arena); +} +constexpr auto PublishOdometryResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishOdometryResponse), + alignof(PublishOdometryResponse)); +} +PROTOBUF_CONSTINIT +PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::google::protobuf::internal::ClassDataFull PublishOdometryResponse::_class_data_ = { + ::google::protobuf::internal::ClassData{ + &_PublishOdometryResponse_default_instance_._instance, + &_table_.header, + nullptr, // OnDemandRegisterArenaDtor + nullptr, // IsInitialized + &PublishOdometryResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), +#if defined(PROTOBUF_CUSTOM_VTABLE) + &PublishOdometryResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishOdometryResponse::ByteSizeLong, + &PublishOdometryResponse::_InternalSerialize, +#endif // PROTOBUF_CUSTOM_VTABLE + PROTOBUF_FIELD_OFFSET(PublishOdometryResponse, _impl_._cached_size_), + false, + }, + &PublishOdometryResponse::kDescriptorMethods, + &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, + nullptr, // tracker +}; +const ::google::protobuf::internal::ClassData* PublishOdometryResponse::GetClassData() const { + ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); + ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); + return _class_data_.base(); +} +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishOdometryResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(PublishOdometryResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + _class_data_.base(), + nullptr, // post_loop_handler + ::_pbi::TcParser::GenericFallback, // fallback + #ifdef PROTOBUF_PREFETCH_PARSE_TABLE + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishOdometryResponse>(), // to_prefetch + #endif // PROTOBUF_PREFETCH_PARSE_TABLE + }, {{ + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishOdometryResponse, _impl_.telemetry_server_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + {PROTOBUF_FIELD_OFFSET(PublishOdometryResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, + }}, {{ + }}, +}; + +PROTOBUF_NOINLINE void PublishOdometryResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishOdometryResponse) + ::google::protobuf::internal::TSanWrite(&_impl_); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.telemetry_server_result_ != nullptr); + _impl_.telemetry_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +#if defined(PROTOBUF_CUSTOM_VTABLE) + ::uint8_t* PublishOdometryResponse::_InternalSerialize( + const MessageLite& base, ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) { + const PublishOdometryResponse& this_ = static_cast(base); +#else // PROTOBUF_CUSTOM_VTABLE + ::uint8_t* PublishOdometryResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + const PublishOdometryResponse& this_ = *this; +#endif // PROTOBUF_CUSTOM_VTABLE + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishOdometryResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = this_._impl_._has_bits_[0]; + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, *this_._impl_.telemetry_server_result_, this_._impl_.telemetry_server_result_->GetCachedSize(), target, + stream); + } + + if (PROTOBUF_PREDICT_FALSE(this_._internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishOdometryResponse) + return target; + } + +#if defined(PROTOBUF_CUSTOM_VTABLE) + ::size_t PublishOdometryResponse::ByteSizeLong(const MessageLite& base) { + const PublishOdometryResponse& this_ = static_cast(base); +#else // PROTOBUF_CUSTOM_VTABLE + ::size_t PublishOdometryResponse::ByteSizeLong() const { + const PublishOdometryResponse& this_ = *this; +#endif // PROTOBUF_CUSTOM_VTABLE + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishOdometryResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void)cached_has_bits; + + { + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + cached_has_bits = this_._impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize(*this_._impl_.telemetry_server_result_); + } + } + return this_.MaybeComputeUnknownFieldsSize(total_size, + &this_._impl_._cached_size_); + } + +void PublishOdometryResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + ::google::protobuf::Arena* arena = _this->GetArena(); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishOdometryResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = from._impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(from._impl_.telemetry_server_result_ != nullptr); + if (_this->_impl_.telemetry_server_result_ == nullptr) { + _this->_impl_.telemetry_server_result_ = + ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::TelemetryServerResult>(arena, *from._impl_.telemetry_server_result_); + } else { + _this->_impl_.telemetry_server_result_->MergeFrom(*from._impl_.telemetry_server_result_); + } + } + _this->_impl_._has_bits_[0] |= cached_has_bits; + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void PublishOdometryResponse::CopyFrom(const PublishOdometryResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishOdometryResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + + +void PublishOdometryResponse::InternalSwap(PublishOdometryResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); +} + +::google::protobuf::Metadata PublishOdometryResponse::GetMetadata() const { + return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); +} +// =================================================================== + +class PublishPositionVelocityNedResponse::_Internal { + public: + using HasBits = + decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(PublishPositionVelocityNedResponse, _impl_._has_bits_); +}; + +PublishPositionVelocityNedResponse::PublishPositionVelocityNedResponse(::google::protobuf::Arena* arena) +#if defined(PROTOBUF_CUSTOM_VTABLE) + : ::google::protobuf::Message(arena, _class_data_.base()) { +#else // PROTOBUF_CUSTOM_VTABLE + : ::google::protobuf::Message(arena) { +#endif // PROTOBUF_CUSTOM_VTABLE + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) +} +inline PROTOBUF_NDEBUG_INLINE PublishPositionVelocityNedResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishPositionVelocityNedResponse& from_msg) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +PublishPositionVelocityNedResponse::PublishPositionVelocityNedResponse( + ::google::protobuf::Arena* arena, + const PublishPositionVelocityNedResponse& from) +#if defined(PROTOBUF_CUSTOM_VTABLE) + : ::google::protobuf::Message(arena, _class_data_.base()) { +#else // PROTOBUF_CUSTOM_VTABLE + : ::google::protobuf::Message(arena) { +#endif // PROTOBUF_CUSTOM_VTABLE + PublishPositionVelocityNedResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_, from); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.telemetry_server_result_ = (cached_has_bits & 0x00000001u) ? ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::TelemetryServerResult>( + arena, *from._impl_.telemetry_server_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) +} +inline PROTOBUF_NDEBUG_INLINE PublishPositionVelocityNedResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void PublishPositionVelocityNedResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.telemetry_server_result_ = {}; +} +PublishPositionVelocityNedResponse::~PublishPositionVelocityNedResponse() { // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) SharedDtor(*this); } -inline void PublishPositionVelocityNedResponse::SharedDtor(MessageLite& self) { - PublishPositionVelocityNedResponse& this_ = static_cast(self); +inline void PublishPositionVelocityNedResponse::SharedDtor(MessageLite& self) { + PublishPositionVelocityNedResponse& this_ = static_cast(self); + this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + ABSL_DCHECK(this_.GetArena() == nullptr); + delete this_._impl_.telemetry_server_result_; + this_._impl_.~Impl_(); +} + +inline void* PublishPositionVelocityNedResponse::PlacementNew_(const void*, void* mem, + ::google::protobuf::Arena* arena) { + return ::new (mem) PublishPositionVelocityNedResponse(arena); +} +constexpr auto PublishPositionVelocityNedResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishPositionVelocityNedResponse), + alignof(PublishPositionVelocityNedResponse)); +} +PROTOBUF_CONSTINIT +PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::google::protobuf::internal::ClassDataFull PublishPositionVelocityNedResponse::_class_data_ = { + ::google::protobuf::internal::ClassData{ + &_PublishPositionVelocityNedResponse_default_instance_._instance, + &_table_.header, + nullptr, // OnDemandRegisterArenaDtor + nullptr, // IsInitialized + &PublishPositionVelocityNedResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), +#if defined(PROTOBUF_CUSTOM_VTABLE) + &PublishPositionVelocityNedResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishPositionVelocityNedResponse::ByteSizeLong, + &PublishPositionVelocityNedResponse::_InternalSerialize, +#endif // PROTOBUF_CUSTOM_VTABLE + PROTOBUF_FIELD_OFFSET(PublishPositionVelocityNedResponse, _impl_._cached_size_), + false, + }, + &PublishPositionVelocityNedResponse::kDescriptorMethods, + &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, + nullptr, // tracker +}; +const ::google::protobuf::internal::ClassData* PublishPositionVelocityNedResponse::GetClassData() const { + ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); + ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); + return _class_data_.base(); +} +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishPositionVelocityNedResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(PublishPositionVelocityNedResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + _class_data_.base(), + nullptr, // post_loop_handler + ::_pbi::TcParser::GenericFallback, // fallback + #ifdef PROTOBUF_PREFETCH_PARSE_TABLE + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishPositionVelocityNedResponse>(), // to_prefetch + #endif // PROTOBUF_PREFETCH_PARSE_TABLE + }, {{ + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishPositionVelocityNedResponse, _impl_.telemetry_server_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + {PROTOBUF_FIELD_OFFSET(PublishPositionVelocityNedResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, + }}, {{ + }}, +}; + +PROTOBUF_NOINLINE void PublishPositionVelocityNedResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) + ::google::protobuf::internal::TSanWrite(&_impl_); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.telemetry_server_result_ != nullptr); + _impl_.telemetry_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +#if defined(PROTOBUF_CUSTOM_VTABLE) + ::uint8_t* PublishPositionVelocityNedResponse::_InternalSerialize( + const MessageLite& base, ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) { + const PublishPositionVelocityNedResponse& this_ = static_cast(base); +#else // PROTOBUF_CUSTOM_VTABLE + ::uint8_t* PublishPositionVelocityNedResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + const PublishPositionVelocityNedResponse& this_ = *this; +#endif // PROTOBUF_CUSTOM_VTABLE + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = this_._impl_._has_bits_[0]; + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, *this_._impl_.telemetry_server_result_, this_._impl_.telemetry_server_result_->GetCachedSize(), target, + stream); + } + + if (PROTOBUF_PREDICT_FALSE(this_._internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) + return target; + } + +#if defined(PROTOBUF_CUSTOM_VTABLE) + ::size_t PublishPositionVelocityNedResponse::ByteSizeLong(const MessageLite& base) { + const PublishPositionVelocityNedResponse& this_ = static_cast(base); +#else // PROTOBUF_CUSTOM_VTABLE + ::size_t PublishPositionVelocityNedResponse::ByteSizeLong() const { + const PublishPositionVelocityNedResponse& this_ = *this; +#endif // PROTOBUF_CUSTOM_VTABLE + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void)cached_has_bits; + + { + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + cached_has_bits = this_._impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize(*this_._impl_.telemetry_server_result_); + } + } + return this_.MaybeComputeUnknownFieldsSize(total_size, + &this_._impl_._cached_size_); + } + +void PublishPositionVelocityNedResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + ::google::protobuf::Arena* arena = _this->GetArena(); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = from._impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(from._impl_.telemetry_server_result_ != nullptr); + if (_this->_impl_.telemetry_server_result_ == nullptr) { + _this->_impl_.telemetry_server_result_ = + ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::TelemetryServerResult>(arena, *from._impl_.telemetry_server_result_); + } else { + _this->_impl_.telemetry_server_result_->MergeFrom(*from._impl_.telemetry_server_result_); + } + } + _this->_impl_._has_bits_[0] |= cached_has_bits; + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void PublishPositionVelocityNedResponse::CopyFrom(const PublishPositionVelocityNedResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + + +void PublishPositionVelocityNedResponse::InternalSwap(PublishPositionVelocityNedResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); +} + +::google::protobuf::Metadata PublishPositionVelocityNedResponse::GetMetadata() const { + return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); +} +// =================================================================== + +class PublishGroundTruthResponse::_Internal { + public: + using HasBits = + decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(PublishGroundTruthResponse, _impl_._has_bits_); +}; + +PublishGroundTruthResponse::PublishGroundTruthResponse(::google::protobuf::Arena* arena) +#if defined(PROTOBUF_CUSTOM_VTABLE) + : ::google::protobuf::Message(arena, _class_data_.base()) { +#else // PROTOBUF_CUSTOM_VTABLE + : ::google::protobuf::Message(arena) { +#endif // PROTOBUF_CUSTOM_VTABLE + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) +} +inline PROTOBUF_NDEBUG_INLINE PublishGroundTruthResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishGroundTruthResponse& from_msg) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +PublishGroundTruthResponse::PublishGroundTruthResponse( + ::google::protobuf::Arena* arena, + const PublishGroundTruthResponse& from) +#if defined(PROTOBUF_CUSTOM_VTABLE) + : ::google::protobuf::Message(arena, _class_data_.base()) { +#else // PROTOBUF_CUSTOM_VTABLE + : ::google::protobuf::Message(arena) { +#endif // PROTOBUF_CUSTOM_VTABLE + PublishGroundTruthResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_, from); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.telemetry_server_result_ = (cached_has_bits & 0x00000001u) ? ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::TelemetryServerResult>( + arena, *from._impl_.telemetry_server_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) +} +inline PROTOBUF_NDEBUG_INLINE PublishGroundTruthResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void PublishGroundTruthResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.telemetry_server_result_ = {}; +} +PublishGroundTruthResponse::~PublishGroundTruthResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) + SharedDtor(*this); +} +inline void PublishGroundTruthResponse::SharedDtor(MessageLite& self) { + PublishGroundTruthResponse& this_ = static_cast(self); + this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + ABSL_DCHECK(this_.GetArena() == nullptr); + delete this_._impl_.telemetry_server_result_; + this_._impl_.~Impl_(); +} + +inline void* PublishGroundTruthResponse::PlacementNew_(const void*, void* mem, + ::google::protobuf::Arena* arena) { + return ::new (mem) PublishGroundTruthResponse(arena); +} +constexpr auto PublishGroundTruthResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishGroundTruthResponse), + alignof(PublishGroundTruthResponse)); +} +PROTOBUF_CONSTINIT +PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::google::protobuf::internal::ClassDataFull PublishGroundTruthResponse::_class_data_ = { + ::google::protobuf::internal::ClassData{ + &_PublishGroundTruthResponse_default_instance_._instance, + &_table_.header, + nullptr, // OnDemandRegisterArenaDtor + nullptr, // IsInitialized + &PublishGroundTruthResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), +#if defined(PROTOBUF_CUSTOM_VTABLE) + &PublishGroundTruthResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishGroundTruthResponse::ByteSizeLong, + &PublishGroundTruthResponse::_InternalSerialize, +#endif // PROTOBUF_CUSTOM_VTABLE + PROTOBUF_FIELD_OFFSET(PublishGroundTruthResponse, _impl_._cached_size_), + false, + }, + &PublishGroundTruthResponse::kDescriptorMethods, + &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, + nullptr, // tracker +}; +const ::google::protobuf::internal::ClassData* PublishGroundTruthResponse::GetClassData() const { + ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); + ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); + return _class_data_.base(); +} +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishGroundTruthResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(PublishGroundTruthResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + _class_data_.base(), + nullptr, // post_loop_handler + ::_pbi::TcParser::GenericFallback, // fallback + #ifdef PROTOBUF_PREFETCH_PARSE_TABLE + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishGroundTruthResponse>(), // to_prefetch + #endif // PROTOBUF_PREFETCH_PARSE_TABLE + }, {{ + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishGroundTruthResponse, _impl_.telemetry_server_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + {PROTOBUF_FIELD_OFFSET(PublishGroundTruthResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, + }}, {{ + }}, +}; + +PROTOBUF_NOINLINE void PublishGroundTruthResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) + ::google::protobuf::internal::TSanWrite(&_impl_); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.telemetry_server_result_ != nullptr); + _impl_.telemetry_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +#if defined(PROTOBUF_CUSTOM_VTABLE) + ::uint8_t* PublishGroundTruthResponse::_InternalSerialize( + const MessageLite& base, ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) { + const PublishGroundTruthResponse& this_ = static_cast(base); +#else // PROTOBUF_CUSTOM_VTABLE + ::uint8_t* PublishGroundTruthResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + const PublishGroundTruthResponse& this_ = *this; +#endif // PROTOBUF_CUSTOM_VTABLE + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = this_._impl_._has_bits_[0]; + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, *this_._impl_.telemetry_server_result_, this_._impl_.telemetry_server_result_->GetCachedSize(), target, + stream); + } + + if (PROTOBUF_PREDICT_FALSE(this_._internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) + return target; + } + +#if defined(PROTOBUF_CUSTOM_VTABLE) + ::size_t PublishGroundTruthResponse::ByteSizeLong(const MessageLite& base) { + const PublishGroundTruthResponse& this_ = static_cast(base); +#else // PROTOBUF_CUSTOM_VTABLE + ::size_t PublishGroundTruthResponse::ByteSizeLong() const { + const PublishGroundTruthResponse& this_ = *this; +#endif // PROTOBUF_CUSTOM_VTABLE + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void)cached_has_bits; + + { + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + cached_has_bits = this_._impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize(*this_._impl_.telemetry_server_result_); + } + } + return this_.MaybeComputeUnknownFieldsSize(total_size, + &this_._impl_._cached_size_); + } + +void PublishGroundTruthResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + ::google::protobuf::Arena* arena = _this->GetArena(); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = from._impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(from._impl_.telemetry_server_result_ != nullptr); + if (_this->_impl_.telemetry_server_result_ == nullptr) { + _this->_impl_.telemetry_server_result_ = + ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::TelemetryServerResult>(arena, *from._impl_.telemetry_server_result_); + } else { + _this->_impl_.telemetry_server_result_->MergeFrom(*from._impl_.telemetry_server_result_); + } + } + _this->_impl_._has_bits_[0] |= cached_has_bits; + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void PublishGroundTruthResponse::CopyFrom(const PublishGroundTruthResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + + +void PublishGroundTruthResponse::InternalSwap(PublishGroundTruthResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); +} + +::google::protobuf::Metadata PublishGroundTruthResponse::GetMetadata() const { + return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); +} +// =================================================================== + +class PublishImuResponse::_Internal { + public: + using HasBits = + decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(PublishImuResponse, _impl_._has_bits_); +}; + +PublishImuResponse::PublishImuResponse(::google::protobuf::Arena* arena) +#if defined(PROTOBUF_CUSTOM_VTABLE) + : ::google::protobuf::Message(arena, _class_data_.base()) { +#else // PROTOBUF_CUSTOM_VTABLE + : ::google::protobuf::Message(arena) { +#endif // PROTOBUF_CUSTOM_VTABLE + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishImuResponse) +} +inline PROTOBUF_NDEBUG_INLINE PublishImuResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishImuResponse& from_msg) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +PublishImuResponse::PublishImuResponse( + ::google::protobuf::Arena* arena, + const PublishImuResponse& from) +#if defined(PROTOBUF_CUSTOM_VTABLE) + : ::google::protobuf::Message(arena, _class_data_.base()) { +#else // PROTOBUF_CUSTOM_VTABLE + : ::google::protobuf::Message(arena) { +#endif // PROTOBUF_CUSTOM_VTABLE + PublishImuResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_, from); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.telemetry_server_result_ = (cached_has_bits & 0x00000001u) ? ::google::protobuf::Message::CopyConstruct<::mavsdk::rpc::telemetry_server::TelemetryServerResult>( + arena, *from._impl_.telemetry_server_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishImuResponse) +} +inline PROTOBUF_NDEBUG_INLINE PublishImuResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void PublishImuResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.telemetry_server_result_ = {}; +} +PublishImuResponse::~PublishImuResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishImuResponse) + SharedDtor(*this); +} +inline void PublishImuResponse::SharedDtor(MessageLite& self) { + PublishImuResponse& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); delete this_._impl_.telemetry_server_result_; this_._impl_.~Impl_(); } -inline void* PublishPositionVelocityNedResponse::PlacementNew_(const void*, void* mem, +inline void* PublishImuResponse::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishPositionVelocityNedResponse(arena); + return ::new (mem) PublishImuResponse(arena); } -constexpr auto PublishPositionVelocityNedResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishPositionVelocityNedResponse), - alignof(PublishPositionVelocityNedResponse)); +constexpr auto PublishImuResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishImuResponse), + alignof(PublishImuResponse)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishPositionVelocityNedResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishImuResponse::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishPositionVelocityNedResponse_default_instance_._instance, + &_PublishImuResponse_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishPositionVelocityNedResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishImuResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishPositionVelocityNedResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishPositionVelocityNedResponse::ByteSizeLong, - &PublishPositionVelocityNedResponse::_InternalSerialize, + &PublishImuResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishImuResponse::ByteSizeLong, + &PublishImuResponse::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishPositionVelocityNedResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishImuResponse, _impl_._cached_size_), false, }, - &PublishPositionVelocityNedResponse::kDescriptorMethods, + &PublishImuResponse::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishPositionVelocityNedResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishImuResponse::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishPositionVelocityNedResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishImuResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishPositionVelocityNedResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishImuResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -9570,17 +10801,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishPositionVelocityNedResponse::_t nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishPositionVelocityNedResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishImuResponse>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishPositionVelocityNedResponse, _impl_.telemetry_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishImuResponse, _impl_.telemetry_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishPositionVelocityNedResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(PublishImuResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, @@ -9588,8 +10819,8 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishPositionVelocityNedResponse::_t }}, }; -PROTOBUF_NOINLINE void PublishPositionVelocityNedResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) +PROTOBUF_NOINLINE void PublishImuResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishImuResponse) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -9605,17 +10836,17 @@ PROTOBUF_NOINLINE void PublishPositionVelocityNedResponse::Clear() { } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishPositionVelocityNedResponse::_InternalSerialize( + ::uint8_t* PublishImuResponse::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishPositionVelocityNedResponse& this_ = static_cast(base); + const PublishImuResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishPositionVelocityNedResponse::_InternalSerialize( + ::uint8_t* PublishImuResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishPositionVelocityNedResponse& this_ = *this; + const PublishImuResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishImuResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -9632,18 +10863,18 @@ PROTOBUF_NOINLINE void PublishPositionVelocityNedResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishImuResponse) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishPositionVelocityNedResponse::ByteSizeLong(const MessageLite& base) { - const PublishPositionVelocityNedResponse& this_ = static_cast(base); + ::size_t PublishImuResponse::ByteSizeLong(const MessageLite& base) { + const PublishImuResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishPositionVelocityNedResponse::ByteSizeLong() const { - const PublishPositionVelocityNedResponse& this_ = *this; + ::size_t PublishImuResponse::ByteSizeLong() const { + const PublishImuResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishImuResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -9662,11 +10893,11 @@ PROTOBUF_NOINLINE void PublishPositionVelocityNedResponse::Clear() { &this_._impl_._cached_size_); } -void PublishPositionVelocityNedResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishImuResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishImuResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -9685,58 +10916,58 @@ void PublishPositionVelocityNedResponse::MergeImpl(::google::protobuf::MessageLi _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishPositionVelocityNedResponse::CopyFrom(const PublishPositionVelocityNedResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) +void PublishImuResponse::CopyFrom(const PublishImuResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishImuResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishPositionVelocityNedResponse::InternalSwap(PublishPositionVelocityNedResponse* PROTOBUF_RESTRICT other) { +void PublishImuResponse::InternalSwap(PublishImuResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); } -::google::protobuf::Metadata PublishPositionVelocityNedResponse::GetMetadata() const { +::google::protobuf::Metadata PublishImuResponse::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== -class PublishGroundTruthResponse::_Internal { +class PublishScaledImuResponse::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishGroundTruthResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishScaledImuResponse, _impl_._has_bits_); }; -PublishGroundTruthResponse::PublishGroundTruthResponse(::google::protobuf::Arena* arena) +PublishScaledImuResponse::PublishScaledImuResponse(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishGroundTruthResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishScaledImuResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishGroundTruthResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishScaledImuResponse& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishGroundTruthResponse::PublishGroundTruthResponse( +PublishScaledImuResponse::PublishScaledImuResponse( ::google::protobuf::Arena* arena, - const PublishGroundTruthResponse& from) + const PublishScaledImuResponse& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishGroundTruthResponse* const _this = this; + PublishScaledImuResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -9746,68 +10977,68 @@ PublishGroundTruthResponse::PublishGroundTruthResponse( arena, *from._impl_.telemetry_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishGroundTruthResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishScaledImuResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishGroundTruthResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishScaledImuResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_server_result_ = {}; } -PublishGroundTruthResponse::~PublishGroundTruthResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) +PublishScaledImuResponse::~PublishScaledImuResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) SharedDtor(*this); } -inline void PublishGroundTruthResponse::SharedDtor(MessageLite& self) { - PublishGroundTruthResponse& this_ = static_cast(self); +inline void PublishScaledImuResponse::SharedDtor(MessageLite& self) { + PublishScaledImuResponse& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); delete this_._impl_.telemetry_server_result_; this_._impl_.~Impl_(); } -inline void* PublishGroundTruthResponse::PlacementNew_(const void*, void* mem, +inline void* PublishScaledImuResponse::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishGroundTruthResponse(arena); + return ::new (mem) PublishScaledImuResponse(arena); } -constexpr auto PublishGroundTruthResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishGroundTruthResponse), - alignof(PublishGroundTruthResponse)); +constexpr auto PublishScaledImuResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishScaledImuResponse), + alignof(PublishScaledImuResponse)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishGroundTruthResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishScaledImuResponse::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishGroundTruthResponse_default_instance_._instance, + &_PublishScaledImuResponse_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishGroundTruthResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishScaledImuResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishGroundTruthResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishGroundTruthResponse::ByteSizeLong, - &PublishGroundTruthResponse::_InternalSerialize, + &PublishScaledImuResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishScaledImuResponse::ByteSizeLong, + &PublishScaledImuResponse::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishGroundTruthResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishScaledImuResponse, _impl_._cached_size_), false, }, - &PublishGroundTruthResponse::kDescriptorMethods, + &PublishScaledImuResponse::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishGroundTruthResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishScaledImuResponse::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishGroundTruthResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishScaledImuResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishGroundTruthResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishScaledImuResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -9820,17 +11051,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishGroundTruthResponse::_table_ = nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishGroundTruthResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishScaledImuResponse>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishGroundTruthResponse, _impl_.telemetry_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishScaledImuResponse, _impl_.telemetry_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishGroundTruthResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(PublishScaledImuResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, @@ -9838,8 +11069,8 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishGroundTruthResponse::_table_ = }}, }; -PROTOBUF_NOINLINE void PublishGroundTruthResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) +PROTOBUF_NOINLINE void PublishScaledImuResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -9855,17 +11086,17 @@ PROTOBUF_NOINLINE void PublishGroundTruthResponse::Clear() { } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishGroundTruthResponse::_InternalSerialize( + ::uint8_t* PublishScaledImuResponse::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishGroundTruthResponse& this_ = static_cast(base); + const PublishScaledImuResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishGroundTruthResponse::_InternalSerialize( + ::uint8_t* PublishScaledImuResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishGroundTruthResponse& this_ = *this; + const PublishScaledImuResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -9882,18 +11113,18 @@ PROTOBUF_NOINLINE void PublishGroundTruthResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishGroundTruthResponse::ByteSizeLong(const MessageLite& base) { - const PublishGroundTruthResponse& this_ = static_cast(base); + ::size_t PublishScaledImuResponse::ByteSizeLong(const MessageLite& base) { + const PublishScaledImuResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishGroundTruthResponse::ByteSizeLong() const { - const PublishGroundTruthResponse& this_ = *this; + ::size_t PublishScaledImuResponse::ByteSizeLong() const { + const PublishScaledImuResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -9912,11 +11143,11 @@ PROTOBUF_NOINLINE void PublishGroundTruthResponse::Clear() { &this_._impl_._cached_size_); } -void PublishGroundTruthResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishScaledImuResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -9935,58 +11166,58 @@ void PublishGroundTruthResponse::MergeImpl(::google::protobuf::MessageLite& to_m _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishGroundTruthResponse::CopyFrom(const PublishGroundTruthResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) +void PublishScaledImuResponse::CopyFrom(const PublishScaledImuResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishGroundTruthResponse::InternalSwap(PublishGroundTruthResponse* PROTOBUF_RESTRICT other) { +void PublishScaledImuResponse::InternalSwap(PublishScaledImuResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); } -::google::protobuf::Metadata PublishGroundTruthResponse::GetMetadata() const { +::google::protobuf::Metadata PublishScaledImuResponse::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== -class PublishImuResponse::_Internal { +class PublishRawImuResponse::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishImuResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishRawImuResponse, _impl_._has_bits_); }; -PublishImuResponse::PublishImuResponse(::google::protobuf::Arena* arena) +PublishRawImuResponse::PublishRawImuResponse(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishImuResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishRawImuResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishImuResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishRawImuResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishImuResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishRawImuResponse& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishImuResponse::PublishImuResponse( +PublishRawImuResponse::PublishRawImuResponse( ::google::protobuf::Arena* arena, - const PublishImuResponse& from) + const PublishRawImuResponse& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishImuResponse* const _this = this; + PublishRawImuResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -9996,68 +11227,68 @@ PublishImuResponse::PublishImuResponse( arena, *from._impl_.telemetry_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishImuResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishRawImuResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishImuResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishRawImuResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishImuResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishRawImuResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_server_result_ = {}; } -PublishImuResponse::~PublishImuResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishImuResponse) +PublishRawImuResponse::~PublishRawImuResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishRawImuResponse) SharedDtor(*this); } -inline void PublishImuResponse::SharedDtor(MessageLite& self) { - PublishImuResponse& this_ = static_cast(self); +inline void PublishRawImuResponse::SharedDtor(MessageLite& self) { + PublishRawImuResponse& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); delete this_._impl_.telemetry_server_result_; this_._impl_.~Impl_(); } -inline void* PublishImuResponse::PlacementNew_(const void*, void* mem, +inline void* PublishRawImuResponse::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishImuResponse(arena); + return ::new (mem) PublishRawImuResponse(arena); } -constexpr auto PublishImuResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishImuResponse), - alignof(PublishImuResponse)); +constexpr auto PublishRawImuResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishRawImuResponse), + alignof(PublishRawImuResponse)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishImuResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishRawImuResponse::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishImuResponse_default_instance_._instance, + &_PublishRawImuResponse_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishImuResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishRawImuResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishImuResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishImuResponse::ByteSizeLong, - &PublishImuResponse::_InternalSerialize, + &PublishRawImuResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishRawImuResponse::ByteSizeLong, + &PublishRawImuResponse::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishImuResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishRawImuResponse, _impl_._cached_size_), false, }, - &PublishImuResponse::kDescriptorMethods, + &PublishRawImuResponse::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishImuResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishRawImuResponse::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishImuResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishRawImuResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishImuResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishRawImuResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -10070,17 +11301,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishImuResponse::_table_ = { nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishImuResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishRawImuResponse>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishImuResponse, _impl_.telemetry_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishRawImuResponse, _impl_.telemetry_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishImuResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(PublishRawImuResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, @@ -10088,8 +11319,8 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishImuResponse::_table_ = { }}, }; -PROTOBUF_NOINLINE void PublishImuResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishImuResponse) +PROTOBUF_NOINLINE void PublishRawImuResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishRawImuResponse) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -10105,17 +11336,17 @@ PROTOBUF_NOINLINE void PublishImuResponse::Clear() { } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishImuResponse::_InternalSerialize( + ::uint8_t* PublishRawImuResponse::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishImuResponse& this_ = static_cast(base); + const PublishRawImuResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishImuResponse::_InternalSerialize( + ::uint8_t* PublishRawImuResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishImuResponse& this_ = *this; + const PublishRawImuResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishImuResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishRawImuResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -10132,18 +11363,18 @@ PROTOBUF_NOINLINE void PublishImuResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishImuResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishRawImuResponse) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishImuResponse::ByteSizeLong(const MessageLite& base) { - const PublishImuResponse& this_ = static_cast(base); + ::size_t PublishRawImuResponse::ByteSizeLong(const MessageLite& base) { + const PublishRawImuResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishImuResponse::ByteSizeLong() const { - const PublishImuResponse& this_ = *this; + ::size_t PublishRawImuResponse::ByteSizeLong() const { + const PublishRawImuResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishImuResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishRawImuResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -10162,11 +11393,11 @@ PROTOBUF_NOINLINE void PublishImuResponse::Clear() { &this_._impl_._cached_size_); } -void PublishImuResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishRawImuResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishImuResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishRawImuResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -10185,58 +11416,58 @@ void PublishImuResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, cons _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishImuResponse::CopyFrom(const PublishImuResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishImuResponse) +void PublishRawImuResponse::CopyFrom(const PublishRawImuResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishRawImuResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishImuResponse::InternalSwap(PublishImuResponse* PROTOBUF_RESTRICT other) { +void PublishRawImuResponse::InternalSwap(PublishRawImuResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); } -::google::protobuf::Metadata PublishImuResponse::GetMetadata() const { +::google::protobuf::Metadata PublishRawImuResponse::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== -class PublishScaledImuResponse::_Internal { +class PublishUnixEpochTimeResponse::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishScaledImuResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishUnixEpochTimeResponse, _impl_._has_bits_); }; -PublishScaledImuResponse::PublishScaledImuResponse(::google::protobuf::Arena* arena) +PublishUnixEpochTimeResponse::PublishUnixEpochTimeResponse(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishScaledImuResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishUnixEpochTimeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishScaledImuResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeResponse& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishScaledImuResponse::PublishScaledImuResponse( +PublishUnixEpochTimeResponse::PublishUnixEpochTimeResponse( ::google::protobuf::Arena* arena, - const PublishScaledImuResponse& from) + const PublishUnixEpochTimeResponse& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishScaledImuResponse* const _this = this; + PublishUnixEpochTimeResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -10246,68 +11477,68 @@ PublishScaledImuResponse::PublishScaledImuResponse( arena, *from._impl_.telemetry_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishScaledImuResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishUnixEpochTimeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishScaledImuResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishUnixEpochTimeResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_server_result_ = {}; } -PublishScaledImuResponse::~PublishScaledImuResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) +PublishUnixEpochTimeResponse::~PublishUnixEpochTimeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) SharedDtor(*this); } -inline void PublishScaledImuResponse::SharedDtor(MessageLite& self) { - PublishScaledImuResponse& this_ = static_cast(self); +inline void PublishUnixEpochTimeResponse::SharedDtor(MessageLite& self) { + PublishUnixEpochTimeResponse& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); delete this_._impl_.telemetry_server_result_; this_._impl_.~Impl_(); } -inline void* PublishScaledImuResponse::PlacementNew_(const void*, void* mem, +inline void* PublishUnixEpochTimeResponse::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishScaledImuResponse(arena); + return ::new (mem) PublishUnixEpochTimeResponse(arena); } -constexpr auto PublishScaledImuResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishScaledImuResponse), - alignof(PublishScaledImuResponse)); +constexpr auto PublishUnixEpochTimeResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishUnixEpochTimeResponse), + alignof(PublishUnixEpochTimeResponse)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishScaledImuResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishUnixEpochTimeResponse::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishScaledImuResponse_default_instance_._instance, + &_PublishUnixEpochTimeResponse_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishScaledImuResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishUnixEpochTimeResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishScaledImuResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishScaledImuResponse::ByteSizeLong, - &PublishScaledImuResponse::_InternalSerialize, + &PublishUnixEpochTimeResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishUnixEpochTimeResponse::ByteSizeLong, + &PublishUnixEpochTimeResponse::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishScaledImuResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishUnixEpochTimeResponse, _impl_._cached_size_), false, }, - &PublishScaledImuResponse::kDescriptorMethods, + &PublishUnixEpochTimeResponse::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishScaledImuResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishUnixEpochTimeResponse::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishScaledImuResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishUnixEpochTimeResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishScaledImuResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishUnixEpochTimeResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -10320,17 +11551,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishScaledImuResponse::_table_ = { nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishScaledImuResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeResponse>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishScaledImuResponse, _impl_.telemetry_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishUnixEpochTimeResponse, _impl_.telemetry_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishScaledImuResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(PublishUnixEpochTimeResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, @@ -10338,8 +11569,8 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishScaledImuResponse::_table_ = { }}, }; -PROTOBUF_NOINLINE void PublishScaledImuResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) +PROTOBUF_NOINLINE void PublishUnixEpochTimeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -10355,17 +11586,17 @@ PROTOBUF_NOINLINE void PublishScaledImuResponse::Clear() { } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishScaledImuResponse::_InternalSerialize( + ::uint8_t* PublishUnixEpochTimeResponse::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishScaledImuResponse& this_ = static_cast(base); + const PublishUnixEpochTimeResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishScaledImuResponse::_InternalSerialize( + ::uint8_t* PublishUnixEpochTimeResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishScaledImuResponse& this_ = *this; + const PublishUnixEpochTimeResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -10382,18 +11613,18 @@ PROTOBUF_NOINLINE void PublishScaledImuResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishScaledImuResponse::ByteSizeLong(const MessageLite& base) { - const PublishScaledImuResponse& this_ = static_cast(base); + ::size_t PublishUnixEpochTimeResponse::ByteSizeLong(const MessageLite& base) { + const PublishUnixEpochTimeResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishScaledImuResponse::ByteSizeLong() const { - const PublishScaledImuResponse& this_ = *this; + ::size_t PublishUnixEpochTimeResponse::ByteSizeLong() const { + const PublishUnixEpochTimeResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -10412,11 +11643,11 @@ PROTOBUF_NOINLINE void PublishScaledImuResponse::Clear() { &this_._impl_._cached_size_); } -void PublishScaledImuResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishUnixEpochTimeResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -10435,58 +11666,58 @@ void PublishScaledImuResponse::MergeImpl(::google::protobuf::MessageLite& to_msg _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishScaledImuResponse::CopyFrom(const PublishScaledImuResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) +void PublishUnixEpochTimeResponse::CopyFrom(const PublishUnixEpochTimeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishScaledImuResponse::InternalSwap(PublishScaledImuResponse* PROTOBUF_RESTRICT other) { +void PublishUnixEpochTimeResponse::InternalSwap(PublishUnixEpochTimeResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); } -::google::protobuf::Metadata PublishScaledImuResponse::GetMetadata() const { +::google::protobuf::Metadata PublishUnixEpochTimeResponse::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== -class PublishRawImuResponse::_Internal { +class PublishDistanceSensorResponse::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishRawImuResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishDistanceSensorResponse, _impl_._has_bits_); }; -PublishRawImuResponse::PublishRawImuResponse(::google::protobuf::Arena* arena) +PublishDistanceSensorResponse::PublishDistanceSensorResponse(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishRawImuResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishRawImuResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishDistanceSensorResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishRawImuResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishRawImuResponse::PublishRawImuResponse( +PublishDistanceSensorResponse::PublishDistanceSensorResponse( ::google::protobuf::Arena* arena, - const PublishRawImuResponse& from) + const PublishDistanceSensorResponse& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishRawImuResponse* const _this = this; + PublishDistanceSensorResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -10496,68 +11727,68 @@ PublishRawImuResponse::PublishRawImuResponse( arena, *from._impl_.telemetry_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishRawImuResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishRawImuResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishDistanceSensorResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishRawImuResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishDistanceSensorResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_server_result_ = {}; } -PublishRawImuResponse::~PublishRawImuResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishRawImuResponse) +PublishDistanceSensorResponse::~PublishDistanceSensorResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) SharedDtor(*this); } -inline void PublishRawImuResponse::SharedDtor(MessageLite& self) { - PublishRawImuResponse& this_ = static_cast(self); +inline void PublishDistanceSensorResponse::SharedDtor(MessageLite& self) { + PublishDistanceSensorResponse& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); delete this_._impl_.telemetry_server_result_; this_._impl_.~Impl_(); } -inline void* PublishRawImuResponse::PlacementNew_(const void*, void* mem, +inline void* PublishDistanceSensorResponse::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishRawImuResponse(arena); + return ::new (mem) PublishDistanceSensorResponse(arena); } -constexpr auto PublishRawImuResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishRawImuResponse), - alignof(PublishRawImuResponse)); +constexpr auto PublishDistanceSensorResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishDistanceSensorResponse), + alignof(PublishDistanceSensorResponse)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishRawImuResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishDistanceSensorResponse::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishRawImuResponse_default_instance_._instance, + &_PublishDistanceSensorResponse_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishRawImuResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishDistanceSensorResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishRawImuResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishRawImuResponse::ByteSizeLong, - &PublishRawImuResponse::_InternalSerialize, + &PublishDistanceSensorResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishDistanceSensorResponse::ByteSizeLong, + &PublishDistanceSensorResponse::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishRawImuResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishDistanceSensorResponse, _impl_._cached_size_), false, }, - &PublishRawImuResponse::kDescriptorMethods, + &PublishDistanceSensorResponse::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishRawImuResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishDistanceSensorResponse::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishRawImuResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishDistanceSensorResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishRawImuResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishDistanceSensorResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -10570,17 +11801,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishRawImuResponse::_table_ = { nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishRawImuResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishRawImuResponse, _impl_.telemetry_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishDistanceSensorResponse, _impl_.telemetry_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishRawImuResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(PublishDistanceSensorResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, @@ -10588,8 +11819,8 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishRawImuResponse::_table_ = { }}, }; -PROTOBUF_NOINLINE void PublishRawImuResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishRawImuResponse) +PROTOBUF_NOINLINE void PublishDistanceSensorResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -10605,17 +11836,17 @@ PROTOBUF_NOINLINE void PublishRawImuResponse::Clear() { } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishRawImuResponse::_InternalSerialize( + ::uint8_t* PublishDistanceSensorResponse::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishRawImuResponse& this_ = static_cast(base); + const PublishDistanceSensorResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishRawImuResponse::_InternalSerialize( + ::uint8_t* PublishDistanceSensorResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishRawImuResponse& this_ = *this; + const PublishDistanceSensorResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishRawImuResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -10632,18 +11863,18 @@ PROTOBUF_NOINLINE void PublishRawImuResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishRawImuResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishRawImuResponse::ByteSizeLong(const MessageLite& base) { - const PublishRawImuResponse& this_ = static_cast(base); + ::size_t PublishDistanceSensorResponse::ByteSizeLong(const MessageLite& base) { + const PublishDistanceSensorResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishRawImuResponse::ByteSizeLong() const { - const PublishRawImuResponse& this_ = *this; + ::size_t PublishDistanceSensorResponse::ByteSizeLong() const { + const PublishDistanceSensorResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishRawImuResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -10662,11 +11893,11 @@ PROTOBUF_NOINLINE void PublishRawImuResponse::Clear() { &this_._impl_._cached_size_); } -void PublishRawImuResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishDistanceSensorResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishRawImuResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -10685,58 +11916,58 @@ void PublishRawImuResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, c _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishRawImuResponse::CopyFrom(const PublishRawImuResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishRawImuResponse) +void PublishDistanceSensorResponse::CopyFrom(const PublishDistanceSensorResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishRawImuResponse::InternalSwap(PublishRawImuResponse* PROTOBUF_RESTRICT other) { +void PublishDistanceSensorResponse::InternalSwap(PublishDistanceSensorResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); } -::google::protobuf::Metadata PublishRawImuResponse::GetMetadata() const { +::google::protobuf::Metadata PublishDistanceSensorResponse::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== -class PublishUnixEpochTimeResponse::_Internal { +class PublishAttitudeResponse::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishUnixEpochTimeResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishAttitudeResponse, _impl_._has_bits_); }; -PublishUnixEpochTimeResponse::PublishUnixEpochTimeResponse(::google::protobuf::Arena* arena) +PublishAttitudeResponse::PublishAttitudeResponse(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishAttitudeResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishUnixEpochTimeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishAttitudeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishAttitudeResponse& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishUnixEpochTimeResponse::PublishUnixEpochTimeResponse( +PublishAttitudeResponse::PublishAttitudeResponse( ::google::protobuf::Arena* arena, - const PublishUnixEpochTimeResponse& from) + const PublishAttitudeResponse& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishUnixEpochTimeResponse* const _this = this; + PublishAttitudeResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -10746,68 +11977,68 @@ PublishUnixEpochTimeResponse::PublishUnixEpochTimeResponse( arena, *from._impl_.telemetry_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishAttitudeResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishUnixEpochTimeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishAttitudeResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishUnixEpochTimeResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishAttitudeResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_server_result_ = {}; } -PublishUnixEpochTimeResponse::~PublishUnixEpochTimeResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) +PublishAttitudeResponse::~PublishAttitudeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishAttitudeResponse) SharedDtor(*this); } -inline void PublishUnixEpochTimeResponse::SharedDtor(MessageLite& self) { - PublishUnixEpochTimeResponse& this_ = static_cast(self); +inline void PublishAttitudeResponse::SharedDtor(MessageLite& self) { + PublishAttitudeResponse& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); delete this_._impl_.telemetry_server_result_; this_._impl_.~Impl_(); } -inline void* PublishUnixEpochTimeResponse::PlacementNew_(const void*, void* mem, +inline void* PublishAttitudeResponse::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishUnixEpochTimeResponse(arena); + return ::new (mem) PublishAttitudeResponse(arena); } -constexpr auto PublishUnixEpochTimeResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishUnixEpochTimeResponse), - alignof(PublishUnixEpochTimeResponse)); +constexpr auto PublishAttitudeResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishAttitudeResponse), + alignof(PublishAttitudeResponse)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishUnixEpochTimeResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishAttitudeResponse::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishUnixEpochTimeResponse_default_instance_._instance, + &_PublishAttitudeResponse_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishUnixEpochTimeResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishAttitudeResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishUnixEpochTimeResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishUnixEpochTimeResponse::ByteSizeLong, - &PublishUnixEpochTimeResponse::_InternalSerialize, + &PublishAttitudeResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishAttitudeResponse::ByteSizeLong, + &PublishAttitudeResponse::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishUnixEpochTimeResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishAttitudeResponse, _impl_._cached_size_), false, }, - &PublishUnixEpochTimeResponse::kDescriptorMethods, + &PublishAttitudeResponse::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishUnixEpochTimeResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishAttitudeResponse::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishUnixEpochTimeResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishAttitudeResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishUnixEpochTimeResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishAttitudeResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -10820,17 +12051,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishUnixEpochTimeResponse::_table_ nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishUnixEpochTimeResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishAttitudeResponse>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishUnixEpochTimeResponse, _impl_.telemetry_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishAttitudeResponse, _impl_.telemetry_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishUnixEpochTimeResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(PublishAttitudeResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, @@ -10838,8 +12069,8 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishUnixEpochTimeResponse::_table_ }}, }; -PROTOBUF_NOINLINE void PublishUnixEpochTimeResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) +PROTOBUF_NOINLINE void PublishAttitudeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishAttitudeResponse) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -10855,17 +12086,17 @@ PROTOBUF_NOINLINE void PublishUnixEpochTimeResponse::Clear() { } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishUnixEpochTimeResponse::_InternalSerialize( + ::uint8_t* PublishAttitudeResponse::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishUnixEpochTimeResponse& this_ = static_cast(base); + const PublishAttitudeResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishUnixEpochTimeResponse::_InternalSerialize( + ::uint8_t* PublishAttitudeResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishUnixEpochTimeResponse& this_ = *this; + const PublishAttitudeResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishAttitudeResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -10882,18 +12113,18 @@ PROTOBUF_NOINLINE void PublishUnixEpochTimeResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishAttitudeResponse) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishUnixEpochTimeResponse::ByteSizeLong(const MessageLite& base) { - const PublishUnixEpochTimeResponse& this_ = static_cast(base); + ::size_t PublishAttitudeResponse::ByteSizeLong(const MessageLite& base) { + const PublishAttitudeResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishUnixEpochTimeResponse::ByteSizeLong() const { - const PublishUnixEpochTimeResponse& this_ = *this; + ::size_t PublishAttitudeResponse::ByteSizeLong() const { + const PublishAttitudeResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishAttitudeResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -10912,11 +12143,11 @@ PROTOBUF_NOINLINE void PublishUnixEpochTimeResponse::Clear() { &this_._impl_._cached_size_); } -void PublishUnixEpochTimeResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishAttitudeResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishAttitudeResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -10935,58 +12166,58 @@ void PublishUnixEpochTimeResponse::MergeImpl(::google::protobuf::MessageLite& to _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishUnixEpochTimeResponse::CopyFrom(const PublishUnixEpochTimeResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) +void PublishAttitudeResponse::CopyFrom(const PublishAttitudeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishAttitudeResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishUnixEpochTimeResponse::InternalSwap(PublishUnixEpochTimeResponse* PROTOBUF_RESTRICT other) { +void PublishAttitudeResponse::InternalSwap(PublishAttitudeResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); } -::google::protobuf::Metadata PublishUnixEpochTimeResponse::GetMetadata() const { +::google::protobuf::Metadata PublishAttitudeResponse::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== -class PublishDistanceSensorResponse::_Internal { +class PublishVisualFlightRulesHudResponse::_Internal { public: using HasBits = - decltype(std::declval()._impl_._has_bits_); + decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(PublishDistanceSensorResponse, _impl_._has_bits_); + 8 * PROTOBUF_FIELD_OFFSET(PublishVisualFlightRulesHudResponse, _impl_._has_bits_); }; -PublishDistanceSensorResponse::PublishDistanceSensorResponse(::google::protobuf::Arena* arena) +PublishVisualFlightRulesHudResponse::PublishVisualFlightRulesHudResponse(::google::protobuf::Arena* arena) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishDistanceSensorResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishVisualFlightRulesHudResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, - const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse& from_msg) + const Impl_& from, const ::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse& from_msg) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -PublishDistanceSensorResponse::PublishDistanceSensorResponse( +PublishVisualFlightRulesHudResponse::PublishVisualFlightRulesHudResponse( ::google::protobuf::Arena* arena, - const PublishDistanceSensorResponse& from) + const PublishVisualFlightRulesHudResponse& from) #if defined(PROTOBUF_CUSTOM_VTABLE) : ::google::protobuf::Message(arena, _class_data_.base()) { #else // PROTOBUF_CUSTOM_VTABLE : ::google::protobuf::Message(arena) { #endif // PROTOBUF_CUSTOM_VTABLE - PublishDistanceSensorResponse* const _this = this; + PublishVisualFlightRulesHudResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -10996,68 +12227,68 @@ PublishDistanceSensorResponse::PublishDistanceSensorResponse( arena, *from._impl_.telemetry_server_result_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse) } -inline PROTOBUF_NDEBUG_INLINE PublishDistanceSensorResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE PublishVisualFlightRulesHudResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void PublishDistanceSensorResponse::SharedCtor(::_pb::Arena* arena) { +inline void PublishVisualFlightRulesHudResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.telemetry_server_result_ = {}; } -PublishDistanceSensorResponse::~PublishDistanceSensorResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) +PublishVisualFlightRulesHudResponse::~PublishVisualFlightRulesHudResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse) SharedDtor(*this); } -inline void PublishDistanceSensorResponse::SharedDtor(MessageLite& self) { - PublishDistanceSensorResponse& this_ = static_cast(self); +inline void PublishVisualFlightRulesHudResponse::SharedDtor(MessageLite& self) { + PublishVisualFlightRulesHudResponse& this_ = static_cast(self); this_._internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); ABSL_DCHECK(this_.GetArena() == nullptr); delete this_._impl_.telemetry_server_result_; this_._impl_.~Impl_(); } -inline void* PublishDistanceSensorResponse::PlacementNew_(const void*, void* mem, +inline void* PublishVisualFlightRulesHudResponse::PlacementNew_(const void*, void* mem, ::google::protobuf::Arena* arena) { - return ::new (mem) PublishDistanceSensorResponse(arena); + return ::new (mem) PublishVisualFlightRulesHudResponse(arena); } -constexpr auto PublishDistanceSensorResponse::InternalNewImpl_() { - return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishDistanceSensorResponse), - alignof(PublishDistanceSensorResponse)); +constexpr auto PublishVisualFlightRulesHudResponse::InternalNewImpl_() { + return ::google::protobuf::internal::MessageCreator::ZeroInit(sizeof(PublishVisualFlightRulesHudResponse), + alignof(PublishVisualFlightRulesHudResponse)); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::google::protobuf::internal::ClassDataFull PublishDistanceSensorResponse::_class_data_ = { +const ::google::protobuf::internal::ClassDataFull PublishVisualFlightRulesHudResponse::_class_data_ = { ::google::protobuf::internal::ClassData{ - &_PublishDistanceSensorResponse_default_instance_._instance, + &_PublishVisualFlightRulesHudResponse_default_instance_._instance, &_table_.header, nullptr, // OnDemandRegisterArenaDtor nullptr, // IsInitialized - &PublishDistanceSensorResponse::MergeImpl, - ::google::protobuf::Message::GetNewImpl(), + &PublishVisualFlightRulesHudResponse::MergeImpl, + ::google::protobuf::Message::GetNewImpl(), #if defined(PROTOBUF_CUSTOM_VTABLE) - &PublishDistanceSensorResponse::SharedDtor, - ::google::protobuf::Message::GetClearImpl(), &PublishDistanceSensorResponse::ByteSizeLong, - &PublishDistanceSensorResponse::_InternalSerialize, + &PublishVisualFlightRulesHudResponse::SharedDtor, + ::google::protobuf::Message::GetClearImpl(), &PublishVisualFlightRulesHudResponse::ByteSizeLong, + &PublishVisualFlightRulesHudResponse::_InternalSerialize, #endif // PROTOBUF_CUSTOM_VTABLE - PROTOBUF_FIELD_OFFSET(PublishDistanceSensorResponse, _impl_._cached_size_), + PROTOBUF_FIELD_OFFSET(PublishVisualFlightRulesHudResponse, _impl_._cached_size_), false, }, - &PublishDistanceSensorResponse::kDescriptorMethods, + &PublishVisualFlightRulesHudResponse::kDescriptorMethods, &descriptor_table_telemetry_5fserver_2ftelemetry_5fserver_2eproto, nullptr, // tracker }; -const ::google::protobuf::internal::ClassData* PublishDistanceSensorResponse::GetClassData() const { +const ::google::protobuf::internal::ClassData* PublishVisualFlightRulesHudResponse::GetClassData() const { ::google::protobuf::internal::PrefetchToLocalCache(&_class_data_); ::google::protobuf::internal::PrefetchToLocalCache(_class_data_.tc_table); return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishDistanceSensorResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishVisualFlightRulesHudResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(PublishDistanceSensorResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(PublishVisualFlightRulesHudResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -11070,17 +12301,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishDistanceSensorResponse::_table_ nullptr, // post_loop_handler ::_pbi::TcParser::GenericFallback, // fallback #ifdef PROTOBUF_PREFETCH_PARSE_TABLE - ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishDistanceSensorResponse>(), // to_prefetch + ::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::PublishVisualFlightRulesHudResponse>(), // to_prefetch #endif // PROTOBUF_PREFETCH_PARSE_TABLE }, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishDistanceSensorResponse, _impl_.telemetry_server_result_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(PublishVisualFlightRulesHudResponse, _impl_.telemetry_server_result_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - {PROTOBUF_FIELD_OFFSET(PublishDistanceSensorResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(PublishVisualFlightRulesHudResponse, _impl_.telemetry_server_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::telemetry_server::TelemetryServerResult>()}, @@ -11088,8 +12319,8 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> PublishDistanceSensorResponse::_table_ }}, }; -PROTOBUF_NOINLINE void PublishDistanceSensorResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) +PROTOBUF_NOINLINE void PublishVisualFlightRulesHudResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse) ::google::protobuf::internal::TSanWrite(&_impl_); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -11105,17 +12336,17 @@ PROTOBUF_NOINLINE void PublishDistanceSensorResponse::Clear() { } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::uint8_t* PublishDistanceSensorResponse::_InternalSerialize( + ::uint8_t* PublishVisualFlightRulesHudResponse::_InternalSerialize( const MessageLite& base, ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) { - const PublishDistanceSensorResponse& this_ = static_cast(base); + const PublishVisualFlightRulesHudResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::uint8_t* PublishDistanceSensorResponse::_InternalSerialize( + ::uint8_t* PublishVisualFlightRulesHudResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - const PublishDistanceSensorResponse& this_ = *this; + const PublishVisualFlightRulesHudResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -11132,18 +12363,18 @@ PROTOBUF_NOINLINE void PublishDistanceSensorResponse::Clear() { ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( this_._internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse) return target; } #if defined(PROTOBUF_CUSTOM_VTABLE) - ::size_t PublishDistanceSensorResponse::ByteSizeLong(const MessageLite& base) { - const PublishDistanceSensorResponse& this_ = static_cast(base); + ::size_t PublishVisualFlightRulesHudResponse::ByteSizeLong(const MessageLite& base) { + const PublishVisualFlightRulesHudResponse& this_ = static_cast(base); #else // PROTOBUF_CUSTOM_VTABLE - ::size_t PublishDistanceSensorResponse::ByteSizeLong() const { - const PublishDistanceSensorResponse& this_ = *this; + ::size_t PublishVisualFlightRulesHudResponse::ByteSizeLong() const { + const PublishVisualFlightRulesHudResponse& this_ = *this; #endif // PROTOBUF_CUSTOM_VTABLE - // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) + // @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -11162,11 +12393,11 @@ PROTOBUF_NOINLINE void PublishDistanceSensorResponse::Clear() { &this_._impl_._cached_size_); } -void PublishDistanceSensorResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); +void PublishVisualFlightRulesHudResponse::MergeImpl(::google::protobuf::MessageLite& to_msg, const ::google::protobuf::MessageLite& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); ::google::protobuf::Arena* arena = _this->GetArena(); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -11185,22 +12416,22 @@ void PublishDistanceSensorResponse::MergeImpl(::google::protobuf::MessageLite& t _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void PublishDistanceSensorResponse::CopyFrom(const PublishDistanceSensorResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) +void PublishVisualFlightRulesHudResponse::CopyFrom(const PublishVisualFlightRulesHudResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void PublishDistanceSensorResponse::InternalSwap(PublishDistanceSensorResponse* PROTOBUF_RESTRICT other) { +void PublishVisualFlightRulesHudResponse::InternalSwap(PublishVisualFlightRulesHudResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.telemetry_server_result_, other->_impl_.telemetry_server_result_); } -::google::protobuf::Metadata PublishDistanceSensorResponse::GetMetadata() const { +::google::protobuf::Metadata PublishVisualFlightRulesHudResponse::GetMetadata() const { return ::google::protobuf::Message::GetMetadataImpl(GetClassData()->full()); } // =================================================================== @@ -17499,9 +18730,9 @@ inline void FixedwingMetrics::SharedCtor(::_pb::Arena* arena) { ::memset(reinterpret_cast(&_impl_) + offsetof(Impl_, airspeed_m_s_), 0, - offsetof(Impl_, climb_rate_m_s_) - + offsetof(Impl_, absolute_altitude_m_) - offsetof(Impl_, airspeed_m_s_) + - sizeof(Impl_::climb_rate_m_s_)); + sizeof(Impl_::absolute_altitude_m_)); } FixedwingMetrics::~FixedwingMetrics() { // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry_server.FixedwingMetrics) @@ -17550,15 +18781,15 @@ const ::google::protobuf::internal::ClassData* FixedwingMetrics::GetClassData() return _class_data_.base(); } PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<2, 3, 0, 0, 2> FixedwingMetrics::_table_ = { +const ::_pbi::TcParseTable<3, 6, 0, 0, 2> FixedwingMetrics::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 3, 24, // max_field_number, fast_idx_mask + 6, 56, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967288, // skipmap + 4294967232, // skipmap offsetof(decltype(_table_), field_entries), - 3, // num_field_entries + 6, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries _class_data_.base(), @@ -17578,6 +18809,16 @@ const ::_pbi::TcParseTable<2, 3, 0, 0, 2> FixedwingMetrics::_table_ = { // float climb_rate_m_s = 3 [(.mavsdk.options.default_value) = "NaN"]; {::_pbi::TcParser::FastF32S1, {29, 63, 0, PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.climb_rate_m_s_)}}, + // float groundspeed_m_s = 4 [(.mavsdk.options.default_value) = "NaN"]; + {::_pbi::TcParser::FastF32S1, + {37, 63, 0, PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.groundspeed_m_s_)}}, + // float heading_deg = 5 [(.mavsdk.options.default_value) = "NaN"]; + {::_pbi::TcParser::FastF32S1, + {45, 63, 0, PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.heading_deg_)}}, + // float absolute_altitude_m = 6 [(.mavsdk.options.default_value) = "NaN"]; + {::_pbi::TcParser::FastF32S1, + {53, 63, 0, PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.absolute_altitude_m_)}}, + {::_pbi::TcParser::MiniParse, {}}, }}, {{ 65535, 65535 }}, {{ @@ -17590,6 +18831,15 @@ const ::_pbi::TcParseTable<2, 3, 0, 0, 2> FixedwingMetrics::_table_ = { // float climb_rate_m_s = 3 [(.mavsdk.options.default_value) = "NaN"]; {PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.climb_rate_m_s_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float groundspeed_m_s = 4 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.groundspeed_m_s_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float heading_deg = 5 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.heading_deg_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float absolute_altitude_m = 6 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.absolute_altitude_m_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, }}, // no aux_entries {{ @@ -17604,8 +18854,8 @@ PROTOBUF_NOINLINE void FixedwingMetrics::Clear() { (void) cached_has_bits; ::memset(&_impl_.airspeed_m_s_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.climb_rate_m_s_) - - reinterpret_cast(&_impl_.airspeed_m_s_)) + sizeof(_impl_.climb_rate_m_s_)); + reinterpret_cast(&_impl_.absolute_altitude_m_) - + reinterpret_cast(&_impl_.airspeed_m_s_)) + sizeof(_impl_.absolute_altitude_m_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -17645,6 +18895,27 @@ PROTOBUF_NOINLINE void FixedwingMetrics::Clear() { 3, this_._internal_climb_rate_m_s(), target); } + // float groundspeed_m_s = 4 [(.mavsdk.options.default_value) = "NaN"]; + if (::absl::bit_cast<::uint32_t>(this_._internal_groundspeed_m_s()) != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 4, this_._internal_groundspeed_m_s(), target); + } + + // float heading_deg = 5 [(.mavsdk.options.default_value) = "NaN"]; + if (::absl::bit_cast<::uint32_t>(this_._internal_heading_deg()) != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 5, this_._internal_heading_deg(), target); + } + + // float absolute_altitude_m = 6 [(.mavsdk.options.default_value) = "NaN"]; + if (::absl::bit_cast<::uint32_t>(this_._internal_absolute_altitude_m()) != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 6, this_._internal_absolute_altitude_m(), target); + } + if (PROTOBUF_PREDICT_FALSE(this_._internal_metadata_.have_unknown_fields())) { target = ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( @@ -17682,6 +18953,18 @@ PROTOBUF_NOINLINE void FixedwingMetrics::Clear() { if (::absl::bit_cast<::uint32_t>(this_._internal_climb_rate_m_s()) != 0) { total_size += 5; } + // float groundspeed_m_s = 4 [(.mavsdk.options.default_value) = "NaN"]; + if (::absl::bit_cast<::uint32_t>(this_._internal_groundspeed_m_s()) != 0) { + total_size += 5; + } + // float heading_deg = 5 [(.mavsdk.options.default_value) = "NaN"]; + if (::absl::bit_cast<::uint32_t>(this_._internal_heading_deg()) != 0) { + total_size += 5; + } + // float absolute_altitude_m = 6 [(.mavsdk.options.default_value) = "NaN"]; + if (::absl::bit_cast<::uint32_t>(this_._internal_absolute_altitude_m()) != 0) { + total_size += 5; + } } return this_.MaybeComputeUnknownFieldsSize(total_size, &this_._impl_._cached_size_); @@ -17704,6 +18987,15 @@ void FixedwingMetrics::MergeImpl(::google::protobuf::MessageLite& to_msg, const if (::absl::bit_cast<::uint32_t>(from._internal_climb_rate_m_s()) != 0) { _this->_impl_.climb_rate_m_s_ = from._impl_.climb_rate_m_s_; } + if (::absl::bit_cast<::uint32_t>(from._internal_groundspeed_m_s()) != 0) { + _this->_impl_.groundspeed_m_s_ = from._impl_.groundspeed_m_s_; + } + if (::absl::bit_cast<::uint32_t>(from._internal_heading_deg()) != 0) { + _this->_impl_.heading_deg_ = from._impl_.heading_deg_; + } + if (::absl::bit_cast<::uint32_t>(from._internal_absolute_altitude_m()) != 0) { + _this->_impl_.absolute_altitude_m_ = from._impl_.absolute_altitude_m_; + } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } @@ -17719,8 +19011,8 @@ void FixedwingMetrics::InternalSwap(FixedwingMetrics* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); ::google::protobuf::internal::memswap< - PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.climb_rate_m_s_) - + sizeof(FixedwingMetrics::_impl_.climb_rate_m_s_) + PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.absolute_altitude_m_) + + sizeof(FixedwingMetrics::_impl_.absolute_altitude_m_) - PROTOBUF_FIELD_OFFSET(FixedwingMetrics, _impl_.airspeed_m_s_)>( reinterpret_cast(&_impl_.airspeed_m_s_), reinterpret_cast(&other->_impl_.airspeed_m_s_)); diff --git a/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.pb.h b/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.pb.h index 6e7c999688..135d148a61 100644 --- a/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.pb.h +++ b/src/mavsdk_server/src/generated/telemetry_server/telemetry_server.pb.h @@ -116,6 +116,12 @@ extern PositionNedDefaultTypeInternal _PositionNed_default_instance_; class PositionVelocityNed; struct PositionVelocityNedDefaultTypeInternal; extern PositionVelocityNedDefaultTypeInternal _PositionVelocityNed_default_instance_; +class PublishAttitudeRequest; +struct PublishAttitudeRequestDefaultTypeInternal; +extern PublishAttitudeRequestDefaultTypeInternal _PublishAttitudeRequest_default_instance_; +class PublishAttitudeResponse; +struct PublishAttitudeResponseDefaultTypeInternal; +extern PublishAttitudeResponseDefaultTypeInternal _PublishAttitudeResponse_default_instance_; class PublishBatteryRequest; struct PublishBatteryRequestDefaultTypeInternal; extern PublishBatteryRequestDefaultTypeInternal _PublishBatteryRequest_default_instance_; @@ -215,6 +221,12 @@ extern PublishUnixEpochTimeRequestDefaultTypeInternal _PublishUnixEpochTimeReque class PublishUnixEpochTimeResponse; struct PublishUnixEpochTimeResponseDefaultTypeInternal; extern PublishUnixEpochTimeResponseDefaultTypeInternal _PublishUnixEpochTimeResponse_default_instance_; +class PublishVisualFlightRulesHudRequest; +struct PublishVisualFlightRulesHudRequestDefaultTypeInternal; +extern PublishVisualFlightRulesHudRequestDefaultTypeInternal _PublishVisualFlightRulesHudRequest_default_instance_; +class PublishVisualFlightRulesHudResponse; +struct PublishVisualFlightRulesHudResponseDefaultTypeInternal; +extern PublishVisualFlightRulesHudResponseDefaultTypeInternal _PublishVisualFlightRulesHudResponse_default_instance_; class Quaternion; struct QuaternionDefaultTypeInternal; extern QuaternionDefaultTypeInternal _Quaternion_default_instance_; @@ -533,7 +545,7 @@ class VelocityNed final return reinterpret_cast( &_VelocityNed_default_instance_); } - static constexpr int kIndexInFileMessages = 52; + static constexpr int kIndexInFileMessages = 56; friend void swap(VelocityNed& a, VelocityNed& b) { a.Swap(&b); } inline void Swap(VelocityNed* other) { if (other == this) return; @@ -748,7 +760,7 @@ class VelocityBody final return reinterpret_cast( &_VelocityBody_default_instance_); } - static constexpr int kIndexInFileMessages = 46; + static constexpr int kIndexInFileMessages = 50; friend void swap(VelocityBody& a, VelocityBody& b) { a.Swap(&b); } inline void Swap(VelocityBody* other) { if (other == this) return; @@ -963,7 +975,7 @@ class TelemetryServerResult final return reinterpret_cast( &_TelemetryServerResult_default_instance_); } - static constexpr int kIndexInFileMessages = 60; + static constexpr int kIndexInFileMessages = 64; friend void swap(TelemetryServerResult& a, TelemetryServerResult& b) { a.Swap(&b); } inline void Swap(TelemetryServerResult* other) { if (other == this) return; @@ -1197,7 +1209,7 @@ class StatusText final return reinterpret_cast( &_StatusText_default_instance_); } - static constexpr int kIndexInFileMessages = 42; + static constexpr int kIndexInFileMessages = 46; friend void swap(StatusText& a, StatusText& b) { a.Swap(&b); } inline void Swap(StatusText* other) { if (other == this) return; @@ -1406,7 +1418,7 @@ class ScaledPressure final return reinterpret_cast( &_ScaledPressure_default_instance_); } - static constexpr int kIndexInFileMessages = 50; + static constexpr int kIndexInFileMessages = 54; friend void swap(ScaledPressure& a, ScaledPressure& b) { a.Swap(&b); } inline void Swap(ScaledPressure* other) { if (other == this) return; @@ -1645,7 +1657,7 @@ class RcStatus final return reinterpret_cast( &_RcStatus_default_instance_); } - static constexpr int kIndexInFileMessages = 41; + static constexpr int kIndexInFileMessages = 45; friend void swap(RcStatus& a, RcStatus& b) { a.Swap(&b); } inline void Swap(RcStatus* other) { if (other == this) return; @@ -1860,7 +1872,7 @@ class RawGps final return reinterpret_cast( &_RawGps_default_instance_); } - static constexpr int kIndexInFileMessages = 39; + static constexpr int kIndexInFileMessages = 43; friend void swap(RawGps& a, RawGps& b) { a.Swap(&b); } inline void Swap(RawGps* other) { if (other == this) return; @@ -2207,7 +2219,7 @@ class Quaternion final return reinterpret_cast( &_Quaternion_default_instance_); } - static constexpr int kIndexInFileMessages = 35; + static constexpr int kIndexInFileMessages = 39; friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); } inline void Swap(Quaternion* other) { if (other == this) return; @@ -3222,7 +3234,7 @@ class PositionNed final return reinterpret_cast( &_PositionNed_default_instance_); } - static constexpr int kIndexInFileMessages = 51; + static constexpr int kIndexInFileMessages = 55; friend void swap(PositionNed& a, PositionNed& b) { a.Swap(&b); } inline void Swap(PositionNed* other) { if (other == this) return; @@ -3437,7 +3449,7 @@ class PositionBody final return reinterpret_cast( &_PositionBody_default_instance_); } - static constexpr int kIndexInFileMessages = 47; + static constexpr int kIndexInFileMessages = 51; friend void swap(PositionBody& a, PositionBody& b) { a.Swap(&b); } inline void Swap(PositionBody* other) { if (other == this) return; @@ -3652,7 +3664,7 @@ class Position final return reinterpret_cast( &_Position_default_instance_); } - static constexpr int kIndexInFileMessages = 33; + static constexpr int kIndexInFileMessages = 37; friend void swap(Position& a, Position& b) { a.Swap(&b); } inline void Swap(Position* other) { if (other == this) return; @@ -3879,7 +3891,7 @@ class MagneticFieldFrd final return reinterpret_cast( &_MagneticFieldFrd_default_instance_); } - static constexpr int kIndexInFileMessages = 58; + static constexpr int kIndexInFileMessages = 62; friend void swap(MagneticFieldFrd& a, MagneticFieldFrd& b) { a.Swap(&b); } inline void Swap(MagneticFieldFrd* other) { if (other == this) return; @@ -4094,7 +4106,7 @@ class Heading final return reinterpret_cast( &_Heading_default_instance_); } - static constexpr int kIndexInFileMessages = 34; + static constexpr int kIndexInFileMessages = 38; friend void swap(Heading& a, Heading& b) { a.Swap(&b); } inline void Swap(Heading* other) { if (other == this) return; @@ -4285,7 +4297,7 @@ class GroundTruth final return reinterpret_cast( &_GroundTruth_default_instance_); } - static constexpr int kIndexInFileMessages = 54; + static constexpr int kIndexInFileMessages = 58; friend void swap(GroundTruth& a, GroundTruth& b) { a.Swap(&b); } inline void Swap(GroundTruth* other) { if (other == this) return; @@ -4500,7 +4512,7 @@ class GpsInfo final return reinterpret_cast( &_GpsInfo_default_instance_); } - static constexpr int kIndexInFileMessages = 38; + static constexpr int kIndexInFileMessages = 42; friend void swap(GpsInfo& a, GpsInfo& b) { a.Swap(&b); } inline void Swap(GpsInfo* other) { if (other == this) return; @@ -4703,7 +4715,7 @@ class FixedwingMetrics final return reinterpret_cast( &_FixedwingMetrics_default_instance_); } - static constexpr int kIndexInFileMessages = 55; + static constexpr int kIndexInFileMessages = 59; friend void swap(FixedwingMetrics& a, FixedwingMetrics& b) { a.Swap(&b); } inline void Swap(FixedwingMetrics* other) { if (other == this) return; @@ -4793,6 +4805,9 @@ class FixedwingMetrics final kAirspeedMSFieldNumber = 1, kThrottlePercentageFieldNumber = 2, kClimbRateMSFieldNumber = 3, + kGroundspeedMSFieldNumber = 4, + kHeadingDegFieldNumber = 5, + kAbsoluteAltitudeMFieldNumber = 6, }; // float airspeed_m_s = 1 [(.mavsdk.options.default_value) = "NaN"]; void clear_airspeed_m_s() ; @@ -4823,13 +4838,43 @@ class FixedwingMetrics final float _internal_climb_rate_m_s() const; void _internal_set_climb_rate_m_s(float value); + public: + // float groundspeed_m_s = 4 [(.mavsdk.options.default_value) = "NaN"]; + void clear_groundspeed_m_s() ; + float groundspeed_m_s() const; + void set_groundspeed_m_s(float value); + + private: + float _internal_groundspeed_m_s() const; + void _internal_set_groundspeed_m_s(float value); + + public: + // float heading_deg = 5 [(.mavsdk.options.default_value) = "NaN"]; + void clear_heading_deg() ; + float heading_deg() const; + void set_heading_deg(float value); + + private: + float _internal_heading_deg() const; + void _internal_set_heading_deg(float value); + + public: + // float absolute_altitude_m = 6 [(.mavsdk.options.default_value) = "NaN"]; + void clear_absolute_altitude_m() ; + float absolute_altitude_m() const; + void set_absolute_altitude_m(float value); + + private: + float _internal_absolute_altitude_m() const; + void _internal_set_absolute_altitude_m(float value); + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.FixedwingMetrics) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 0, + 3, 6, 0, 0, 2> _table_; @@ -4850,6 +4895,9 @@ class FixedwingMetrics final float airspeed_m_s_; float throttle_percentage_; float climb_rate_m_s_; + float groundspeed_m_s_; + float heading_deg_; + float absolute_altitude_m_; ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -4918,7 +4966,7 @@ class EulerAngle final return reinterpret_cast( &_EulerAngle_default_instance_); } - static constexpr int kIndexInFileMessages = 36; + static constexpr int kIndexInFileMessages = 40; friend void swap(EulerAngle& a, EulerAngle& b) { a.Swap(&b); } inline void Swap(EulerAngle* other) { if (other == this) return; @@ -5145,7 +5193,7 @@ class DistanceSensor final return reinterpret_cast( &_DistanceSensor_default_instance_); } - static constexpr int kIndexInFileMessages = 49; + static constexpr int kIndexInFileMessages = 53; friend void swap(DistanceSensor& a, DistanceSensor& b) { a.Swap(&b); } inline void Swap(DistanceSensor* other) { if (other == this) return; @@ -5360,7 +5408,7 @@ class Covariance final return reinterpret_cast( &_Covariance_default_instance_); } - static constexpr int kIndexInFileMessages = 45; + static constexpr int kIndexInFileMessages = 49; friend void swap(Covariance& a, Covariance& b) { a.Swap(&b); } inline void Swap(Covariance* other) { if (other == this) return; @@ -5559,7 +5607,7 @@ class Battery final return reinterpret_cast( &_Battery_default_instance_); } - static constexpr int kIndexInFileMessages = 40; + static constexpr int kIndexInFileMessages = 44; friend void swap(Battery& a, Battery& b) { a.Swap(&b); } inline void Swap(Battery* other) { if (other == this) return; @@ -5762,7 +5810,7 @@ class AngularVelocityFrd final return reinterpret_cast( &_AngularVelocityFrd_default_instance_); } - static constexpr int kIndexInFileMessages = 57; + static constexpr int kIndexInFileMessages = 61; friend void swap(AngularVelocityFrd& a, AngularVelocityFrd& b) { a.Swap(&b); } inline void Swap(AngularVelocityFrd* other) { if (other == this) return; @@ -5977,7 +6025,7 @@ class AngularVelocityBody final return reinterpret_cast( &_AngularVelocityBody_default_instance_); } - static constexpr int kIndexInFileMessages = 37; + static constexpr int kIndexInFileMessages = 41; friend void swap(AngularVelocityBody& a, AngularVelocityBody& b) { a.Swap(&b); } inline void Swap(AngularVelocityBody* other) { if (other == this) return; @@ -6192,7 +6240,7 @@ class ActuatorOutputStatus final return reinterpret_cast( &_ActuatorOutputStatus_default_instance_); } - static constexpr int kIndexInFileMessages = 44; + static constexpr int kIndexInFileMessages = 48; friend void swap(ActuatorOutputStatus& a, ActuatorOutputStatus& b) { a.Swap(&b); } inline void Swap(ActuatorOutputStatus* other) { if (other == this) return; @@ -6403,7 +6451,7 @@ class ActuatorControlTarget final return reinterpret_cast( &_ActuatorControlTarget_default_instance_); } - static constexpr int kIndexInFileMessages = 43; + static constexpr int kIndexInFileMessages = 47; friend void swap(ActuatorControlTarget& a, ActuatorControlTarget& b) { a.Swap(&b); } inline void Swap(ActuatorControlTarget* other) { if (other == this) return; @@ -6614,7 +6662,7 @@ class AccelerationFrd final return reinterpret_cast( &_AccelerationFrd_default_instance_); } - static constexpr int kIndexInFileMessages = 56; + static constexpr int kIndexInFileMessages = 60; friend void swap(AccelerationFrd& a, AccelerationFrd& b) { a.Swap(&b); } inline void Swap(AccelerationFrd* other) { if (other == this) return; @@ -6769,32 +6817,32 @@ class AccelerationFrd final }; // ------------------------------------------------------------------- -class PublishUnixEpochTimeResponse final +class PublishVisualFlightRulesHudResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse) */ { public: - inline PublishUnixEpochTimeResponse() : PublishUnixEpochTimeResponse(nullptr) {} - ~PublishUnixEpochTimeResponse() PROTOBUF_FINAL; + inline PublishVisualFlightRulesHudResponse() : PublishVisualFlightRulesHudResponse(nullptr) {} + ~PublishVisualFlightRulesHudResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishUnixEpochTimeResponse* msg, std::destroying_delete_t) { + void operator delete(PublishVisualFlightRulesHudResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishUnixEpochTimeResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishVisualFlightRulesHudResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishUnixEpochTimeResponse( + explicit PROTOBUF_CONSTEXPR PublishVisualFlightRulesHudResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishUnixEpochTimeResponse(const PublishUnixEpochTimeResponse& from) : PublishUnixEpochTimeResponse(nullptr, from) {} - inline PublishUnixEpochTimeResponse(PublishUnixEpochTimeResponse&& from) noexcept - : PublishUnixEpochTimeResponse(nullptr, std::move(from)) {} - inline PublishUnixEpochTimeResponse& operator=(const PublishUnixEpochTimeResponse& from) { + inline PublishVisualFlightRulesHudResponse(const PublishVisualFlightRulesHudResponse& from) : PublishVisualFlightRulesHudResponse(nullptr, from) {} + inline PublishVisualFlightRulesHudResponse(PublishVisualFlightRulesHudResponse&& from) noexcept + : PublishVisualFlightRulesHudResponse(nullptr, std::move(from)) {} + inline PublishVisualFlightRulesHudResponse& operator=(const PublishVisualFlightRulesHudResponse& from) { CopyFrom(from); return *this; } - inline PublishUnixEpochTimeResponse& operator=(PublishUnixEpochTimeResponse&& from) noexcept { + inline PublishVisualFlightRulesHudResponse& operator=(PublishVisualFlightRulesHudResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -6822,16 +6870,16 @@ class PublishUnixEpochTimeResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishUnixEpochTimeResponse& default_instance() { + static const PublishVisualFlightRulesHudResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishUnixEpochTimeResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishUnixEpochTimeResponse_default_instance_); + static inline const PublishVisualFlightRulesHudResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishVisualFlightRulesHudResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 31; - friend void swap(PublishUnixEpochTimeResponse& a, PublishUnixEpochTimeResponse& b) { a.Swap(&b); } - inline void Swap(PublishUnixEpochTimeResponse* other) { + static constexpr int kIndexInFileMessages = 36; + friend void swap(PublishVisualFlightRulesHudResponse& a, PublishVisualFlightRulesHudResponse& b) { a.Swap(&b); } + inline void Swap(PublishVisualFlightRulesHudResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -6839,7 +6887,7 @@ class PublishUnixEpochTimeResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishUnixEpochTimeResponse* other) { + void UnsafeArenaSwap(PublishVisualFlightRulesHudResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -6847,13 +6895,13 @@ class PublishUnixEpochTimeResponse final // implements Message ---------------------------------------------- - PublishUnixEpochTimeResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishVisualFlightRulesHudResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishUnixEpochTimeResponse& from); + void CopyFrom(const PublishVisualFlightRulesHudResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishUnixEpochTimeResponse& from) { PublishUnixEpochTimeResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishVisualFlightRulesHudResponse& from) { PublishVisualFlightRulesHudResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -6890,18 +6938,18 @@ class PublishUnixEpochTimeResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishUnixEpochTimeResponse* other); + void InternalSwap(PublishVisualFlightRulesHudResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse"; } protected: - explicit PublishUnixEpochTimeResponse(::google::protobuf::Arena* arena); - PublishUnixEpochTimeResponse(::google::protobuf::Arena* arena, const PublishUnixEpochTimeResponse& from); - PublishUnixEpochTimeResponse(::google::protobuf::Arena* arena, PublishUnixEpochTimeResponse&& from) noexcept - : PublishUnixEpochTimeResponse(arena) { + explicit PublishVisualFlightRulesHudResponse(::google::protobuf::Arena* arena); + PublishVisualFlightRulesHudResponse(::google::protobuf::Arena* arena, const PublishVisualFlightRulesHudResponse& from); + PublishVisualFlightRulesHudResponse(::google::protobuf::Arena* arena, PublishVisualFlightRulesHudResponse&& from) noexcept + : PublishVisualFlightRulesHudResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -6933,7 +6981,7 @@ class PublishUnixEpochTimeResponse final ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -6955,7 +7003,7 @@ class PublishUnixEpochTimeResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishUnixEpochTimeResponse& from_msg); + const PublishVisualFlightRulesHudResponse& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; @@ -6966,32 +7014,32 @@ class PublishUnixEpochTimeResponse final }; // ------------------------------------------------------------------- -class PublishSysStatusResponse final +class PublishVisualFlightRulesHudRequest final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest) */ { public: - inline PublishSysStatusResponse() : PublishSysStatusResponse(nullptr) {} - ~PublishSysStatusResponse() PROTOBUF_FINAL; + inline PublishVisualFlightRulesHudRequest() : PublishVisualFlightRulesHudRequest(nullptr) {} + ~PublishVisualFlightRulesHudRequest() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishSysStatusResponse* msg, std::destroying_delete_t) { + void operator delete(PublishVisualFlightRulesHudRequest* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishSysStatusResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishVisualFlightRulesHudRequest)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishSysStatusResponse( + explicit PROTOBUF_CONSTEXPR PublishVisualFlightRulesHudRequest( ::google::protobuf::internal::ConstantInitialized); - inline PublishSysStatusResponse(const PublishSysStatusResponse& from) : PublishSysStatusResponse(nullptr, from) {} - inline PublishSysStatusResponse(PublishSysStatusResponse&& from) noexcept - : PublishSysStatusResponse(nullptr, std::move(from)) {} - inline PublishSysStatusResponse& operator=(const PublishSysStatusResponse& from) { + inline PublishVisualFlightRulesHudRequest(const PublishVisualFlightRulesHudRequest& from) : PublishVisualFlightRulesHudRequest(nullptr, from) {} + inline PublishVisualFlightRulesHudRequest(PublishVisualFlightRulesHudRequest&& from) noexcept + : PublishVisualFlightRulesHudRequest(nullptr, std::move(from)) {} + inline PublishVisualFlightRulesHudRequest& operator=(const PublishVisualFlightRulesHudRequest& from) { CopyFrom(from); return *this; } - inline PublishSysStatusResponse& operator=(PublishSysStatusResponse&& from) noexcept { + inline PublishVisualFlightRulesHudRequest& operator=(PublishVisualFlightRulesHudRequest&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -7019,16 +7067,16 @@ class PublishSysStatusResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishSysStatusResponse& default_instance() { + static const PublishVisualFlightRulesHudRequest& default_instance() { return *internal_default_instance(); } - static inline const PublishSysStatusResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishSysStatusResponse_default_instance_); + static inline const PublishVisualFlightRulesHudRequest* internal_default_instance() { + return reinterpret_cast( + &_PublishVisualFlightRulesHudRequest_default_instance_); } - static constexpr int kIndexInFileMessages = 20; - friend void swap(PublishSysStatusResponse& a, PublishSysStatusResponse& b) { a.Swap(&b); } - inline void Swap(PublishSysStatusResponse* other) { + static constexpr int kIndexInFileMessages = 19; + friend void swap(PublishVisualFlightRulesHudRequest& a, PublishVisualFlightRulesHudRequest& b) { a.Swap(&b); } + inline void Swap(PublishVisualFlightRulesHudRequest* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -7036,7 +7084,7 @@ class PublishSysStatusResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishSysStatusResponse* other) { + void UnsafeArenaSwap(PublishVisualFlightRulesHudRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7044,13 +7092,13 @@ class PublishSysStatusResponse final // implements Message ---------------------------------------------- - PublishSysStatusResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishVisualFlightRulesHudRequest* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishSysStatusResponse& from); + void CopyFrom(const PublishVisualFlightRulesHudRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishSysStatusResponse& from) { PublishSysStatusResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishVisualFlightRulesHudRequest& from) { PublishVisualFlightRulesHudRequest::MergeImpl(*this, from); } private: static void MergeImpl( @@ -7087,18 +7135,18 @@ class PublishSysStatusResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishSysStatusResponse* other); + void InternalSwap(PublishVisualFlightRulesHudRequest* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishSysStatusResponse"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest"; } protected: - explicit PublishSysStatusResponse(::google::protobuf::Arena* arena); - PublishSysStatusResponse(::google::protobuf::Arena* arena, const PublishSysStatusResponse& from); - PublishSysStatusResponse(::google::protobuf::Arena* arena, PublishSysStatusResponse&& from) noexcept - : PublishSysStatusResponse(arena) { + explicit PublishVisualFlightRulesHudRequest(::google::protobuf::Arena* arena); + PublishVisualFlightRulesHudRequest(::google::protobuf::Arena* arena, const PublishVisualFlightRulesHudRequest& from); + PublishVisualFlightRulesHudRequest(::google::protobuf::Arena* arena, PublishVisualFlightRulesHudRequest&& from) noexcept + : PublishVisualFlightRulesHudRequest(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -7113,24 +7161,24 @@ class PublishSysStatusResponse final // accessors ------------------------------------------------------- enum : int { - kTelemetryServerResultFieldNumber = 1, + kFixedWingMetricsFieldNumber = 1, }; - // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - bool has_telemetry_server_result() const; - void clear_telemetry_server_result() ; - const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& telemetry_server_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::TelemetryServerResult* release_telemetry_server_result(); - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* mutable_telemetry_server_result(); - void set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); - void unsafe_arena_set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* unsafe_arena_release_telemetry_server_result(); + // .mavsdk.rpc.telemetry_server.FixedwingMetrics fixed_wing_metrics = 1; + bool has_fixed_wing_metrics() const; + void clear_fixed_wing_metrics() ; + const ::mavsdk::rpc::telemetry_server::FixedwingMetrics& fixed_wing_metrics() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::FixedwingMetrics* release_fixed_wing_metrics(); + ::mavsdk::rpc::telemetry_server::FixedwingMetrics* mutable_fixed_wing_metrics(); + void set_allocated_fixed_wing_metrics(::mavsdk::rpc::telemetry_server::FixedwingMetrics* value); + void unsafe_arena_set_allocated_fixed_wing_metrics(::mavsdk::rpc::telemetry_server::FixedwingMetrics* value); + ::mavsdk::rpc::telemetry_server::FixedwingMetrics* unsafe_arena_release_fixed_wing_metrics(); private: - const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& _internal_telemetry_server_result() const; - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); + const ::mavsdk::rpc::telemetry_server::FixedwingMetrics& _internal_fixed_wing_metrics() const; + ::mavsdk::rpc::telemetry_server::FixedwingMetrics* _internal_mutable_fixed_wing_metrics(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -7152,10 +7200,10 @@ class PublishSysStatusResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishSysStatusResponse& from_msg); + const PublishVisualFlightRulesHudRequest& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; + ::mavsdk::rpc::telemetry_server::FixedwingMetrics* fixed_wing_metrics_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -7163,32 +7211,32 @@ class PublishSysStatusResponse final }; // ------------------------------------------------------------------- -class PublishSysStatusRequest final +class PublishUnixEpochTimeResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishSysStatusRequest) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) */ { public: - inline PublishSysStatusRequest() : PublishSysStatusRequest(nullptr) {} - ~PublishSysStatusRequest() PROTOBUF_FINAL; + inline PublishUnixEpochTimeResponse() : PublishUnixEpochTimeResponse(nullptr) {} + ~PublishUnixEpochTimeResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishSysStatusRequest* msg, std::destroying_delete_t) { + void operator delete(PublishUnixEpochTimeResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishSysStatusRequest)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishUnixEpochTimeResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishSysStatusRequest( + explicit PROTOBUF_CONSTEXPR PublishUnixEpochTimeResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishSysStatusRequest(const PublishSysStatusRequest& from) : PublishSysStatusRequest(nullptr, from) {} - inline PublishSysStatusRequest(PublishSysStatusRequest&& from) noexcept - : PublishSysStatusRequest(nullptr, std::move(from)) {} - inline PublishSysStatusRequest& operator=(const PublishSysStatusRequest& from) { + inline PublishUnixEpochTimeResponse(const PublishUnixEpochTimeResponse& from) : PublishUnixEpochTimeResponse(nullptr, from) {} + inline PublishUnixEpochTimeResponse(PublishUnixEpochTimeResponse&& from) noexcept + : PublishUnixEpochTimeResponse(nullptr, std::move(from)) {} + inline PublishUnixEpochTimeResponse& operator=(const PublishUnixEpochTimeResponse& from) { CopyFrom(from); return *this; } - inline PublishSysStatusRequest& operator=(PublishSysStatusRequest&& from) noexcept { + inline PublishUnixEpochTimeResponse& operator=(PublishUnixEpochTimeResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -7216,16 +7264,16 @@ class PublishSysStatusRequest final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishSysStatusRequest& default_instance() { + static const PublishUnixEpochTimeResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishSysStatusRequest* internal_default_instance() { - return reinterpret_cast( - &_PublishSysStatusRequest_default_instance_); + static inline const PublishUnixEpochTimeResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishUnixEpochTimeResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 2; - friend void swap(PublishSysStatusRequest& a, PublishSysStatusRequest& b) { a.Swap(&b); } - inline void Swap(PublishSysStatusRequest* other) { + static constexpr int kIndexInFileMessages = 33; + friend void swap(PublishUnixEpochTimeResponse& a, PublishUnixEpochTimeResponse& b) { a.Swap(&b); } + inline void Swap(PublishUnixEpochTimeResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -7233,7 +7281,7 @@ class PublishSysStatusRequest final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishSysStatusRequest* other) { + void UnsafeArenaSwap(PublishUnixEpochTimeResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7241,13 +7289,13 @@ class PublishSysStatusRequest final // implements Message ---------------------------------------------- - PublishSysStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishUnixEpochTimeResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishSysStatusRequest& from); + void CopyFrom(const PublishUnixEpochTimeResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishSysStatusRequest& from) { PublishSysStatusRequest::MergeImpl(*this, from); } + void MergeFrom(const PublishUnixEpochTimeResponse& from) { PublishUnixEpochTimeResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -7284,18 +7332,18 @@ class PublishSysStatusRequest final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishSysStatusRequest* other); + void InternalSwap(PublishUnixEpochTimeResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishSysStatusRequest"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse"; } protected: - explicit PublishSysStatusRequest(::google::protobuf::Arena* arena); - PublishSysStatusRequest(::google::protobuf::Arena* arena, const PublishSysStatusRequest& from); - PublishSysStatusRequest(::google::protobuf::Arena* arena, PublishSysStatusRequest&& from) noexcept - : PublishSysStatusRequest(arena) { + explicit PublishUnixEpochTimeResponse(::google::protobuf::Arena* arena); + PublishUnixEpochTimeResponse(::google::protobuf::Arena* arena, const PublishUnixEpochTimeResponse& from); + PublishUnixEpochTimeResponse(::google::protobuf::Arena* arena, PublishUnixEpochTimeResponse&& from) noexcept + : PublishUnixEpochTimeResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -7310,84 +7358,877 @@ class PublishSysStatusRequest final // accessors ------------------------------------------------------- enum : int { - kBatteryFieldNumber = 1, - kRcReceiverStatusFieldNumber = 2, - kGyroStatusFieldNumber = 3, - kAccelStatusFieldNumber = 4, - kMagStatusFieldNumber = 5, - kGpsStatusFieldNumber = 6, + kTelemetryServerResultFieldNumber = 1, }; - // .mavsdk.rpc.telemetry_server.Battery battery = 1; - bool has_battery() const; - void clear_battery() ; - const ::mavsdk::rpc::telemetry_server::Battery& battery() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::Battery* release_battery(); - ::mavsdk::rpc::telemetry_server::Battery* mutable_battery(); - void set_allocated_battery(::mavsdk::rpc::telemetry_server::Battery* value); - void unsafe_arena_set_allocated_battery(::mavsdk::rpc::telemetry_server::Battery* value); - ::mavsdk::rpc::telemetry_server::Battery* unsafe_arena_release_battery(); + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + bool has_telemetry_server_result() const; + void clear_telemetry_server_result() ; + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& telemetry_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::TelemetryServerResult* release_telemetry_server_result(); + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* mutable_telemetry_server_result(); + void set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); + void unsafe_arena_set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* unsafe_arena_release_telemetry_server_result(); private: - const ::mavsdk::rpc::telemetry_server::Battery& _internal_battery() const; - ::mavsdk::rpc::telemetry_server::Battery* _internal_mutable_battery(); + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& _internal_telemetry_server_result() const; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // bool rc_receiver_status = 2; - void clear_rc_receiver_status() ; - bool rc_receiver_status() const; - void set_rc_receiver_status(bool value); - - private: - bool _internal_rc_receiver_status() const; - void _internal_set_rc_receiver_status(bool value); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishUnixEpochTimeResponse) + private: + class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 1, + 0, 2> + _table_; - public: - // bool gyro_status = 3; - void clear_gyro_status() ; - bool gyro_status() const; - void set_gyro_status(bool value); + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from, + const PublishUnixEpochTimeResponse& from_msg); + ::google::protobuf::internal::HasBits<1> _has_bits_; + ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_telemetry_5fserver_2ftelemetry_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class PublishSysStatusResponse final + : public ::google::protobuf::Message +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) */ { + public: + inline PublishSysStatusResponse() : PublishSysStatusResponse(nullptr) {} + ~PublishSysStatusResponse() PROTOBUF_FINAL; + +#if defined(PROTOBUF_CUSTOM_VTABLE) + void operator delete(PublishSysStatusResponse* msg, std::destroying_delete_t) { + SharedDtor(*msg); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishSysStatusResponse)); + } +#endif + + template + explicit PROTOBUF_CONSTEXPR PublishSysStatusResponse( + ::google::protobuf::internal::ConstantInitialized); + + inline PublishSysStatusResponse(const PublishSysStatusResponse& from) : PublishSysStatusResponse(nullptr, from) {} + inline PublishSysStatusResponse(PublishSysStatusResponse&& from) noexcept + : PublishSysStatusResponse(nullptr, std::move(from)) {} + inline PublishSysStatusResponse& operator=(const PublishSysStatusResponse& from) { + CopyFrom(from); + return *this; + } + inline PublishSysStatusResponse& operator=(PublishSysStatusResponse&& from) noexcept { + if (this == &from) return *this; + if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const PublishSysStatusResponse& default_instance() { + return *internal_default_instance(); + } + static inline const PublishSysStatusResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishSysStatusResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = 22; + friend void swap(PublishSysStatusResponse& a, PublishSysStatusResponse& b) { a.Swap(&b); } + inline void Swap(PublishSysStatusResponse* other) { + if (other == this) return; + if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(PublishSysStatusResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + PublishSysStatusResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const PublishSysStatusResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom(const PublishSysStatusResponse& from) { PublishSysStatusResponse::MergeImpl(*this, from); } + + private: + static void MergeImpl( + ::google::protobuf::MessageLite& to_msg, + const ::google::protobuf::MessageLite& from_msg); + + public: + bool IsInitialized() const { + return true; + } + ABSL_ATTRIBUTE_REINITIALIZES void Clear() PROTOBUF_FINAL; + #if defined(PROTOBUF_CUSTOM_VTABLE) + private: + static ::size_t ByteSizeLong(const ::google::protobuf::MessageLite& msg); + static ::uint8_t* _InternalSerialize( + const MessageLite& msg, ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream); + + public: + ::size_t ByteSizeLong() const { return ByteSizeLong(*this); } + ::uint8_t* _InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + return _InternalSerialize(*this, target, stream); + } + #else // PROTOBUF_CUSTOM_VTABLE + ::size_t ByteSizeLong() const final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + #endif // PROTOBUF_CUSTOM_VTABLE + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::google::protobuf::Arena* arena); + static void SharedDtor(MessageLite& self); + void InternalSwap(PublishSysStatusResponse* other); + private: + template + friend ::absl::string_view( + ::google::protobuf::internal::GetAnyMessageName)(); + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishSysStatusResponse"; } + + protected: + explicit PublishSysStatusResponse(::google::protobuf::Arena* arena); + PublishSysStatusResponse(::google::protobuf::Arena* arena, const PublishSysStatusResponse& from); + PublishSysStatusResponse(::google::protobuf::Arena* arena, PublishSysStatusResponse&& from) noexcept + : PublishSysStatusResponse(arena) { + *this = ::std::move(from); + } + const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; + static void* PlacementNew_(const void*, void* mem, + ::google::protobuf::Arena* arena); + static constexpr auto InternalNewImpl_(); + static const ::google::protobuf::internal::ClassDataFull _class_data_; + + public: + ::google::protobuf::Metadata GetMetadata() const; + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + enum : int { + kTelemetryServerResultFieldNumber = 1, + }; + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + bool has_telemetry_server_result() const; + void clear_telemetry_server_result() ; + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& telemetry_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::TelemetryServerResult* release_telemetry_server_result(); + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* mutable_telemetry_server_result(); + void set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); + void unsafe_arena_set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* unsafe_arena_release_telemetry_server_result(); + + private: + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& _internal_telemetry_server_result() const; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishSysStatusResponse) + private: + class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 1, + 0, 2> + _table_; + + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from, + const PublishSysStatusResponse& from_msg); + ::google::protobuf::internal::HasBits<1> _has_bits_; + ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_telemetry_5fserver_2ftelemetry_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class PublishSysStatusRequest final + : public ::google::protobuf::Message +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishSysStatusRequest) */ { + public: + inline PublishSysStatusRequest() : PublishSysStatusRequest(nullptr) {} + ~PublishSysStatusRequest() PROTOBUF_FINAL; + +#if defined(PROTOBUF_CUSTOM_VTABLE) + void operator delete(PublishSysStatusRequest* msg, std::destroying_delete_t) { + SharedDtor(*msg); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishSysStatusRequest)); + } +#endif + + template + explicit PROTOBUF_CONSTEXPR PublishSysStatusRequest( + ::google::protobuf::internal::ConstantInitialized); + + inline PublishSysStatusRequest(const PublishSysStatusRequest& from) : PublishSysStatusRequest(nullptr, from) {} + inline PublishSysStatusRequest(PublishSysStatusRequest&& from) noexcept + : PublishSysStatusRequest(nullptr, std::move(from)) {} + inline PublishSysStatusRequest& operator=(const PublishSysStatusRequest& from) { + CopyFrom(from); + return *this; + } + inline PublishSysStatusRequest& operator=(PublishSysStatusRequest&& from) noexcept { + if (this == &from) return *this; + if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const PublishSysStatusRequest& default_instance() { + return *internal_default_instance(); + } + static inline const PublishSysStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_PublishSysStatusRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = 2; + friend void swap(PublishSysStatusRequest& a, PublishSysStatusRequest& b) { a.Swap(&b); } + inline void Swap(PublishSysStatusRequest* other) { + if (other == this) return; + if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(PublishSysStatusRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + PublishSysStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const PublishSysStatusRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom(const PublishSysStatusRequest& from) { PublishSysStatusRequest::MergeImpl(*this, from); } + + private: + static void MergeImpl( + ::google::protobuf::MessageLite& to_msg, + const ::google::protobuf::MessageLite& from_msg); + + public: + bool IsInitialized() const { + return true; + } + ABSL_ATTRIBUTE_REINITIALIZES void Clear() PROTOBUF_FINAL; + #if defined(PROTOBUF_CUSTOM_VTABLE) + private: + static ::size_t ByteSizeLong(const ::google::protobuf::MessageLite& msg); + static ::uint8_t* _InternalSerialize( + const MessageLite& msg, ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream); + + public: + ::size_t ByteSizeLong() const { return ByteSizeLong(*this); } + ::uint8_t* _InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + return _InternalSerialize(*this, target, stream); + } + #else // PROTOBUF_CUSTOM_VTABLE + ::size_t ByteSizeLong() const final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + #endif // PROTOBUF_CUSTOM_VTABLE + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::google::protobuf::Arena* arena); + static void SharedDtor(MessageLite& self); + void InternalSwap(PublishSysStatusRequest* other); + private: + template + friend ::absl::string_view( + ::google::protobuf::internal::GetAnyMessageName)(); + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishSysStatusRequest"; } + + protected: + explicit PublishSysStatusRequest(::google::protobuf::Arena* arena); + PublishSysStatusRequest(::google::protobuf::Arena* arena, const PublishSysStatusRequest& from); + PublishSysStatusRequest(::google::protobuf::Arena* arena, PublishSysStatusRequest&& from) noexcept + : PublishSysStatusRequest(arena) { + *this = ::std::move(from); + } + const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; + static void* PlacementNew_(const void*, void* mem, + ::google::protobuf::Arena* arena); + static constexpr auto InternalNewImpl_(); + static const ::google::protobuf::internal::ClassDataFull _class_data_; + + public: + ::google::protobuf::Metadata GetMetadata() const; + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + enum : int { + kBatteryFieldNumber = 1, + kRcReceiverStatusFieldNumber = 2, + kGyroStatusFieldNumber = 3, + kAccelStatusFieldNumber = 4, + kMagStatusFieldNumber = 5, + kGpsStatusFieldNumber = 6, + }; + // .mavsdk.rpc.telemetry_server.Battery battery = 1; + bool has_battery() const; + void clear_battery() ; + const ::mavsdk::rpc::telemetry_server::Battery& battery() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::Battery* release_battery(); + ::mavsdk::rpc::telemetry_server::Battery* mutable_battery(); + void set_allocated_battery(::mavsdk::rpc::telemetry_server::Battery* value); + void unsafe_arena_set_allocated_battery(::mavsdk::rpc::telemetry_server::Battery* value); + ::mavsdk::rpc::telemetry_server::Battery* unsafe_arena_release_battery(); + + private: + const ::mavsdk::rpc::telemetry_server::Battery& _internal_battery() const; + ::mavsdk::rpc::telemetry_server::Battery* _internal_mutable_battery(); + + public: + // bool rc_receiver_status = 2; + void clear_rc_receiver_status() ; + bool rc_receiver_status() const; + void set_rc_receiver_status(bool value); + + private: + bool _internal_rc_receiver_status() const; + void _internal_set_rc_receiver_status(bool value); + + public: + // bool gyro_status = 3; + void clear_gyro_status() ; + bool gyro_status() const; + void set_gyro_status(bool value); + + private: + bool _internal_gyro_status() const; + void _internal_set_gyro_status(bool value); + + public: + // bool accel_status = 4; + void clear_accel_status() ; + bool accel_status() const; + void set_accel_status(bool value); + + private: + bool _internal_accel_status() const; + void _internal_set_accel_status(bool value); + + public: + // bool mag_status = 5; + void clear_mag_status() ; + bool mag_status() const; + void set_mag_status(bool value); + + private: + bool _internal_mag_status() const; + void _internal_set_mag_status(bool value); + + public: + // bool gps_status = 6; + void clear_gps_status() ; + bool gps_status() const; + void set_gps_status(bool value); + + private: + bool _internal_gps_status() const; + void _internal_set_gps_status(bool value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishSysStatusRequest) + private: + class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 3, 6, 1, + 0, 2> + _table_; + + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from, + const PublishSysStatusRequest& from_msg); + ::google::protobuf::internal::HasBits<1> _has_bits_; + ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::telemetry_server::Battery* battery_; + bool rc_receiver_status_; + bool gyro_status_; + bool accel_status_; + bool mag_status_; + bool gps_status_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_telemetry_5fserver_2ftelemetry_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class PublishStatusTextResponse final + : public ::google::protobuf::Message +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) */ { + public: + inline PublishStatusTextResponse() : PublishStatusTextResponse(nullptr) {} + ~PublishStatusTextResponse() PROTOBUF_FINAL; + +#if defined(PROTOBUF_CUSTOM_VTABLE) + void operator delete(PublishStatusTextResponse* msg, std::destroying_delete_t) { + SharedDtor(*msg); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishStatusTextResponse)); + } +#endif + + template + explicit PROTOBUF_CONSTEXPR PublishStatusTextResponse( + ::google::protobuf::internal::ConstantInitialized); + + inline PublishStatusTextResponse(const PublishStatusTextResponse& from) : PublishStatusTextResponse(nullptr, from) {} + inline PublishStatusTextResponse(PublishStatusTextResponse&& from) noexcept + : PublishStatusTextResponse(nullptr, std::move(from)) {} + inline PublishStatusTextResponse& operator=(const PublishStatusTextResponse& from) { + CopyFrom(from); + return *this; + } + inline PublishStatusTextResponse& operator=(PublishStatusTextResponse&& from) noexcept { + if (this == &from) return *this; + if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const PublishStatusTextResponse& default_instance() { + return *internal_default_instance(); + } + static inline const PublishStatusTextResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishStatusTextResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = 26; + friend void swap(PublishStatusTextResponse& a, PublishStatusTextResponse& b) { a.Swap(&b); } + inline void Swap(PublishStatusTextResponse* other) { + if (other == this) return; + if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(PublishStatusTextResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + PublishStatusTextResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const PublishStatusTextResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom(const PublishStatusTextResponse& from) { PublishStatusTextResponse::MergeImpl(*this, from); } + + private: + static void MergeImpl( + ::google::protobuf::MessageLite& to_msg, + const ::google::protobuf::MessageLite& from_msg); + + public: + bool IsInitialized() const { + return true; + } + ABSL_ATTRIBUTE_REINITIALIZES void Clear() PROTOBUF_FINAL; + #if defined(PROTOBUF_CUSTOM_VTABLE) + private: + static ::size_t ByteSizeLong(const ::google::protobuf::MessageLite& msg); + static ::uint8_t* _InternalSerialize( + const MessageLite& msg, ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream); + + public: + ::size_t ByteSizeLong() const { return ByteSizeLong(*this); } + ::uint8_t* _InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + return _InternalSerialize(*this, target, stream); + } + #else // PROTOBUF_CUSTOM_VTABLE + ::size_t ByteSizeLong() const final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + #endif // PROTOBUF_CUSTOM_VTABLE + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + void SharedCtor(::google::protobuf::Arena* arena); + static void SharedDtor(MessageLite& self); + void InternalSwap(PublishStatusTextResponse* other); + private: + template + friend ::absl::string_view( + ::google::protobuf::internal::GetAnyMessageName)(); + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishStatusTextResponse"; } + + protected: + explicit PublishStatusTextResponse(::google::protobuf::Arena* arena); + PublishStatusTextResponse(::google::protobuf::Arena* arena, const PublishStatusTextResponse& from); + PublishStatusTextResponse(::google::protobuf::Arena* arena, PublishStatusTextResponse&& from) noexcept + : PublishStatusTextResponse(arena) { + *this = ::std::move(from); + } + const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; + static void* PlacementNew_(const void*, void* mem, + ::google::protobuf::Arena* arena); + static constexpr auto InternalNewImpl_(); + static const ::google::protobuf::internal::ClassDataFull _class_data_; + + public: + ::google::protobuf::Metadata GetMetadata() const; + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + enum : int { + kTelemetryServerResultFieldNumber = 1, + }; + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + bool has_telemetry_server_result() const; + void clear_telemetry_server_result() ; + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& telemetry_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::TelemetryServerResult* release_telemetry_server_result(); + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* mutable_telemetry_server_result(); + void set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); + void unsafe_arena_set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* unsafe_arena_release_telemetry_server_result(); + + private: + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& _internal_telemetry_server_result() const; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + private: + class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 1, + 0, 2> + _table_; + + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from, + const PublishStatusTextResponse& from_msg); + ::google::protobuf::internal::HasBits<1> _has_bits_; + ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_telemetry_5fserver_2ftelemetry_5fserver_2eproto; +}; +// ------------------------------------------------------------------- + +class PublishStatusTextRequest final + : public ::google::protobuf::Message +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishStatusTextRequest) */ { + public: + inline PublishStatusTextRequest() : PublishStatusTextRequest(nullptr) {} + ~PublishStatusTextRequest() PROTOBUF_FINAL; + +#if defined(PROTOBUF_CUSTOM_VTABLE) + void operator delete(PublishStatusTextRequest* msg, std::destroying_delete_t) { + SharedDtor(*msg); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishStatusTextRequest)); + } +#endif + + template + explicit PROTOBUF_CONSTEXPR PublishStatusTextRequest( + ::google::protobuf::internal::ConstantInitialized); + + inline PublishStatusTextRequest(const PublishStatusTextRequest& from) : PublishStatusTextRequest(nullptr, from) {} + inline PublishStatusTextRequest(PublishStatusTextRequest&& from) noexcept + : PublishStatusTextRequest(nullptr, std::move(from)) {} + inline PublishStatusTextRequest& operator=(const PublishStatusTextRequest& from) { + CopyFrom(from); + return *this; + } + inline PublishStatusTextRequest& operator=(PublishStatusTextRequest&& from) noexcept { + if (this == &from) return *this; + if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const PublishStatusTextRequest& default_instance() { + return *internal_default_instance(); + } + static inline const PublishStatusTextRequest* internal_default_instance() { + return reinterpret_cast( + &_PublishStatusTextRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = 9; + friend void swap(PublishStatusTextRequest& a, PublishStatusTextRequest& b) { a.Swap(&b); } + inline void Swap(PublishStatusTextRequest* other) { + if (other == this) return; + if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(PublishStatusTextRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + PublishStatusTextRequest* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const PublishStatusTextRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom(const PublishStatusTextRequest& from) { PublishStatusTextRequest::MergeImpl(*this, from); } private: - bool _internal_gyro_status() const; - void _internal_set_gyro_status(bool value); + static void MergeImpl( + ::google::protobuf::MessageLite& to_msg, + const ::google::protobuf::MessageLite& from_msg); public: - // bool accel_status = 4; - void clear_accel_status() ; - bool accel_status() const; - void set_accel_status(bool value); - + bool IsInitialized() const { + return true; + } + ABSL_ATTRIBUTE_REINITIALIZES void Clear() PROTOBUF_FINAL; + #if defined(PROTOBUF_CUSTOM_VTABLE) private: - bool _internal_accel_status() const; - void _internal_set_accel_status(bool value); + static ::size_t ByteSizeLong(const ::google::protobuf::MessageLite& msg); + static ::uint8_t* _InternalSerialize( + const MessageLite& msg, ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream); public: - // bool mag_status = 5; - void clear_mag_status() ; - bool mag_status() const; - void set_mag_status(bool value); + ::size_t ByteSizeLong() const { return ByteSizeLong(*this); } + ::uint8_t* _InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + return _InternalSerialize(*this, target, stream); + } + #else // PROTOBUF_CUSTOM_VTABLE + ::size_t ByteSizeLong() const final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + #endif // PROTOBUF_CUSTOM_VTABLE + int GetCachedSize() const { return _impl_._cached_size_.Get(); } private: - bool _internal_mag_status() const; - void _internal_set_mag_status(bool value); + void SharedCtor(::google::protobuf::Arena* arena); + static void SharedDtor(MessageLite& self); + void InternalSwap(PublishStatusTextRequest* other); + private: + template + friend ::absl::string_view( + ::google::protobuf::internal::GetAnyMessageName)(); + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishStatusTextRequest"; } - public: - // bool gps_status = 6; - void clear_gps_status() ; - bool gps_status() const; - void set_gps_status(bool value); + protected: + explicit PublishStatusTextRequest(::google::protobuf::Arena* arena); + PublishStatusTextRequest(::google::protobuf::Arena* arena, const PublishStatusTextRequest& from); + PublishStatusTextRequest(::google::protobuf::Arena* arena, PublishStatusTextRequest&& from) noexcept + : PublishStatusTextRequest(arena) { + *this = ::std::move(from); + } + const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; + static void* PlacementNew_(const void*, void* mem, + ::google::protobuf::Arena* arena); + static constexpr auto InternalNewImpl_(); + static const ::google::protobuf::internal::ClassDataFull _class_data_; + + public: + ::google::protobuf::Metadata GetMetadata() const; + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + enum : int { + kStatusTextFieldNumber = 1, + }; + // .mavsdk.rpc.telemetry_server.StatusText status_text = 1; + bool has_status_text() const; + void clear_status_text() ; + const ::mavsdk::rpc::telemetry_server::StatusText& status_text() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::StatusText* release_status_text(); + ::mavsdk::rpc::telemetry_server::StatusText* mutable_status_text(); + void set_allocated_status_text(::mavsdk::rpc::telemetry_server::StatusText* value); + void unsafe_arena_set_allocated_status_text(::mavsdk::rpc::telemetry_server::StatusText* value); + ::mavsdk::rpc::telemetry_server::StatusText* unsafe_arena_release_status_text(); private: - bool _internal_gps_status() const; - void _internal_set_gps_status(bool value); + const ::mavsdk::rpc::telemetry_server::StatusText& _internal_status_text() const; + ::mavsdk::rpc::telemetry_server::StatusText* _internal_mutable_status_text(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishSysStatusRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishStatusTextRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 3, 6, 1, + 0, 1, 1, 0, 2> _table_; @@ -7404,15 +8245,10 @@ class PublishSysStatusRequest final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishSysStatusRequest& from_msg); + const PublishStatusTextRequest& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry_server::Battery* battery_; - bool rc_receiver_status_; - bool gyro_status_; - bool accel_status_; - bool mag_status_; - bool gps_status_; + ::mavsdk::rpc::telemetry_server::StatusText* status_text_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -7420,32 +8256,32 @@ class PublishSysStatusRequest final }; // ------------------------------------------------------------------- -class PublishStatusTextResponse final +class PublishScaledImuResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) */ { public: - inline PublishStatusTextResponse() : PublishStatusTextResponse(nullptr) {} - ~PublishStatusTextResponse() PROTOBUF_FINAL; + inline PublishScaledImuResponse() : PublishScaledImuResponse(nullptr) {} + ~PublishScaledImuResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishStatusTextResponse* msg, std::destroying_delete_t) { + void operator delete(PublishScaledImuResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishStatusTextResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishScaledImuResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishStatusTextResponse( + explicit PROTOBUF_CONSTEXPR PublishScaledImuResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishStatusTextResponse(const PublishStatusTextResponse& from) : PublishStatusTextResponse(nullptr, from) {} - inline PublishStatusTextResponse(PublishStatusTextResponse&& from) noexcept - : PublishStatusTextResponse(nullptr, std::move(from)) {} - inline PublishStatusTextResponse& operator=(const PublishStatusTextResponse& from) { + inline PublishScaledImuResponse(const PublishScaledImuResponse& from) : PublishScaledImuResponse(nullptr, from) {} + inline PublishScaledImuResponse(PublishScaledImuResponse&& from) noexcept + : PublishScaledImuResponse(nullptr, std::move(from)) {} + inline PublishScaledImuResponse& operator=(const PublishScaledImuResponse& from) { CopyFrom(from); return *this; } - inline PublishStatusTextResponse& operator=(PublishStatusTextResponse&& from) noexcept { + inline PublishScaledImuResponse& operator=(PublishScaledImuResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -7473,16 +8309,16 @@ class PublishStatusTextResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishStatusTextResponse& default_instance() { + static const PublishScaledImuResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishStatusTextResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishStatusTextResponse_default_instance_); + static inline const PublishScaledImuResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishScaledImuResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 24; - friend void swap(PublishStatusTextResponse& a, PublishStatusTextResponse& b) { a.Swap(&b); } - inline void Swap(PublishStatusTextResponse* other) { + static constexpr int kIndexInFileMessages = 31; + friend void swap(PublishScaledImuResponse& a, PublishScaledImuResponse& b) { a.Swap(&b); } + inline void Swap(PublishScaledImuResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -7490,7 +8326,7 @@ class PublishStatusTextResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishStatusTextResponse* other) { + void UnsafeArenaSwap(PublishScaledImuResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7498,13 +8334,13 @@ class PublishStatusTextResponse final // implements Message ---------------------------------------------- - PublishStatusTextResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishScaledImuResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishStatusTextResponse& from); + void CopyFrom(const PublishScaledImuResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishStatusTextResponse& from) { PublishStatusTextResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishScaledImuResponse& from) { PublishScaledImuResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -7541,18 +8377,18 @@ class PublishStatusTextResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishStatusTextResponse* other); + void InternalSwap(PublishScaledImuResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishStatusTextResponse"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishScaledImuResponse"; } protected: - explicit PublishStatusTextResponse(::google::protobuf::Arena* arena); - PublishStatusTextResponse(::google::protobuf::Arena* arena, const PublishStatusTextResponse& from); - PublishStatusTextResponse(::google::protobuf::Arena* arena, PublishStatusTextResponse&& from) noexcept - : PublishStatusTextResponse(arena) { + explicit PublishScaledImuResponse(::google::protobuf::Arena* arena); + PublishScaledImuResponse(::google::protobuf::Arena* arena, const PublishScaledImuResponse& from); + PublishScaledImuResponse(::google::protobuf::Arena* arena, PublishScaledImuResponse&& from) noexcept + : PublishScaledImuResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -7584,7 +8420,7 @@ class PublishStatusTextResponse final ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishStatusTextResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -7606,7 +8442,7 @@ class PublishStatusTextResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishStatusTextResponse& from_msg); + const PublishScaledImuResponse& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; @@ -7617,32 +8453,32 @@ class PublishStatusTextResponse final }; // ------------------------------------------------------------------- -class PublishStatusTextRequest final +class PublishRcStatusRequest final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishStatusTextRequest) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishRcStatusRequest) */ { public: - inline PublishStatusTextRequest() : PublishStatusTextRequest(nullptr) {} - ~PublishStatusTextRequest() PROTOBUF_FINAL; + inline PublishRcStatusRequest() : PublishRcStatusRequest(nullptr) {} + ~PublishRcStatusRequest() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishStatusTextRequest* msg, std::destroying_delete_t) { + void operator delete(PublishRcStatusRequest* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishStatusTextRequest)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishRcStatusRequest)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishStatusTextRequest( + explicit PROTOBUF_CONSTEXPR PublishRcStatusRequest( ::google::protobuf::internal::ConstantInitialized); - inline PublishStatusTextRequest(const PublishStatusTextRequest& from) : PublishStatusTextRequest(nullptr, from) {} - inline PublishStatusTextRequest(PublishStatusTextRequest&& from) noexcept - : PublishStatusTextRequest(nullptr, std::move(from)) {} - inline PublishStatusTextRequest& operator=(const PublishStatusTextRequest& from) { + inline PublishRcStatusRequest(const PublishRcStatusRequest& from) : PublishRcStatusRequest(nullptr, from) {} + inline PublishRcStatusRequest(PublishRcStatusRequest&& from) noexcept + : PublishRcStatusRequest(nullptr, std::move(from)) {} + inline PublishRcStatusRequest& operator=(const PublishRcStatusRequest& from) { CopyFrom(from); return *this; } - inline PublishStatusTextRequest& operator=(PublishStatusTextRequest&& from) noexcept { + inline PublishRcStatusRequest& operator=(PublishRcStatusRequest&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -7670,16 +8506,16 @@ class PublishStatusTextRequest final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishStatusTextRequest& default_instance() { + static const PublishRcStatusRequest& default_instance() { return *internal_default_instance(); } - static inline const PublishStatusTextRequest* internal_default_instance() { - return reinterpret_cast( - &_PublishStatusTextRequest_default_instance_); + static inline const PublishRcStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_PublishRcStatusRequest_default_instance_); } - static constexpr int kIndexInFileMessages = 9; - friend void swap(PublishStatusTextRequest& a, PublishStatusTextRequest& b) { a.Swap(&b); } - inline void Swap(PublishStatusTextRequest* other) { + static constexpr int kIndexInFileMessages = 8; + friend void swap(PublishRcStatusRequest& a, PublishRcStatusRequest& b) { a.Swap(&b); } + inline void Swap(PublishRcStatusRequest* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -7687,7 +8523,7 @@ class PublishStatusTextRequest final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishStatusTextRequest* other) { + void UnsafeArenaSwap(PublishRcStatusRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7695,13 +8531,13 @@ class PublishStatusTextRequest final // implements Message ---------------------------------------------- - PublishStatusTextRequest* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishRcStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishStatusTextRequest& from); + void CopyFrom(const PublishRcStatusRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishStatusTextRequest& from) { PublishStatusTextRequest::MergeImpl(*this, from); } + void MergeFrom(const PublishRcStatusRequest& from) { PublishRcStatusRequest::MergeImpl(*this, from); } private: static void MergeImpl( @@ -7738,18 +8574,18 @@ class PublishStatusTextRequest final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishStatusTextRequest* other); + void InternalSwap(PublishRcStatusRequest* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishStatusTextRequest"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishRcStatusRequest"; } protected: - explicit PublishStatusTextRequest(::google::protobuf::Arena* arena); - PublishStatusTextRequest(::google::protobuf::Arena* arena, const PublishStatusTextRequest& from); - PublishStatusTextRequest(::google::protobuf::Arena* arena, PublishStatusTextRequest&& from) noexcept - : PublishStatusTextRequest(arena) { + explicit PublishRcStatusRequest(::google::protobuf::Arena* arena); + PublishRcStatusRequest(::google::protobuf::Arena* arena, const PublishRcStatusRequest& from); + PublishRcStatusRequest(::google::protobuf::Arena* arena, PublishRcStatusRequest&& from) noexcept + : PublishRcStatusRequest(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -7764,24 +8600,24 @@ class PublishStatusTextRequest final // accessors ------------------------------------------------------- enum : int { - kStatusTextFieldNumber = 1, + kRcStatusFieldNumber = 1, }; - // .mavsdk.rpc.telemetry_server.StatusText status_text = 1; - bool has_status_text() const; - void clear_status_text() ; - const ::mavsdk::rpc::telemetry_server::StatusText& status_text() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::StatusText* release_status_text(); - ::mavsdk::rpc::telemetry_server::StatusText* mutable_status_text(); - void set_allocated_status_text(::mavsdk::rpc::telemetry_server::StatusText* value); - void unsafe_arena_set_allocated_status_text(::mavsdk::rpc::telemetry_server::StatusText* value); - ::mavsdk::rpc::telemetry_server::StatusText* unsafe_arena_release_status_text(); + // .mavsdk.rpc.telemetry_server.RcStatus rc_status = 1; + bool has_rc_status() const; + void clear_rc_status() ; + const ::mavsdk::rpc::telemetry_server::RcStatus& rc_status() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::RcStatus* release_rc_status(); + ::mavsdk::rpc::telemetry_server::RcStatus* mutable_rc_status(); + void set_allocated_rc_status(::mavsdk::rpc::telemetry_server::RcStatus* value); + void unsafe_arena_set_allocated_rc_status(::mavsdk::rpc::telemetry_server::RcStatus* value); + ::mavsdk::rpc::telemetry_server::RcStatus* unsafe_arena_release_rc_status(); private: - const ::mavsdk::rpc::telemetry_server::StatusText& _internal_status_text() const; - ::mavsdk::rpc::telemetry_server::StatusText* _internal_mutable_status_text(); + const ::mavsdk::rpc::telemetry_server::RcStatus& _internal_rc_status() const; + ::mavsdk::rpc::telemetry_server::RcStatus* _internal_mutable_rc_status(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishStatusTextRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishRcStatusRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -7803,10 +8639,10 @@ class PublishStatusTextRequest final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishStatusTextRequest& from_msg); + const PublishRcStatusRequest& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry_server::StatusText* status_text_; + ::mavsdk::rpc::telemetry_server::RcStatus* rc_status_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -7814,32 +8650,32 @@ class PublishStatusTextRequest final }; // ------------------------------------------------------------------- -class PublishScaledImuResponse final +class PublishRawImuResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishRawImuResponse) */ { public: - inline PublishScaledImuResponse() : PublishScaledImuResponse(nullptr) {} - ~PublishScaledImuResponse() PROTOBUF_FINAL; + inline PublishRawImuResponse() : PublishRawImuResponse(nullptr) {} + ~PublishRawImuResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishScaledImuResponse* msg, std::destroying_delete_t) { + void operator delete(PublishRawImuResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishScaledImuResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishRawImuResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishScaledImuResponse( + explicit PROTOBUF_CONSTEXPR PublishRawImuResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishScaledImuResponse(const PublishScaledImuResponse& from) : PublishScaledImuResponse(nullptr, from) {} - inline PublishScaledImuResponse(PublishScaledImuResponse&& from) noexcept - : PublishScaledImuResponse(nullptr, std::move(from)) {} - inline PublishScaledImuResponse& operator=(const PublishScaledImuResponse& from) { + inline PublishRawImuResponse(const PublishRawImuResponse& from) : PublishRawImuResponse(nullptr, from) {} + inline PublishRawImuResponse(PublishRawImuResponse&& from) noexcept + : PublishRawImuResponse(nullptr, std::move(from)) {} + inline PublishRawImuResponse& operator=(const PublishRawImuResponse& from) { CopyFrom(from); return *this; } - inline PublishScaledImuResponse& operator=(PublishScaledImuResponse&& from) noexcept { + inline PublishRawImuResponse& operator=(PublishRawImuResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -7867,16 +8703,16 @@ class PublishScaledImuResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishScaledImuResponse& default_instance() { + static const PublishRawImuResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishScaledImuResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishScaledImuResponse_default_instance_); + static inline const PublishRawImuResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishRawImuResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 29; - friend void swap(PublishScaledImuResponse& a, PublishScaledImuResponse& b) { a.Swap(&b); } - inline void Swap(PublishScaledImuResponse* other) { + static constexpr int kIndexInFileMessages = 32; + friend void swap(PublishRawImuResponse& a, PublishRawImuResponse& b) { a.Swap(&b); } + inline void Swap(PublishRawImuResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -7884,7 +8720,7 @@ class PublishScaledImuResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishScaledImuResponse* other) { + void UnsafeArenaSwap(PublishRawImuResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -7892,13 +8728,13 @@ class PublishScaledImuResponse final // implements Message ---------------------------------------------- - PublishScaledImuResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishRawImuResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishScaledImuResponse& from); + void CopyFrom(const PublishRawImuResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishScaledImuResponse& from) { PublishScaledImuResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishRawImuResponse& from) { PublishRawImuResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -7935,18 +8771,18 @@ class PublishScaledImuResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishScaledImuResponse* other); + void InternalSwap(PublishRawImuResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishScaledImuResponse"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishRawImuResponse"; } protected: - explicit PublishScaledImuResponse(::google::protobuf::Arena* arena); - PublishScaledImuResponse(::google::protobuf::Arena* arena, const PublishScaledImuResponse& from); - PublishScaledImuResponse(::google::protobuf::Arena* arena, PublishScaledImuResponse&& from) noexcept - : PublishScaledImuResponse(arena) { + explicit PublishRawImuResponse(::google::protobuf::Arena* arena); + PublishRawImuResponse(::google::protobuf::Arena* arena, const PublishRawImuResponse& from); + PublishRawImuResponse(::google::protobuf::Arena* arena, PublishRawImuResponse&& from) noexcept + : PublishRawImuResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -7978,7 +8814,7 @@ class PublishScaledImuResponse final ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishScaledImuResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishRawImuResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -8000,7 +8836,7 @@ class PublishScaledImuResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishScaledImuResponse& from_msg); + const PublishRawImuResponse& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; @@ -8011,32 +8847,32 @@ class PublishScaledImuResponse final }; // ------------------------------------------------------------------- -class PublishRcStatusRequest final +class PublishRawGpsResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishRcStatusRequest) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) */ { public: - inline PublishRcStatusRequest() : PublishRcStatusRequest(nullptr) {} - ~PublishRcStatusRequest() PROTOBUF_FINAL; + inline PublishRawGpsResponse() : PublishRawGpsResponse(nullptr) {} + ~PublishRawGpsResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishRcStatusRequest* msg, std::destroying_delete_t) { + void operator delete(PublishRawGpsResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishRcStatusRequest)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishRawGpsResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishRcStatusRequest( + explicit PROTOBUF_CONSTEXPR PublishRawGpsResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishRcStatusRequest(const PublishRcStatusRequest& from) : PublishRcStatusRequest(nullptr, from) {} - inline PublishRcStatusRequest(PublishRcStatusRequest&& from) noexcept - : PublishRcStatusRequest(nullptr, std::move(from)) {} - inline PublishRcStatusRequest& operator=(const PublishRcStatusRequest& from) { + inline PublishRawGpsResponse(const PublishRawGpsResponse& from) : PublishRawGpsResponse(nullptr, from) {} + inline PublishRawGpsResponse(PublishRawGpsResponse&& from) noexcept + : PublishRawGpsResponse(nullptr, std::move(from)) {} + inline PublishRawGpsResponse& operator=(const PublishRawGpsResponse& from) { CopyFrom(from); return *this; } - inline PublishRcStatusRequest& operator=(PublishRcStatusRequest&& from) noexcept { + inline PublishRawGpsResponse& operator=(PublishRawGpsResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -8064,16 +8900,16 @@ class PublishRcStatusRequest final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishRcStatusRequest& default_instance() { + static const PublishRawGpsResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishRcStatusRequest* internal_default_instance() { - return reinterpret_cast( - &_PublishRcStatusRequest_default_instance_); + static inline const PublishRawGpsResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishRawGpsResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 8; - friend void swap(PublishRcStatusRequest& a, PublishRcStatusRequest& b) { a.Swap(&b); } - inline void Swap(PublishRcStatusRequest* other) { + static constexpr int kIndexInFileMessages = 24; + friend void swap(PublishRawGpsResponse& a, PublishRawGpsResponse& b) { a.Swap(&b); } + inline void Swap(PublishRawGpsResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -8081,7 +8917,7 @@ class PublishRcStatusRequest final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishRcStatusRequest* other) { + void UnsafeArenaSwap(PublishRawGpsResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8089,13 +8925,13 @@ class PublishRcStatusRequest final // implements Message ---------------------------------------------- - PublishRcStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishRawGpsResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishRcStatusRequest& from); + void CopyFrom(const PublishRawGpsResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishRcStatusRequest& from) { PublishRcStatusRequest::MergeImpl(*this, from); } + void MergeFrom(const PublishRawGpsResponse& from) { PublishRawGpsResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -8132,18 +8968,18 @@ class PublishRcStatusRequest final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishRcStatusRequest* other); + void InternalSwap(PublishRawGpsResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishRcStatusRequest"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishRawGpsResponse"; } protected: - explicit PublishRcStatusRequest(::google::protobuf::Arena* arena); - PublishRcStatusRequest(::google::protobuf::Arena* arena, const PublishRcStatusRequest& from); - PublishRcStatusRequest(::google::protobuf::Arena* arena, PublishRcStatusRequest&& from) noexcept - : PublishRcStatusRequest(arena) { + explicit PublishRawGpsResponse(::google::protobuf::Arena* arena); + PublishRawGpsResponse(::google::protobuf::Arena* arena, const PublishRawGpsResponse& from); + PublishRawGpsResponse(::google::protobuf::Arena* arena, PublishRawGpsResponse&& from) noexcept + : PublishRawGpsResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -8158,24 +8994,24 @@ class PublishRcStatusRequest final // accessors ------------------------------------------------------- enum : int { - kRcStatusFieldNumber = 1, + kTelemetryServerResultFieldNumber = 1, }; - // .mavsdk.rpc.telemetry_server.RcStatus rc_status = 1; - bool has_rc_status() const; - void clear_rc_status() ; - const ::mavsdk::rpc::telemetry_server::RcStatus& rc_status() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::RcStatus* release_rc_status(); - ::mavsdk::rpc::telemetry_server::RcStatus* mutable_rc_status(); - void set_allocated_rc_status(::mavsdk::rpc::telemetry_server::RcStatus* value); - void unsafe_arena_set_allocated_rc_status(::mavsdk::rpc::telemetry_server::RcStatus* value); - ::mavsdk::rpc::telemetry_server::RcStatus* unsafe_arena_release_rc_status(); + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + bool has_telemetry_server_result() const; + void clear_telemetry_server_result() ; + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& telemetry_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::TelemetryServerResult* release_telemetry_server_result(); + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* mutable_telemetry_server_result(); + void set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); + void unsafe_arena_set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* unsafe_arena_release_telemetry_server_result(); private: - const ::mavsdk::rpc::telemetry_server::RcStatus& _internal_rc_status() const; - ::mavsdk::rpc::telemetry_server::RcStatus* _internal_mutable_rc_status(); + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& _internal_telemetry_server_result() const; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishRcStatusRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -8197,10 +9033,10 @@ class PublishRcStatusRequest final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishRcStatusRequest& from_msg); + const PublishRawGpsResponse& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry_server::RcStatus* rc_status_; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -8208,32 +9044,32 @@ class PublishRcStatusRequest final }; // ------------------------------------------------------------------- -class PublishRawImuResponse final +class PublishRawGpsRequest final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishRawImuResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishRawGpsRequest) */ { public: - inline PublishRawImuResponse() : PublishRawImuResponse(nullptr) {} - ~PublishRawImuResponse() PROTOBUF_FINAL; + inline PublishRawGpsRequest() : PublishRawGpsRequest(nullptr) {} + ~PublishRawGpsRequest() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishRawImuResponse* msg, std::destroying_delete_t) { + void operator delete(PublishRawGpsRequest* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishRawImuResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishRawGpsRequest)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishRawImuResponse( + explicit PROTOBUF_CONSTEXPR PublishRawGpsRequest( ::google::protobuf::internal::ConstantInitialized); - inline PublishRawImuResponse(const PublishRawImuResponse& from) : PublishRawImuResponse(nullptr, from) {} - inline PublishRawImuResponse(PublishRawImuResponse&& from) noexcept - : PublishRawImuResponse(nullptr, std::move(from)) {} - inline PublishRawImuResponse& operator=(const PublishRawImuResponse& from) { + inline PublishRawGpsRequest(const PublishRawGpsRequest& from) : PublishRawGpsRequest(nullptr, from) {} + inline PublishRawGpsRequest(PublishRawGpsRequest&& from) noexcept + : PublishRawGpsRequest(nullptr, std::move(from)) {} + inline PublishRawGpsRequest& operator=(const PublishRawGpsRequest& from) { CopyFrom(from); return *this; } - inline PublishRawImuResponse& operator=(PublishRawImuResponse&& from) noexcept { + inline PublishRawGpsRequest& operator=(PublishRawGpsRequest&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -8261,16 +9097,16 @@ class PublishRawImuResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishRawImuResponse& default_instance() { + static const PublishRawGpsRequest& default_instance() { return *internal_default_instance(); } - static inline const PublishRawImuResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishRawImuResponse_default_instance_); + static inline const PublishRawGpsRequest* internal_default_instance() { + return reinterpret_cast( + &_PublishRawGpsRequest_default_instance_); } - static constexpr int kIndexInFileMessages = 30; - friend void swap(PublishRawImuResponse& a, PublishRawImuResponse& b) { a.Swap(&b); } - inline void Swap(PublishRawImuResponse* other) { + static constexpr int kIndexInFileMessages = 6; + friend void swap(PublishRawGpsRequest& a, PublishRawGpsRequest& b) { a.Swap(&b); } + inline void Swap(PublishRawGpsRequest* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -8278,7 +9114,7 @@ class PublishRawImuResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishRawImuResponse* other) { + void UnsafeArenaSwap(PublishRawGpsRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8286,13 +9122,13 @@ class PublishRawImuResponse final // implements Message ---------------------------------------------- - PublishRawImuResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishRawGpsRequest* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishRawImuResponse& from); + void CopyFrom(const PublishRawGpsRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishRawImuResponse& from) { PublishRawImuResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishRawGpsRequest& from) { PublishRawGpsRequest::MergeImpl(*this, from); } private: static void MergeImpl( @@ -8329,18 +9165,18 @@ class PublishRawImuResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishRawImuResponse* other); + void InternalSwap(PublishRawGpsRequest* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishRawImuResponse"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishRawGpsRequest"; } protected: - explicit PublishRawImuResponse(::google::protobuf::Arena* arena); - PublishRawImuResponse(::google::protobuf::Arena* arena, const PublishRawImuResponse& from); - PublishRawImuResponse(::google::protobuf::Arena* arena, PublishRawImuResponse&& from) noexcept - : PublishRawImuResponse(arena) { + explicit PublishRawGpsRequest(::google::protobuf::Arena* arena); + PublishRawGpsRequest(::google::protobuf::Arena* arena, const PublishRawGpsRequest& from); + PublishRawGpsRequest(::google::protobuf::Arena* arena, PublishRawGpsRequest&& from) noexcept + : PublishRawGpsRequest(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -8355,29 +9191,45 @@ class PublishRawImuResponse final // accessors ------------------------------------------------------- enum : int { - kTelemetryServerResultFieldNumber = 1, + kRawGpsFieldNumber = 1, + kGpsInfoFieldNumber = 2, }; - // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - bool has_telemetry_server_result() const; - void clear_telemetry_server_result() ; - const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& telemetry_server_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::TelemetryServerResult* release_telemetry_server_result(); - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* mutable_telemetry_server_result(); - void set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); - void unsafe_arena_set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* unsafe_arena_release_telemetry_server_result(); + // .mavsdk.rpc.telemetry_server.RawGps raw_gps = 1; + bool has_raw_gps() const; + void clear_raw_gps() ; + const ::mavsdk::rpc::telemetry_server::RawGps& raw_gps() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::RawGps* release_raw_gps(); + ::mavsdk::rpc::telemetry_server::RawGps* mutable_raw_gps(); + void set_allocated_raw_gps(::mavsdk::rpc::telemetry_server::RawGps* value); + void unsafe_arena_set_allocated_raw_gps(::mavsdk::rpc::telemetry_server::RawGps* value); + ::mavsdk::rpc::telemetry_server::RawGps* unsafe_arena_release_raw_gps(); + + private: + const ::mavsdk::rpc::telemetry_server::RawGps& _internal_raw_gps() const; + ::mavsdk::rpc::telemetry_server::RawGps* _internal_mutable_raw_gps(); + + public: + // .mavsdk.rpc.telemetry_server.GpsInfo gps_info = 2; + bool has_gps_info() const; + void clear_gps_info() ; + const ::mavsdk::rpc::telemetry_server::GpsInfo& gps_info() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::GpsInfo* release_gps_info(); + ::mavsdk::rpc::telemetry_server::GpsInfo* mutable_gps_info(); + void set_allocated_gps_info(::mavsdk::rpc::telemetry_server::GpsInfo* value); + void unsafe_arena_set_allocated_gps_info(::mavsdk::rpc::telemetry_server::GpsInfo* value); + ::mavsdk::rpc::telemetry_server::GpsInfo* unsafe_arena_release_gps_info(); private: - const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& _internal_telemetry_server_result() const; - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); + const ::mavsdk::rpc::telemetry_server::GpsInfo& _internal_gps_info() const; + ::mavsdk::rpc::telemetry_server::GpsInfo* _internal_mutable_gps_info(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishRawImuResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishRawGpsRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 1, 2, 2, 0, 2> _table_; @@ -8394,10 +9246,11 @@ class PublishRawImuResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishRawImuResponse& from_msg); + const PublishRawGpsRequest& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; + ::mavsdk::rpc::telemetry_server::RawGps* raw_gps_; + ::mavsdk::rpc::telemetry_server::GpsInfo* gps_info_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -8405,32 +9258,32 @@ class PublishRawImuResponse final }; // ------------------------------------------------------------------- -class PublishRawGpsResponse final +class PublishPositionVelocityNedResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) */ { public: - inline PublishRawGpsResponse() : PublishRawGpsResponse(nullptr) {} - ~PublishRawGpsResponse() PROTOBUF_FINAL; + inline PublishPositionVelocityNedResponse() : PublishPositionVelocityNedResponse(nullptr) {} + ~PublishPositionVelocityNedResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishRawGpsResponse* msg, std::destroying_delete_t) { + void operator delete(PublishPositionVelocityNedResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishRawGpsResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishPositionVelocityNedResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishRawGpsResponse( + explicit PROTOBUF_CONSTEXPR PublishPositionVelocityNedResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishRawGpsResponse(const PublishRawGpsResponse& from) : PublishRawGpsResponse(nullptr, from) {} - inline PublishRawGpsResponse(PublishRawGpsResponse&& from) noexcept - : PublishRawGpsResponse(nullptr, std::move(from)) {} - inline PublishRawGpsResponse& operator=(const PublishRawGpsResponse& from) { + inline PublishPositionVelocityNedResponse(const PublishPositionVelocityNedResponse& from) : PublishPositionVelocityNedResponse(nullptr, from) {} + inline PublishPositionVelocityNedResponse(PublishPositionVelocityNedResponse&& from) noexcept + : PublishPositionVelocityNedResponse(nullptr, std::move(from)) {} + inline PublishPositionVelocityNedResponse& operator=(const PublishPositionVelocityNedResponse& from) { CopyFrom(from); return *this; } - inline PublishRawGpsResponse& operator=(PublishRawGpsResponse&& from) noexcept { + inline PublishPositionVelocityNedResponse& operator=(PublishPositionVelocityNedResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -8458,16 +9311,16 @@ class PublishRawGpsResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishRawGpsResponse& default_instance() { + static const PublishPositionVelocityNedResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishRawGpsResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishRawGpsResponse_default_instance_); + static inline const PublishPositionVelocityNedResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishPositionVelocityNedResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 22; - friend void swap(PublishRawGpsResponse& a, PublishRawGpsResponse& b) { a.Swap(&b); } - inline void Swap(PublishRawGpsResponse* other) { + static constexpr int kIndexInFileMessages = 28; + friend void swap(PublishPositionVelocityNedResponse& a, PublishPositionVelocityNedResponse& b) { a.Swap(&b); } + inline void Swap(PublishPositionVelocityNedResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -8475,7 +9328,7 @@ class PublishRawGpsResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishRawGpsResponse* other) { + void UnsafeArenaSwap(PublishPositionVelocityNedResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8483,13 +9336,13 @@ class PublishRawGpsResponse final // implements Message ---------------------------------------------- - PublishRawGpsResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishPositionVelocityNedResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishRawGpsResponse& from); + void CopyFrom(const PublishPositionVelocityNedResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishRawGpsResponse& from) { PublishRawGpsResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishPositionVelocityNedResponse& from) { PublishPositionVelocityNedResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -8526,18 +9379,18 @@ class PublishRawGpsResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishRawGpsResponse* other); + void InternalSwap(PublishPositionVelocityNedResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishRawGpsResponse"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse"; } protected: - explicit PublishRawGpsResponse(::google::protobuf::Arena* arena); - PublishRawGpsResponse(::google::protobuf::Arena* arena, const PublishRawGpsResponse& from); - PublishRawGpsResponse(::google::protobuf::Arena* arena, PublishRawGpsResponse&& from) noexcept - : PublishRawGpsResponse(arena) { + explicit PublishPositionVelocityNedResponse(::google::protobuf::Arena* arena); + PublishPositionVelocityNedResponse(::google::protobuf::Arena* arena, const PublishPositionVelocityNedResponse& from); + PublishPositionVelocityNedResponse(::google::protobuf::Arena* arena, PublishPositionVelocityNedResponse&& from) noexcept + : PublishPositionVelocityNedResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -8569,7 +9422,7 @@ class PublishRawGpsResponse final ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishRawGpsResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -8591,7 +9444,7 @@ class PublishRawGpsResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishRawGpsResponse& from_msg); + const PublishPositionVelocityNedResponse& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; @@ -8602,32 +9455,32 @@ class PublishRawGpsResponse final }; // ------------------------------------------------------------------- -class PublishRawGpsRequest final +class PublishPositionResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishRawGpsRequest) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishPositionResponse) */ { public: - inline PublishRawGpsRequest() : PublishRawGpsRequest(nullptr) {} - ~PublishRawGpsRequest() PROTOBUF_FINAL; + inline PublishPositionResponse() : PublishPositionResponse(nullptr) {} + ~PublishPositionResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishRawGpsRequest* msg, std::destroying_delete_t) { + void operator delete(PublishPositionResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishRawGpsRequest)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishPositionResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishRawGpsRequest( + explicit PROTOBUF_CONSTEXPR PublishPositionResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishRawGpsRequest(const PublishRawGpsRequest& from) : PublishRawGpsRequest(nullptr, from) {} - inline PublishRawGpsRequest(PublishRawGpsRequest&& from) noexcept - : PublishRawGpsRequest(nullptr, std::move(from)) {} - inline PublishRawGpsRequest& operator=(const PublishRawGpsRequest& from) { + inline PublishPositionResponse(const PublishPositionResponse& from) : PublishPositionResponse(nullptr, from) {} + inline PublishPositionResponse(PublishPositionResponse&& from) noexcept + : PublishPositionResponse(nullptr, std::move(from)) {} + inline PublishPositionResponse& operator=(const PublishPositionResponse& from) { CopyFrom(from); return *this; } - inline PublishRawGpsRequest& operator=(PublishRawGpsRequest&& from) noexcept { + inline PublishPositionResponse& operator=(PublishPositionResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -8655,16 +9508,16 @@ class PublishRawGpsRequest final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishRawGpsRequest& default_instance() { + static const PublishPositionResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishRawGpsRequest* internal_default_instance() { - return reinterpret_cast( - &_PublishRawGpsRequest_default_instance_); + static inline const PublishPositionResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishPositionResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 6; - friend void swap(PublishRawGpsRequest& a, PublishRawGpsRequest& b) { a.Swap(&b); } - inline void Swap(PublishRawGpsRequest* other) { + static constexpr int kIndexInFileMessages = 20; + friend void swap(PublishPositionResponse& a, PublishPositionResponse& b) { a.Swap(&b); } + inline void Swap(PublishPositionResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -8672,7 +9525,7 @@ class PublishRawGpsRequest final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishRawGpsRequest* other) { + void UnsafeArenaSwap(PublishPositionResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8680,13 +9533,13 @@ class PublishRawGpsRequest final // implements Message ---------------------------------------------- - PublishRawGpsRequest* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishPositionResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishRawGpsRequest& from); + void CopyFrom(const PublishPositionResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishRawGpsRequest& from) { PublishRawGpsRequest::MergeImpl(*this, from); } + void MergeFrom(const PublishPositionResponse& from) { PublishPositionResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -8723,18 +9576,18 @@ class PublishRawGpsRequest final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishRawGpsRequest* other); + void InternalSwap(PublishPositionResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishRawGpsRequest"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishPositionResponse"; } protected: - explicit PublishRawGpsRequest(::google::protobuf::Arena* arena); - PublishRawGpsRequest(::google::protobuf::Arena* arena, const PublishRawGpsRequest& from); - PublishRawGpsRequest(::google::protobuf::Arena* arena, PublishRawGpsRequest&& from) noexcept - : PublishRawGpsRequest(arena) { + explicit PublishPositionResponse(::google::protobuf::Arena* arena); + PublishPositionResponse(::google::protobuf::Arena* arena, const PublishPositionResponse& from); + PublishPositionResponse(::google::protobuf::Arena* arena, PublishPositionResponse&& from) noexcept + : PublishPositionResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -8749,45 +9602,29 @@ class PublishRawGpsRequest final // accessors ------------------------------------------------------- enum : int { - kRawGpsFieldNumber = 1, - kGpsInfoFieldNumber = 2, + kTelemetryServerResultFieldNumber = 1, }; - // .mavsdk.rpc.telemetry_server.RawGps raw_gps = 1; - bool has_raw_gps() const; - void clear_raw_gps() ; - const ::mavsdk::rpc::telemetry_server::RawGps& raw_gps() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::RawGps* release_raw_gps(); - ::mavsdk::rpc::telemetry_server::RawGps* mutable_raw_gps(); - void set_allocated_raw_gps(::mavsdk::rpc::telemetry_server::RawGps* value); - void unsafe_arena_set_allocated_raw_gps(::mavsdk::rpc::telemetry_server::RawGps* value); - ::mavsdk::rpc::telemetry_server::RawGps* unsafe_arena_release_raw_gps(); - - private: - const ::mavsdk::rpc::telemetry_server::RawGps& _internal_raw_gps() const; - ::mavsdk::rpc::telemetry_server::RawGps* _internal_mutable_raw_gps(); - - public: - // .mavsdk.rpc.telemetry_server.GpsInfo gps_info = 2; - bool has_gps_info() const; - void clear_gps_info() ; - const ::mavsdk::rpc::telemetry_server::GpsInfo& gps_info() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::GpsInfo* release_gps_info(); - ::mavsdk::rpc::telemetry_server::GpsInfo* mutable_gps_info(); - void set_allocated_gps_info(::mavsdk::rpc::telemetry_server::GpsInfo* value); - void unsafe_arena_set_allocated_gps_info(::mavsdk::rpc::telemetry_server::GpsInfo* value); - ::mavsdk::rpc::telemetry_server::GpsInfo* unsafe_arena_release_gps_info(); + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + bool has_telemetry_server_result() const; + void clear_telemetry_server_result() ; + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& telemetry_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::TelemetryServerResult* release_telemetry_server_result(); + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* mutable_telemetry_server_result(); + void set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); + void unsafe_arena_set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* unsafe_arena_release_telemetry_server_result(); private: - const ::mavsdk::rpc::telemetry_server::GpsInfo& _internal_gps_info() const; - ::mavsdk::rpc::telemetry_server::GpsInfo* _internal_mutable_gps_info(); + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& _internal_telemetry_server_result() const; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishRawGpsRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishPositionResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 1, 2, 2, + 0, 1, 1, 0, 2> _table_; @@ -8804,11 +9641,10 @@ class PublishRawGpsRequest final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishRawGpsRequest& from_msg); + const PublishPositionResponse& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry_server::RawGps* raw_gps_; - ::mavsdk::rpc::telemetry_server::GpsInfo* gps_info_; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -8816,32 +9652,32 @@ class PublishRawGpsRequest final }; // ------------------------------------------------------------------- -class PublishPositionVelocityNedResponse final +class PublishPositionRequest final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishPositionRequest) */ { public: - inline PublishPositionVelocityNedResponse() : PublishPositionVelocityNedResponse(nullptr) {} - ~PublishPositionVelocityNedResponse() PROTOBUF_FINAL; + inline PublishPositionRequest() : PublishPositionRequest(nullptr) {} + ~PublishPositionRequest() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishPositionVelocityNedResponse* msg, std::destroying_delete_t) { + void operator delete(PublishPositionRequest* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishPositionVelocityNedResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishPositionRequest)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishPositionVelocityNedResponse( + explicit PROTOBUF_CONSTEXPR PublishPositionRequest( ::google::protobuf::internal::ConstantInitialized); - inline PublishPositionVelocityNedResponse(const PublishPositionVelocityNedResponse& from) : PublishPositionVelocityNedResponse(nullptr, from) {} - inline PublishPositionVelocityNedResponse(PublishPositionVelocityNedResponse&& from) noexcept - : PublishPositionVelocityNedResponse(nullptr, std::move(from)) {} - inline PublishPositionVelocityNedResponse& operator=(const PublishPositionVelocityNedResponse& from) { + inline PublishPositionRequest(const PublishPositionRequest& from) : PublishPositionRequest(nullptr, from) {} + inline PublishPositionRequest(PublishPositionRequest&& from) noexcept + : PublishPositionRequest(nullptr, std::move(from)) {} + inline PublishPositionRequest& operator=(const PublishPositionRequest& from) { CopyFrom(from); return *this; } - inline PublishPositionVelocityNedResponse& operator=(PublishPositionVelocityNedResponse&& from) noexcept { + inline PublishPositionRequest& operator=(PublishPositionRequest&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -8869,16 +9705,16 @@ class PublishPositionVelocityNedResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishPositionVelocityNedResponse& default_instance() { + static const PublishPositionRequest& default_instance() { return *internal_default_instance(); } - static inline const PublishPositionVelocityNedResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishPositionVelocityNedResponse_default_instance_); + static inline const PublishPositionRequest* internal_default_instance() { + return reinterpret_cast( + &_PublishPositionRequest_default_instance_); } - static constexpr int kIndexInFileMessages = 26; - friend void swap(PublishPositionVelocityNedResponse& a, PublishPositionVelocityNedResponse& b) { a.Swap(&b); } - inline void Swap(PublishPositionVelocityNedResponse* other) { + static constexpr int kIndexInFileMessages = 0; + friend void swap(PublishPositionRequest& a, PublishPositionRequest& b) { a.Swap(&b); } + inline void Swap(PublishPositionRequest* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -8886,7 +9722,7 @@ class PublishPositionVelocityNedResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishPositionVelocityNedResponse* other) { + void UnsafeArenaSwap(PublishPositionRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -8894,13 +9730,13 @@ class PublishPositionVelocityNedResponse final // implements Message ---------------------------------------------- - PublishPositionVelocityNedResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishPositionRequest* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishPositionVelocityNedResponse& from); + void CopyFrom(const PublishPositionRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishPositionVelocityNedResponse& from) { PublishPositionVelocityNedResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishPositionRequest& from) { PublishPositionRequest::MergeImpl(*this, from); } private: static void MergeImpl( @@ -8937,18 +9773,18 @@ class PublishPositionVelocityNedResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishPositionVelocityNedResponse* other); + void InternalSwap(PublishPositionRequest* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse"; } - - protected: - explicit PublishPositionVelocityNedResponse(::google::protobuf::Arena* arena); - PublishPositionVelocityNedResponse(::google::protobuf::Arena* arena, const PublishPositionVelocityNedResponse& from); - PublishPositionVelocityNedResponse(::google::protobuf::Arena* arena, PublishPositionVelocityNedResponse&& from) noexcept - : PublishPositionVelocityNedResponse(arena) { + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishPositionRequest"; } + + protected: + explicit PublishPositionRequest(::google::protobuf::Arena* arena); + PublishPositionRequest(::google::protobuf::Arena* arena, const PublishPositionRequest& from); + PublishPositionRequest(::google::protobuf::Arena* arena, PublishPositionRequest&& from) noexcept + : PublishPositionRequest(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -8963,29 +9799,61 @@ class PublishPositionVelocityNedResponse final // accessors ------------------------------------------------------- enum : int { - kTelemetryServerResultFieldNumber = 1, + kPositionFieldNumber = 1, + kVelocityNedFieldNumber = 2, + kHeadingFieldNumber = 3, }; - // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - bool has_telemetry_server_result() const; - void clear_telemetry_server_result() ; - const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& telemetry_server_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::TelemetryServerResult* release_telemetry_server_result(); - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* mutable_telemetry_server_result(); - void set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); - void unsafe_arena_set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* unsafe_arena_release_telemetry_server_result(); + // .mavsdk.rpc.telemetry_server.Position position = 1; + bool has_position() const; + void clear_position() ; + const ::mavsdk::rpc::telemetry_server::Position& position() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::Position* release_position(); + ::mavsdk::rpc::telemetry_server::Position* mutable_position(); + void set_allocated_position(::mavsdk::rpc::telemetry_server::Position* value); + void unsafe_arena_set_allocated_position(::mavsdk::rpc::telemetry_server::Position* value); + ::mavsdk::rpc::telemetry_server::Position* unsafe_arena_release_position(); private: - const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& _internal_telemetry_server_result() const; - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); + const ::mavsdk::rpc::telemetry_server::Position& _internal_position() const; + ::mavsdk::rpc::telemetry_server::Position* _internal_mutable_position(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishPositionVelocityNedResponse) + // .mavsdk.rpc.telemetry_server.VelocityNed velocity_ned = 2; + bool has_velocity_ned() const; + void clear_velocity_ned() ; + const ::mavsdk::rpc::telemetry_server::VelocityNed& velocity_ned() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::VelocityNed* release_velocity_ned(); + ::mavsdk::rpc::telemetry_server::VelocityNed* mutable_velocity_ned(); + void set_allocated_velocity_ned(::mavsdk::rpc::telemetry_server::VelocityNed* value); + void unsafe_arena_set_allocated_velocity_ned(::mavsdk::rpc::telemetry_server::VelocityNed* value); + ::mavsdk::rpc::telemetry_server::VelocityNed* unsafe_arena_release_velocity_ned(); + + private: + const ::mavsdk::rpc::telemetry_server::VelocityNed& _internal_velocity_ned() const; + ::mavsdk::rpc::telemetry_server::VelocityNed* _internal_mutable_velocity_ned(); + + public: + // .mavsdk.rpc.telemetry_server.Heading heading = 3; + bool has_heading() const; + void clear_heading() ; + const ::mavsdk::rpc::telemetry_server::Heading& heading() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::Heading* release_heading(); + ::mavsdk::rpc::telemetry_server::Heading* mutable_heading(); + void set_allocated_heading(::mavsdk::rpc::telemetry_server::Heading* value); + void unsafe_arena_set_allocated_heading(::mavsdk::rpc::telemetry_server::Heading* value); + ::mavsdk::rpc::telemetry_server::Heading* unsafe_arena_release_heading(); + + private: + const ::mavsdk::rpc::telemetry_server::Heading& _internal_heading() const; + ::mavsdk::rpc::telemetry_server::Heading* _internal_mutable_heading(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishPositionRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 2, 3, 3, 0, 2> _table_; @@ -9002,10 +9870,12 @@ class PublishPositionVelocityNedResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishPositionVelocityNedResponse& from_msg); + const PublishPositionRequest& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; + ::mavsdk::rpc::telemetry_server::Position* position_; + ::mavsdk::rpc::telemetry_server::VelocityNed* velocity_ned_; + ::mavsdk::rpc::telemetry_server::Heading* heading_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -9013,32 +9883,32 @@ class PublishPositionVelocityNedResponse final }; // ------------------------------------------------------------------- -class PublishPositionResponse final +class PublishOdometryResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishPositionResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishOdometryResponse) */ { public: - inline PublishPositionResponse() : PublishPositionResponse(nullptr) {} - ~PublishPositionResponse() PROTOBUF_FINAL; + inline PublishOdometryResponse() : PublishOdometryResponse(nullptr) {} + ~PublishOdometryResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishPositionResponse* msg, std::destroying_delete_t) { + void operator delete(PublishOdometryResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishPositionResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishOdometryResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishPositionResponse( + explicit PROTOBUF_CONSTEXPR PublishOdometryResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishPositionResponse(const PublishPositionResponse& from) : PublishPositionResponse(nullptr, from) {} - inline PublishPositionResponse(PublishPositionResponse&& from) noexcept - : PublishPositionResponse(nullptr, std::move(from)) {} - inline PublishPositionResponse& operator=(const PublishPositionResponse& from) { + inline PublishOdometryResponse(const PublishOdometryResponse& from) : PublishOdometryResponse(nullptr, from) {} + inline PublishOdometryResponse(PublishOdometryResponse&& from) noexcept + : PublishOdometryResponse(nullptr, std::move(from)) {} + inline PublishOdometryResponse& operator=(const PublishOdometryResponse& from) { CopyFrom(from); return *this; } - inline PublishPositionResponse& operator=(PublishPositionResponse&& from) noexcept { + inline PublishOdometryResponse& operator=(PublishOdometryResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -9066,16 +9936,16 @@ class PublishPositionResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishPositionResponse& default_instance() { + static const PublishOdometryResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishPositionResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishPositionResponse_default_instance_); + static inline const PublishOdometryResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishOdometryResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 18; - friend void swap(PublishPositionResponse& a, PublishPositionResponse& b) { a.Swap(&b); } - inline void Swap(PublishPositionResponse* other) { + static constexpr int kIndexInFileMessages = 27; + friend void swap(PublishOdometryResponse& a, PublishOdometryResponse& b) { a.Swap(&b); } + inline void Swap(PublishOdometryResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -9083,7 +9953,7 @@ class PublishPositionResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishPositionResponse* other) { + void UnsafeArenaSwap(PublishOdometryResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9091,13 +9961,13 @@ class PublishPositionResponse final // implements Message ---------------------------------------------- - PublishPositionResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishOdometryResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishPositionResponse& from); + void CopyFrom(const PublishOdometryResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishPositionResponse& from) { PublishPositionResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishOdometryResponse& from) { PublishOdometryResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -9134,18 +10004,18 @@ class PublishPositionResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishPositionResponse* other); + void InternalSwap(PublishOdometryResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishPositionResponse"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishOdometryResponse"; } protected: - explicit PublishPositionResponse(::google::protobuf::Arena* arena); - PublishPositionResponse(::google::protobuf::Arena* arena, const PublishPositionResponse& from); - PublishPositionResponse(::google::protobuf::Arena* arena, PublishPositionResponse&& from) noexcept - : PublishPositionResponse(arena) { + explicit PublishOdometryResponse(::google::protobuf::Arena* arena); + PublishOdometryResponse(::google::protobuf::Arena* arena, const PublishOdometryResponse& from); + PublishOdometryResponse(::google::protobuf::Arena* arena, PublishOdometryResponse&& from) noexcept + : PublishOdometryResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -9177,7 +10047,7 @@ class PublishPositionResponse final ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishPositionResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishOdometryResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -9199,7 +10069,7 @@ class PublishPositionResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishPositionResponse& from_msg); + const PublishOdometryResponse& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; @@ -9210,32 +10080,32 @@ class PublishPositionResponse final }; // ------------------------------------------------------------------- -class PublishPositionRequest final +class PublishImuResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishPositionRequest) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishImuResponse) */ { public: - inline PublishPositionRequest() : PublishPositionRequest(nullptr) {} - ~PublishPositionRequest() PROTOBUF_FINAL; + inline PublishImuResponse() : PublishImuResponse(nullptr) {} + ~PublishImuResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishPositionRequest* msg, std::destroying_delete_t) { + void operator delete(PublishImuResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishPositionRequest)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishImuResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishPositionRequest( + explicit PROTOBUF_CONSTEXPR PublishImuResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishPositionRequest(const PublishPositionRequest& from) : PublishPositionRequest(nullptr, from) {} - inline PublishPositionRequest(PublishPositionRequest&& from) noexcept - : PublishPositionRequest(nullptr, std::move(from)) {} - inline PublishPositionRequest& operator=(const PublishPositionRequest& from) { + inline PublishImuResponse(const PublishImuResponse& from) : PublishImuResponse(nullptr, from) {} + inline PublishImuResponse(PublishImuResponse&& from) noexcept + : PublishImuResponse(nullptr, std::move(from)) {} + inline PublishImuResponse& operator=(const PublishImuResponse& from) { CopyFrom(from); return *this; } - inline PublishPositionRequest& operator=(PublishPositionRequest&& from) noexcept { + inline PublishImuResponse& operator=(PublishImuResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -9263,16 +10133,16 @@ class PublishPositionRequest final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishPositionRequest& default_instance() { + static const PublishImuResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishPositionRequest* internal_default_instance() { - return reinterpret_cast( - &_PublishPositionRequest_default_instance_); + static inline const PublishImuResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishImuResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 0; - friend void swap(PublishPositionRequest& a, PublishPositionRequest& b) { a.Swap(&b); } - inline void Swap(PublishPositionRequest* other) { + static constexpr int kIndexInFileMessages = 30; + friend void swap(PublishImuResponse& a, PublishImuResponse& b) { a.Swap(&b); } + inline void Swap(PublishImuResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -9280,7 +10150,7 @@ class PublishPositionRequest final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishPositionRequest* other) { + void UnsafeArenaSwap(PublishImuResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9288,13 +10158,13 @@ class PublishPositionRequest final // implements Message ---------------------------------------------- - PublishPositionRequest* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishImuResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishPositionRequest& from); + void CopyFrom(const PublishImuResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishPositionRequest& from) { PublishPositionRequest::MergeImpl(*this, from); } + void MergeFrom(const PublishImuResponse& from) { PublishImuResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -9331,18 +10201,18 @@ class PublishPositionRequest final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishPositionRequest* other); + void InternalSwap(PublishImuResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishPositionRequest"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishImuResponse"; } protected: - explicit PublishPositionRequest(::google::protobuf::Arena* arena); - PublishPositionRequest(::google::protobuf::Arena* arena, const PublishPositionRequest& from); - PublishPositionRequest(::google::protobuf::Arena* arena, PublishPositionRequest&& from) noexcept - : PublishPositionRequest(arena) { + explicit PublishImuResponse(::google::protobuf::Arena* arena); + PublishImuResponse(::google::protobuf::Arena* arena, const PublishImuResponse& from); + PublishImuResponse(::google::protobuf::Arena* arena, PublishImuResponse&& from) noexcept + : PublishImuResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -9357,61 +10227,29 @@ class PublishPositionRequest final // accessors ------------------------------------------------------- enum : int { - kPositionFieldNumber = 1, - kVelocityNedFieldNumber = 2, - kHeadingFieldNumber = 3, + kTelemetryServerResultFieldNumber = 1, }; - // .mavsdk.rpc.telemetry_server.Position position = 1; - bool has_position() const; - void clear_position() ; - const ::mavsdk::rpc::telemetry_server::Position& position() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::Position* release_position(); - ::mavsdk::rpc::telemetry_server::Position* mutable_position(); - void set_allocated_position(::mavsdk::rpc::telemetry_server::Position* value); - void unsafe_arena_set_allocated_position(::mavsdk::rpc::telemetry_server::Position* value); - ::mavsdk::rpc::telemetry_server::Position* unsafe_arena_release_position(); - - private: - const ::mavsdk::rpc::telemetry_server::Position& _internal_position() const; - ::mavsdk::rpc::telemetry_server::Position* _internal_mutable_position(); - - public: - // .mavsdk.rpc.telemetry_server.VelocityNed velocity_ned = 2; - bool has_velocity_ned() const; - void clear_velocity_ned() ; - const ::mavsdk::rpc::telemetry_server::VelocityNed& velocity_ned() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::VelocityNed* release_velocity_ned(); - ::mavsdk::rpc::telemetry_server::VelocityNed* mutable_velocity_ned(); - void set_allocated_velocity_ned(::mavsdk::rpc::telemetry_server::VelocityNed* value); - void unsafe_arena_set_allocated_velocity_ned(::mavsdk::rpc::telemetry_server::VelocityNed* value); - ::mavsdk::rpc::telemetry_server::VelocityNed* unsafe_arena_release_velocity_ned(); - - private: - const ::mavsdk::rpc::telemetry_server::VelocityNed& _internal_velocity_ned() const; - ::mavsdk::rpc::telemetry_server::VelocityNed* _internal_mutable_velocity_ned(); - - public: - // .mavsdk.rpc.telemetry_server.Heading heading = 3; - bool has_heading() const; - void clear_heading() ; - const ::mavsdk::rpc::telemetry_server::Heading& heading() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::Heading* release_heading(); - ::mavsdk::rpc::telemetry_server::Heading* mutable_heading(); - void set_allocated_heading(::mavsdk::rpc::telemetry_server::Heading* value); - void unsafe_arena_set_allocated_heading(::mavsdk::rpc::telemetry_server::Heading* value); - ::mavsdk::rpc::telemetry_server::Heading* unsafe_arena_release_heading(); + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + bool has_telemetry_server_result() const; + void clear_telemetry_server_result() ; + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& telemetry_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::TelemetryServerResult* release_telemetry_server_result(); + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* mutable_telemetry_server_result(); + void set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); + void unsafe_arena_set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* unsafe_arena_release_telemetry_server_result(); private: - const ::mavsdk::rpc::telemetry_server::Heading& _internal_heading() const; - ::mavsdk::rpc::telemetry_server::Heading* _internal_mutable_heading(); + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& _internal_telemetry_server_result() const; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishPositionRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishImuResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 3, + 0, 1, 1, 0, 2> _table_; @@ -9428,12 +10266,10 @@ class PublishPositionRequest final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishPositionRequest& from_msg); + const PublishImuResponse& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry_server::Position* position_; - ::mavsdk::rpc::telemetry_server::VelocityNed* velocity_ned_; - ::mavsdk::rpc::telemetry_server::Heading* heading_; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -9441,32 +10277,32 @@ class PublishPositionRequest final }; // ------------------------------------------------------------------- -class PublishOdometryResponse final +class PublishHomeResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishOdometryResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishHomeResponse) */ { public: - inline PublishOdometryResponse() : PublishOdometryResponse(nullptr) {} - ~PublishOdometryResponse() PROTOBUF_FINAL; + inline PublishHomeResponse() : PublishHomeResponse(nullptr) {} + ~PublishHomeResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishOdometryResponse* msg, std::destroying_delete_t) { + void operator delete(PublishHomeResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishOdometryResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishHomeResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishOdometryResponse( + explicit PROTOBUF_CONSTEXPR PublishHomeResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishOdometryResponse(const PublishOdometryResponse& from) : PublishOdometryResponse(nullptr, from) {} - inline PublishOdometryResponse(PublishOdometryResponse&& from) noexcept - : PublishOdometryResponse(nullptr, std::move(from)) {} - inline PublishOdometryResponse& operator=(const PublishOdometryResponse& from) { + inline PublishHomeResponse(const PublishHomeResponse& from) : PublishHomeResponse(nullptr, from) {} + inline PublishHomeResponse(PublishHomeResponse&& from) noexcept + : PublishHomeResponse(nullptr, std::move(from)) {} + inline PublishHomeResponse& operator=(const PublishHomeResponse& from) { CopyFrom(from); return *this; } - inline PublishOdometryResponse& operator=(PublishOdometryResponse&& from) noexcept { + inline PublishHomeResponse& operator=(PublishHomeResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -9494,16 +10330,16 @@ class PublishOdometryResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishOdometryResponse& default_instance() { + static const PublishHomeResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishOdometryResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishOdometryResponse_default_instance_); + static inline const PublishHomeResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishHomeResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 25; - friend void swap(PublishOdometryResponse& a, PublishOdometryResponse& b) { a.Swap(&b); } - inline void Swap(PublishOdometryResponse* other) { + static constexpr int kIndexInFileMessages = 21; + friend void swap(PublishHomeResponse& a, PublishHomeResponse& b) { a.Swap(&b); } + inline void Swap(PublishHomeResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -9511,7 +10347,7 @@ class PublishOdometryResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishOdometryResponse* other) { + void UnsafeArenaSwap(PublishHomeResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9519,13 +10355,13 @@ class PublishOdometryResponse final // implements Message ---------------------------------------------- - PublishOdometryResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishHomeResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishOdometryResponse& from); + void CopyFrom(const PublishHomeResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishOdometryResponse& from) { PublishOdometryResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishHomeResponse& from) { PublishHomeResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -9562,18 +10398,18 @@ class PublishOdometryResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishOdometryResponse* other); + void InternalSwap(PublishHomeResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishOdometryResponse"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishHomeResponse"; } protected: - explicit PublishOdometryResponse(::google::protobuf::Arena* arena); - PublishOdometryResponse(::google::protobuf::Arena* arena, const PublishOdometryResponse& from); - PublishOdometryResponse(::google::protobuf::Arena* arena, PublishOdometryResponse&& from) noexcept - : PublishOdometryResponse(arena) { + explicit PublishHomeResponse(::google::protobuf::Arena* arena); + PublishHomeResponse(::google::protobuf::Arena* arena, const PublishHomeResponse& from); + PublishHomeResponse(::google::protobuf::Arena* arena, PublishHomeResponse&& from) noexcept + : PublishHomeResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -9605,7 +10441,7 @@ class PublishOdometryResponse final ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishOdometryResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishHomeResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -9627,7 +10463,7 @@ class PublishOdometryResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishOdometryResponse& from_msg); + const PublishHomeResponse& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; @@ -9638,32 +10474,32 @@ class PublishOdometryResponse final }; // ------------------------------------------------------------------- -class PublishImuResponse final +class PublishHomeRequest final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishImuResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishHomeRequest) */ { public: - inline PublishImuResponse() : PublishImuResponse(nullptr) {} - ~PublishImuResponse() PROTOBUF_FINAL; + inline PublishHomeRequest() : PublishHomeRequest(nullptr) {} + ~PublishHomeRequest() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishImuResponse* msg, std::destroying_delete_t) { + void operator delete(PublishHomeRequest* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishImuResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishHomeRequest)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishImuResponse( + explicit PROTOBUF_CONSTEXPR PublishHomeRequest( ::google::protobuf::internal::ConstantInitialized); - inline PublishImuResponse(const PublishImuResponse& from) : PublishImuResponse(nullptr, from) {} - inline PublishImuResponse(PublishImuResponse&& from) noexcept - : PublishImuResponse(nullptr, std::move(from)) {} - inline PublishImuResponse& operator=(const PublishImuResponse& from) { + inline PublishHomeRequest(const PublishHomeRequest& from) : PublishHomeRequest(nullptr, from) {} + inline PublishHomeRequest(PublishHomeRequest&& from) noexcept + : PublishHomeRequest(nullptr, std::move(from)) {} + inline PublishHomeRequest& operator=(const PublishHomeRequest& from) { CopyFrom(from); return *this; } - inline PublishImuResponse& operator=(PublishImuResponse&& from) noexcept { + inline PublishHomeRequest& operator=(PublishHomeRequest&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -9691,16 +10527,16 @@ class PublishImuResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishImuResponse& default_instance() { + static const PublishHomeRequest& default_instance() { return *internal_default_instance(); } - static inline const PublishImuResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishImuResponse_default_instance_); + static inline const PublishHomeRequest* internal_default_instance() { + return reinterpret_cast( + &_PublishHomeRequest_default_instance_); } - static constexpr int kIndexInFileMessages = 28; - friend void swap(PublishImuResponse& a, PublishImuResponse& b) { a.Swap(&b); } - inline void Swap(PublishImuResponse* other) { + static constexpr int kIndexInFileMessages = 1; + friend void swap(PublishHomeRequest& a, PublishHomeRequest& b) { a.Swap(&b); } + inline void Swap(PublishHomeRequest* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -9708,7 +10544,7 @@ class PublishImuResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishImuResponse* other) { + void UnsafeArenaSwap(PublishHomeRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9716,13 +10552,13 @@ class PublishImuResponse final // implements Message ---------------------------------------------- - PublishImuResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishHomeRequest* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishImuResponse& from); + void CopyFrom(const PublishHomeRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishImuResponse& from) { PublishImuResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishHomeRequest& from) { PublishHomeRequest::MergeImpl(*this, from); } private: static void MergeImpl( @@ -9759,18 +10595,18 @@ class PublishImuResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishImuResponse* other); + void InternalSwap(PublishHomeRequest* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishImuResponse"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishHomeRequest"; } protected: - explicit PublishImuResponse(::google::protobuf::Arena* arena); - PublishImuResponse(::google::protobuf::Arena* arena, const PublishImuResponse& from); - PublishImuResponse(::google::protobuf::Arena* arena, PublishImuResponse&& from) noexcept - : PublishImuResponse(arena) { + explicit PublishHomeRequest(::google::protobuf::Arena* arena); + PublishHomeRequest(::google::protobuf::Arena* arena, const PublishHomeRequest& from); + PublishHomeRequest(::google::protobuf::Arena* arena, PublishHomeRequest&& from) noexcept + : PublishHomeRequest(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -9785,24 +10621,24 @@ class PublishImuResponse final // accessors ------------------------------------------------------- enum : int { - kTelemetryServerResultFieldNumber = 1, + kHomeFieldNumber = 1, }; - // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - bool has_telemetry_server_result() const; - void clear_telemetry_server_result() ; - const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& telemetry_server_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::TelemetryServerResult* release_telemetry_server_result(); - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* mutable_telemetry_server_result(); - void set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); - void unsafe_arena_set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* unsafe_arena_release_telemetry_server_result(); + // .mavsdk.rpc.telemetry_server.Position home = 1; + bool has_home() const; + void clear_home() ; + const ::mavsdk::rpc::telemetry_server::Position& home() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::Position* release_home(); + ::mavsdk::rpc::telemetry_server::Position* mutable_home(); + void set_allocated_home(::mavsdk::rpc::telemetry_server::Position* value); + void unsafe_arena_set_allocated_home(::mavsdk::rpc::telemetry_server::Position* value); + ::mavsdk::rpc::telemetry_server::Position* unsafe_arena_release_home(); private: - const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& _internal_telemetry_server_result() const; - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); + const ::mavsdk::rpc::telemetry_server::Position& _internal_home() const; + ::mavsdk::rpc::telemetry_server::Position* _internal_mutable_home(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishImuResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishHomeRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -9824,10 +10660,10 @@ class PublishImuResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishImuResponse& from_msg); + const PublishHomeRequest& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; + ::mavsdk::rpc::telemetry_server::Position* home_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -9835,32 +10671,32 @@ class PublishImuResponse final }; // ------------------------------------------------------------------- -class PublishHomeResponse final +class PublishGroundTruthResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishHomeResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) */ { public: - inline PublishHomeResponse() : PublishHomeResponse(nullptr) {} - ~PublishHomeResponse() PROTOBUF_FINAL; + inline PublishGroundTruthResponse() : PublishGroundTruthResponse(nullptr) {} + ~PublishGroundTruthResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishHomeResponse* msg, std::destroying_delete_t) { + void operator delete(PublishGroundTruthResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishHomeResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishGroundTruthResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishHomeResponse( + explicit PROTOBUF_CONSTEXPR PublishGroundTruthResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishHomeResponse(const PublishHomeResponse& from) : PublishHomeResponse(nullptr, from) {} - inline PublishHomeResponse(PublishHomeResponse&& from) noexcept - : PublishHomeResponse(nullptr, std::move(from)) {} - inline PublishHomeResponse& operator=(const PublishHomeResponse& from) { + inline PublishGroundTruthResponse(const PublishGroundTruthResponse& from) : PublishGroundTruthResponse(nullptr, from) {} + inline PublishGroundTruthResponse(PublishGroundTruthResponse&& from) noexcept + : PublishGroundTruthResponse(nullptr, std::move(from)) {} + inline PublishGroundTruthResponse& operator=(const PublishGroundTruthResponse& from) { CopyFrom(from); return *this; } - inline PublishHomeResponse& operator=(PublishHomeResponse&& from) noexcept { + inline PublishGroundTruthResponse& operator=(PublishGroundTruthResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -9888,16 +10724,16 @@ class PublishHomeResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishHomeResponse& default_instance() { + static const PublishGroundTruthResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishHomeResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishHomeResponse_default_instance_); + static inline const PublishGroundTruthResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishGroundTruthResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 19; - friend void swap(PublishHomeResponse& a, PublishHomeResponse& b) { a.Swap(&b); } - inline void Swap(PublishHomeResponse* other) { + static constexpr int kIndexInFileMessages = 29; + friend void swap(PublishGroundTruthResponse& a, PublishGroundTruthResponse& b) { a.Swap(&b); } + inline void Swap(PublishGroundTruthResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -9905,7 +10741,7 @@ class PublishHomeResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishHomeResponse* other) { + void UnsafeArenaSwap(PublishGroundTruthResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -9913,13 +10749,13 @@ class PublishHomeResponse final // implements Message ---------------------------------------------- - PublishHomeResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishGroundTruthResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishHomeResponse& from); + void CopyFrom(const PublishGroundTruthResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishHomeResponse& from) { PublishHomeResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishGroundTruthResponse& from) { PublishGroundTruthResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -9956,18 +10792,18 @@ class PublishHomeResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishHomeResponse* other); + void InternalSwap(PublishGroundTruthResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishHomeResponse"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishGroundTruthResponse"; } protected: - explicit PublishHomeResponse(::google::protobuf::Arena* arena); - PublishHomeResponse(::google::protobuf::Arena* arena, const PublishHomeResponse& from); - PublishHomeResponse(::google::protobuf::Arena* arena, PublishHomeResponse&& from) noexcept - : PublishHomeResponse(arena) { + explicit PublishGroundTruthResponse(::google::protobuf::Arena* arena); + PublishGroundTruthResponse(::google::protobuf::Arena* arena, const PublishGroundTruthResponse& from); + PublishGroundTruthResponse(::google::protobuf::Arena* arena, PublishGroundTruthResponse&& from) noexcept + : PublishGroundTruthResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -9999,7 +10835,7 @@ class PublishHomeResponse final ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishHomeResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -10021,7 +10857,7 @@ class PublishHomeResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishHomeResponse& from_msg); + const PublishGroundTruthResponse& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; @@ -10032,32 +10868,32 @@ class PublishHomeResponse final }; // ------------------------------------------------------------------- -class PublishHomeRequest final +class PublishGroundTruthRequest final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishHomeRequest) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishGroundTruthRequest) */ { public: - inline PublishHomeRequest() : PublishHomeRequest(nullptr) {} - ~PublishHomeRequest() PROTOBUF_FINAL; + inline PublishGroundTruthRequest() : PublishGroundTruthRequest(nullptr) {} + ~PublishGroundTruthRequest() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishHomeRequest* msg, std::destroying_delete_t) { + void operator delete(PublishGroundTruthRequest* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishHomeRequest)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishGroundTruthRequest)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishHomeRequest( + explicit PROTOBUF_CONSTEXPR PublishGroundTruthRequest( ::google::protobuf::internal::ConstantInitialized); - inline PublishHomeRequest(const PublishHomeRequest& from) : PublishHomeRequest(nullptr, from) {} - inline PublishHomeRequest(PublishHomeRequest&& from) noexcept - : PublishHomeRequest(nullptr, std::move(from)) {} - inline PublishHomeRequest& operator=(const PublishHomeRequest& from) { + inline PublishGroundTruthRequest(const PublishGroundTruthRequest& from) : PublishGroundTruthRequest(nullptr, from) {} + inline PublishGroundTruthRequest(PublishGroundTruthRequest&& from) noexcept + : PublishGroundTruthRequest(nullptr, std::move(from)) {} + inline PublishGroundTruthRequest& operator=(const PublishGroundTruthRequest& from) { CopyFrom(from); return *this; } - inline PublishHomeRequest& operator=(PublishHomeRequest&& from) noexcept { + inline PublishGroundTruthRequest& operator=(PublishGroundTruthRequest&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -10085,16 +10921,16 @@ class PublishHomeRequest final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishHomeRequest& default_instance() { + static const PublishGroundTruthRequest& default_instance() { return *internal_default_instance(); } - static inline const PublishHomeRequest* internal_default_instance() { - return reinterpret_cast( - &_PublishHomeRequest_default_instance_); + static inline const PublishGroundTruthRequest* internal_default_instance() { + return reinterpret_cast( + &_PublishGroundTruthRequest_default_instance_); } - static constexpr int kIndexInFileMessages = 1; - friend void swap(PublishHomeRequest& a, PublishHomeRequest& b) { a.Swap(&b); } - inline void Swap(PublishHomeRequest* other) { + static constexpr int kIndexInFileMessages = 12; + friend void swap(PublishGroundTruthRequest& a, PublishGroundTruthRequest& b) { a.Swap(&b); } + inline void Swap(PublishGroundTruthRequest* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -10102,7 +10938,7 @@ class PublishHomeRequest final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishHomeRequest* other) { + void UnsafeArenaSwap(PublishGroundTruthRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -10110,13 +10946,13 @@ class PublishHomeRequest final // implements Message ---------------------------------------------- - PublishHomeRequest* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishGroundTruthRequest* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishHomeRequest& from); + void CopyFrom(const PublishGroundTruthRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishHomeRequest& from) { PublishHomeRequest::MergeImpl(*this, from); } + void MergeFrom(const PublishGroundTruthRequest& from) { PublishGroundTruthRequest::MergeImpl(*this, from); } private: static void MergeImpl( @@ -10153,18 +10989,18 @@ class PublishHomeRequest final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishHomeRequest* other); + void InternalSwap(PublishGroundTruthRequest* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishHomeRequest"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishGroundTruthRequest"; } protected: - explicit PublishHomeRequest(::google::protobuf::Arena* arena); - PublishHomeRequest(::google::protobuf::Arena* arena, const PublishHomeRequest& from); - PublishHomeRequest(::google::protobuf::Arena* arena, PublishHomeRequest&& from) noexcept - : PublishHomeRequest(arena) { + explicit PublishGroundTruthRequest(::google::protobuf::Arena* arena); + PublishGroundTruthRequest(::google::protobuf::Arena* arena, const PublishGroundTruthRequest& from); + PublishGroundTruthRequest(::google::protobuf::Arena* arena, PublishGroundTruthRequest&& from) noexcept + : PublishGroundTruthRequest(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -10179,24 +11015,24 @@ class PublishHomeRequest final // accessors ------------------------------------------------------- enum : int { - kHomeFieldNumber = 1, + kGroundTruthFieldNumber = 1, }; - // .mavsdk.rpc.telemetry_server.Position home = 1; - bool has_home() const; - void clear_home() ; - const ::mavsdk::rpc::telemetry_server::Position& home() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::Position* release_home(); - ::mavsdk::rpc::telemetry_server::Position* mutable_home(); - void set_allocated_home(::mavsdk::rpc::telemetry_server::Position* value); - void unsafe_arena_set_allocated_home(::mavsdk::rpc::telemetry_server::Position* value); - ::mavsdk::rpc::telemetry_server::Position* unsafe_arena_release_home(); + // .mavsdk.rpc.telemetry_server.GroundTruth ground_truth = 1; + bool has_ground_truth() const; + void clear_ground_truth() ; + const ::mavsdk::rpc::telemetry_server::GroundTruth& ground_truth() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::GroundTruth* release_ground_truth(); + ::mavsdk::rpc::telemetry_server::GroundTruth* mutable_ground_truth(); + void set_allocated_ground_truth(::mavsdk::rpc::telemetry_server::GroundTruth* value); + void unsafe_arena_set_allocated_ground_truth(::mavsdk::rpc::telemetry_server::GroundTruth* value); + ::mavsdk::rpc::telemetry_server::GroundTruth* unsafe_arena_release_ground_truth(); private: - const ::mavsdk::rpc::telemetry_server::Position& _internal_home() const; - ::mavsdk::rpc::telemetry_server::Position* _internal_mutable_home(); + const ::mavsdk::rpc::telemetry_server::GroundTruth& _internal_ground_truth() const; + ::mavsdk::rpc::telemetry_server::GroundTruth* _internal_mutable_ground_truth(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishHomeRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishGroundTruthRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -10218,10 +11054,10 @@ class PublishHomeRequest final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishHomeRequest& from_msg); + const PublishGroundTruthRequest& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry_server::Position* home_; + ::mavsdk::rpc::telemetry_server::GroundTruth* ground_truth_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -10229,32 +11065,32 @@ class PublishHomeRequest final }; // ------------------------------------------------------------------- -class PublishGroundTruthResponse final +class PublishExtendedSysStateResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) */ { public: - inline PublishGroundTruthResponse() : PublishGroundTruthResponse(nullptr) {} - ~PublishGroundTruthResponse() PROTOBUF_FINAL; + inline PublishExtendedSysStateResponse() : PublishExtendedSysStateResponse(nullptr) {} + ~PublishExtendedSysStateResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishGroundTruthResponse* msg, std::destroying_delete_t) { + void operator delete(PublishExtendedSysStateResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishGroundTruthResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishExtendedSysStateResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishGroundTruthResponse( + explicit PROTOBUF_CONSTEXPR PublishExtendedSysStateResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishGroundTruthResponse(const PublishGroundTruthResponse& from) : PublishGroundTruthResponse(nullptr, from) {} - inline PublishGroundTruthResponse(PublishGroundTruthResponse&& from) noexcept - : PublishGroundTruthResponse(nullptr, std::move(from)) {} - inline PublishGroundTruthResponse& operator=(const PublishGroundTruthResponse& from) { + inline PublishExtendedSysStateResponse(const PublishExtendedSysStateResponse& from) : PublishExtendedSysStateResponse(nullptr, from) {} + inline PublishExtendedSysStateResponse(PublishExtendedSysStateResponse&& from) noexcept + : PublishExtendedSysStateResponse(nullptr, std::move(from)) {} + inline PublishExtendedSysStateResponse& operator=(const PublishExtendedSysStateResponse& from) { CopyFrom(from); return *this; } - inline PublishGroundTruthResponse& operator=(PublishGroundTruthResponse&& from) noexcept { + inline PublishExtendedSysStateResponse& operator=(PublishExtendedSysStateResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -10282,16 +11118,16 @@ class PublishGroundTruthResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishGroundTruthResponse& default_instance() { + static const PublishExtendedSysStateResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishGroundTruthResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishGroundTruthResponse_default_instance_); + static inline const PublishExtendedSysStateResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishExtendedSysStateResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 27; - friend void swap(PublishGroundTruthResponse& a, PublishGroundTruthResponse& b) { a.Swap(&b); } - inline void Swap(PublishGroundTruthResponse* other) { + static constexpr int kIndexInFileMessages = 23; + friend void swap(PublishExtendedSysStateResponse& a, PublishExtendedSysStateResponse& b) { a.Swap(&b); } + inline void Swap(PublishExtendedSysStateResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -10299,7 +11135,7 @@ class PublishGroundTruthResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishGroundTruthResponse* other) { + void UnsafeArenaSwap(PublishExtendedSysStateResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -10307,13 +11143,13 @@ class PublishGroundTruthResponse final // implements Message ---------------------------------------------- - PublishGroundTruthResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishExtendedSysStateResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishGroundTruthResponse& from); + void CopyFrom(const PublishExtendedSysStateResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishGroundTruthResponse& from) { PublishGroundTruthResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishExtendedSysStateResponse& from) { PublishExtendedSysStateResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -10350,18 +11186,18 @@ class PublishGroundTruthResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishGroundTruthResponse* other); + void InternalSwap(PublishExtendedSysStateResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishGroundTruthResponse"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse"; } protected: - explicit PublishGroundTruthResponse(::google::protobuf::Arena* arena); - PublishGroundTruthResponse(::google::protobuf::Arena* arena, const PublishGroundTruthResponse& from); - PublishGroundTruthResponse(::google::protobuf::Arena* arena, PublishGroundTruthResponse&& from) noexcept - : PublishGroundTruthResponse(arena) { + explicit PublishExtendedSysStateResponse(::google::protobuf::Arena* arena); + PublishExtendedSysStateResponse(::google::protobuf::Arena* arena, const PublishExtendedSysStateResponse& from); + PublishExtendedSysStateResponse(::google::protobuf::Arena* arena, PublishExtendedSysStateResponse&& from) noexcept + : PublishExtendedSysStateResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -10393,7 +11229,7 @@ class PublishGroundTruthResponse final ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishGroundTruthResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -10415,7 +11251,7 @@ class PublishGroundTruthResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishGroundTruthResponse& from_msg); + const PublishExtendedSysStateResponse& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; @@ -10426,32 +11262,32 @@ class PublishGroundTruthResponse final }; // ------------------------------------------------------------------- -class PublishGroundTruthRequest final +class PublishDistanceSensorResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishGroundTruthRequest) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) */ { public: - inline PublishGroundTruthRequest() : PublishGroundTruthRequest(nullptr) {} - ~PublishGroundTruthRequest() PROTOBUF_FINAL; + inline PublishDistanceSensorResponse() : PublishDistanceSensorResponse(nullptr) {} + ~PublishDistanceSensorResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishGroundTruthRequest* msg, std::destroying_delete_t) { + void operator delete(PublishDistanceSensorResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishGroundTruthRequest)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishDistanceSensorResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishGroundTruthRequest( + explicit PROTOBUF_CONSTEXPR PublishDistanceSensorResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishGroundTruthRequest(const PublishGroundTruthRequest& from) : PublishGroundTruthRequest(nullptr, from) {} - inline PublishGroundTruthRequest(PublishGroundTruthRequest&& from) noexcept - : PublishGroundTruthRequest(nullptr, std::move(from)) {} - inline PublishGroundTruthRequest& operator=(const PublishGroundTruthRequest& from) { + inline PublishDistanceSensorResponse(const PublishDistanceSensorResponse& from) : PublishDistanceSensorResponse(nullptr, from) {} + inline PublishDistanceSensorResponse(PublishDistanceSensorResponse&& from) noexcept + : PublishDistanceSensorResponse(nullptr, std::move(from)) {} + inline PublishDistanceSensorResponse& operator=(const PublishDistanceSensorResponse& from) { CopyFrom(from); return *this; } - inline PublishGroundTruthRequest& operator=(PublishGroundTruthRequest&& from) noexcept { + inline PublishDistanceSensorResponse& operator=(PublishDistanceSensorResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -10479,16 +11315,16 @@ class PublishGroundTruthRequest final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishGroundTruthRequest& default_instance() { + static const PublishDistanceSensorResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishGroundTruthRequest* internal_default_instance() { - return reinterpret_cast( - &_PublishGroundTruthRequest_default_instance_); + static inline const PublishDistanceSensorResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishDistanceSensorResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 12; - friend void swap(PublishGroundTruthRequest& a, PublishGroundTruthRequest& b) { a.Swap(&b); } - inline void Swap(PublishGroundTruthRequest* other) { + static constexpr int kIndexInFileMessages = 34; + friend void swap(PublishDistanceSensorResponse& a, PublishDistanceSensorResponse& b) { a.Swap(&b); } + inline void Swap(PublishDistanceSensorResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -10496,7 +11332,7 @@ class PublishGroundTruthRequest final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishGroundTruthRequest* other) { + void UnsafeArenaSwap(PublishDistanceSensorResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -10504,13 +11340,13 @@ class PublishGroundTruthRequest final // implements Message ---------------------------------------------- - PublishGroundTruthRequest* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishDistanceSensorResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishGroundTruthRequest& from); + void CopyFrom(const PublishDistanceSensorResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishGroundTruthRequest& from) { PublishGroundTruthRequest::MergeImpl(*this, from); } + void MergeFrom(const PublishDistanceSensorResponse& from) { PublishDistanceSensorResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -10547,18 +11383,18 @@ class PublishGroundTruthRequest final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishGroundTruthRequest* other); + void InternalSwap(PublishDistanceSensorResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishGroundTruthRequest"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse"; } protected: - explicit PublishGroundTruthRequest(::google::protobuf::Arena* arena); - PublishGroundTruthRequest(::google::protobuf::Arena* arena, const PublishGroundTruthRequest& from); - PublishGroundTruthRequest(::google::protobuf::Arena* arena, PublishGroundTruthRequest&& from) noexcept - : PublishGroundTruthRequest(arena) { + explicit PublishDistanceSensorResponse(::google::protobuf::Arena* arena); + PublishDistanceSensorResponse(::google::protobuf::Arena* arena, const PublishDistanceSensorResponse& from); + PublishDistanceSensorResponse(::google::protobuf::Arena* arena, PublishDistanceSensorResponse&& from) noexcept + : PublishDistanceSensorResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -10573,24 +11409,24 @@ class PublishGroundTruthRequest final // accessors ------------------------------------------------------- enum : int { - kGroundTruthFieldNumber = 1, + kTelemetryServerResultFieldNumber = 1, }; - // .mavsdk.rpc.telemetry_server.GroundTruth ground_truth = 1; - bool has_ground_truth() const; - void clear_ground_truth() ; - const ::mavsdk::rpc::telemetry_server::GroundTruth& ground_truth() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::GroundTruth* release_ground_truth(); - ::mavsdk::rpc::telemetry_server::GroundTruth* mutable_ground_truth(); - void set_allocated_ground_truth(::mavsdk::rpc::telemetry_server::GroundTruth* value); - void unsafe_arena_set_allocated_ground_truth(::mavsdk::rpc::telemetry_server::GroundTruth* value); - ::mavsdk::rpc::telemetry_server::GroundTruth* unsafe_arena_release_ground_truth(); + // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; + bool has_telemetry_server_result() const; + void clear_telemetry_server_result() ; + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& telemetry_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::TelemetryServerResult* release_telemetry_server_result(); + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* mutable_telemetry_server_result(); + void set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); + void unsafe_arena_set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* unsafe_arena_release_telemetry_server_result(); private: - const ::mavsdk::rpc::telemetry_server::GroundTruth& _internal_ground_truth() const; - ::mavsdk::rpc::telemetry_server::GroundTruth* _internal_mutable_ground_truth(); + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& _internal_telemetry_server_result() const; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishGroundTruthRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -10612,10 +11448,10 @@ class PublishGroundTruthRequest final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishGroundTruthRequest& from_msg); + const PublishDistanceSensorResponse& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry_server::GroundTruth* ground_truth_; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -10623,32 +11459,32 @@ class PublishGroundTruthRequest final }; // ------------------------------------------------------------------- -class PublishExtendedSysStateResponse final +class PublishDistanceSensorRequest final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest) */ { public: - inline PublishExtendedSysStateResponse() : PublishExtendedSysStateResponse(nullptr) {} - ~PublishExtendedSysStateResponse() PROTOBUF_FINAL; + inline PublishDistanceSensorRequest() : PublishDistanceSensorRequest(nullptr) {} + ~PublishDistanceSensorRequest() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishExtendedSysStateResponse* msg, std::destroying_delete_t) { + void operator delete(PublishDistanceSensorRequest* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishExtendedSysStateResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishDistanceSensorRequest)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishExtendedSysStateResponse( + explicit PROTOBUF_CONSTEXPR PublishDistanceSensorRequest( ::google::protobuf::internal::ConstantInitialized); - inline PublishExtendedSysStateResponse(const PublishExtendedSysStateResponse& from) : PublishExtendedSysStateResponse(nullptr, from) {} - inline PublishExtendedSysStateResponse(PublishExtendedSysStateResponse&& from) noexcept - : PublishExtendedSysStateResponse(nullptr, std::move(from)) {} - inline PublishExtendedSysStateResponse& operator=(const PublishExtendedSysStateResponse& from) { + inline PublishDistanceSensorRequest(const PublishDistanceSensorRequest& from) : PublishDistanceSensorRequest(nullptr, from) {} + inline PublishDistanceSensorRequest(PublishDistanceSensorRequest&& from) noexcept + : PublishDistanceSensorRequest(nullptr, std::move(from)) {} + inline PublishDistanceSensorRequest& operator=(const PublishDistanceSensorRequest& from) { CopyFrom(from); return *this; } - inline PublishExtendedSysStateResponse& operator=(PublishExtendedSysStateResponse&& from) noexcept { + inline PublishDistanceSensorRequest& operator=(PublishDistanceSensorRequest&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -10676,16 +11512,16 @@ class PublishExtendedSysStateResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishExtendedSysStateResponse& default_instance() { + static const PublishDistanceSensorRequest& default_instance() { return *internal_default_instance(); } - static inline const PublishExtendedSysStateResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishExtendedSysStateResponse_default_instance_); + static inline const PublishDistanceSensorRequest* internal_default_instance() { + return reinterpret_cast( + &_PublishDistanceSensorRequest_default_instance_); } - static constexpr int kIndexInFileMessages = 21; - friend void swap(PublishExtendedSysStateResponse& a, PublishExtendedSysStateResponse& b) { a.Swap(&b); } - inline void Swap(PublishExtendedSysStateResponse* other) { + static constexpr int kIndexInFileMessages = 17; + friend void swap(PublishDistanceSensorRequest& a, PublishDistanceSensorRequest& b) { a.Swap(&b); } + inline void Swap(PublishDistanceSensorRequest* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -10693,21 +11529,21 @@ class PublishExtendedSysStateResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishExtendedSysStateResponse* other) { + void UnsafeArenaSwap(PublishDistanceSensorRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); } // implements Message ---------------------------------------------- - - PublishExtendedSysStateResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + + PublishDistanceSensorRequest* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishExtendedSysStateResponse& from); + void CopyFrom(const PublishDistanceSensorRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishExtendedSysStateResponse& from) { PublishExtendedSysStateResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishDistanceSensorRequest& from) { PublishDistanceSensorRequest::MergeImpl(*this, from); } private: static void MergeImpl( @@ -10744,18 +11580,18 @@ class PublishExtendedSysStateResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishExtendedSysStateResponse* other); + void InternalSwap(PublishDistanceSensorRequest* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest"; } protected: - explicit PublishExtendedSysStateResponse(::google::protobuf::Arena* arena); - PublishExtendedSysStateResponse(::google::protobuf::Arena* arena, const PublishExtendedSysStateResponse& from); - PublishExtendedSysStateResponse(::google::protobuf::Arena* arena, PublishExtendedSysStateResponse&& from) noexcept - : PublishExtendedSysStateResponse(arena) { + explicit PublishDistanceSensorRequest(::google::protobuf::Arena* arena); + PublishDistanceSensorRequest(::google::protobuf::Arena* arena, const PublishDistanceSensorRequest& from); + PublishDistanceSensorRequest(::google::protobuf::Arena* arena, PublishDistanceSensorRequest&& from) noexcept + : PublishDistanceSensorRequest(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -10770,24 +11606,24 @@ class PublishExtendedSysStateResponse final // accessors ------------------------------------------------------- enum : int { - kTelemetryServerResultFieldNumber = 1, + kDistanceSensorFieldNumber = 1, }; - // .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; - bool has_telemetry_server_result() const; - void clear_telemetry_server_result() ; - const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& telemetry_server_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::TelemetryServerResult* release_telemetry_server_result(); - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* mutable_telemetry_server_result(); - void set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); - void unsafe_arena_set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value); - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* unsafe_arena_release_telemetry_server_result(); + // .mavsdk.rpc.telemetry_server.DistanceSensor distance_sensor = 1; + bool has_distance_sensor() const; + void clear_distance_sensor() ; + const ::mavsdk::rpc::telemetry_server::DistanceSensor& distance_sensor() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::DistanceSensor* release_distance_sensor(); + ::mavsdk::rpc::telemetry_server::DistanceSensor* mutable_distance_sensor(); + void set_allocated_distance_sensor(::mavsdk::rpc::telemetry_server::DistanceSensor* value); + void unsafe_arena_set_allocated_distance_sensor(::mavsdk::rpc::telemetry_server::DistanceSensor* value); + ::mavsdk::rpc::telemetry_server::DistanceSensor* unsafe_arena_release_distance_sensor(); private: - const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& _internal_telemetry_server_result() const; - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); + const ::mavsdk::rpc::telemetry_server::DistanceSensor& _internal_distance_sensor() const; + ::mavsdk::rpc::telemetry_server::DistanceSensor* _internal_mutable_distance_sensor(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishExtendedSysStateResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -10809,10 +11645,10 @@ class PublishExtendedSysStateResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishExtendedSysStateResponse& from_msg); + const PublishDistanceSensorRequest& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; + ::mavsdk::rpc::telemetry_server::DistanceSensor* distance_sensor_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -10820,32 +11656,32 @@ class PublishExtendedSysStateResponse final }; // ------------------------------------------------------------------- -class PublishDistanceSensorResponse final +class PublishBatteryResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishBatteryResponse) */ { public: - inline PublishDistanceSensorResponse() : PublishDistanceSensorResponse(nullptr) {} - ~PublishDistanceSensorResponse() PROTOBUF_FINAL; + inline PublishBatteryResponse() : PublishBatteryResponse(nullptr) {} + ~PublishBatteryResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishDistanceSensorResponse* msg, std::destroying_delete_t) { + void operator delete(PublishBatteryResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishDistanceSensorResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishBatteryResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishDistanceSensorResponse( + explicit PROTOBUF_CONSTEXPR PublishBatteryResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishDistanceSensorResponse(const PublishDistanceSensorResponse& from) : PublishDistanceSensorResponse(nullptr, from) {} - inline PublishDistanceSensorResponse(PublishDistanceSensorResponse&& from) noexcept - : PublishDistanceSensorResponse(nullptr, std::move(from)) {} - inline PublishDistanceSensorResponse& operator=(const PublishDistanceSensorResponse& from) { + inline PublishBatteryResponse(const PublishBatteryResponse& from) : PublishBatteryResponse(nullptr, from) {} + inline PublishBatteryResponse(PublishBatteryResponse&& from) noexcept + : PublishBatteryResponse(nullptr, std::move(from)) {} + inline PublishBatteryResponse& operator=(const PublishBatteryResponse& from) { CopyFrom(from); return *this; } - inline PublishDistanceSensorResponse& operator=(PublishDistanceSensorResponse&& from) noexcept { + inline PublishBatteryResponse& operator=(PublishBatteryResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -10873,16 +11709,16 @@ class PublishDistanceSensorResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishDistanceSensorResponse& default_instance() { + static const PublishBatteryResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishDistanceSensorResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishDistanceSensorResponse_default_instance_); + static inline const PublishBatteryResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishBatteryResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 32; - friend void swap(PublishDistanceSensorResponse& a, PublishDistanceSensorResponse& b) { a.Swap(&b); } - inline void Swap(PublishDistanceSensorResponse* other) { + static constexpr int kIndexInFileMessages = 25; + friend void swap(PublishBatteryResponse& a, PublishBatteryResponse& b) { a.Swap(&b); } + inline void Swap(PublishBatteryResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -10890,7 +11726,7 @@ class PublishDistanceSensorResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishDistanceSensorResponse* other) { + void UnsafeArenaSwap(PublishBatteryResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -10898,13 +11734,13 @@ class PublishDistanceSensorResponse final // implements Message ---------------------------------------------- - PublishDistanceSensorResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishBatteryResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishDistanceSensorResponse& from); + void CopyFrom(const PublishBatteryResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishDistanceSensorResponse& from) { PublishDistanceSensorResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishBatteryResponse& from) { PublishBatteryResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -10941,18 +11777,18 @@ class PublishDistanceSensorResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishDistanceSensorResponse* other); + void InternalSwap(PublishBatteryResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishBatteryResponse"; } protected: - explicit PublishDistanceSensorResponse(::google::protobuf::Arena* arena); - PublishDistanceSensorResponse(::google::protobuf::Arena* arena, const PublishDistanceSensorResponse& from); - PublishDistanceSensorResponse(::google::protobuf::Arena* arena, PublishDistanceSensorResponse&& from) noexcept - : PublishDistanceSensorResponse(arena) { + explicit PublishBatteryResponse(::google::protobuf::Arena* arena); + PublishBatteryResponse(::google::protobuf::Arena* arena, const PublishBatteryResponse& from); + PublishBatteryResponse(::google::protobuf::Arena* arena, PublishBatteryResponse&& from) noexcept + : PublishBatteryResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -10984,7 +11820,7 @@ class PublishDistanceSensorResponse final ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishDistanceSensorResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishBatteryResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -11006,7 +11842,7 @@ class PublishDistanceSensorResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishDistanceSensorResponse& from_msg); + const PublishBatteryResponse& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; @@ -11017,32 +11853,32 @@ class PublishDistanceSensorResponse final }; // ------------------------------------------------------------------- -class PublishDistanceSensorRequest final +class PublishBatteryRequest final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishBatteryRequest) */ { public: - inline PublishDistanceSensorRequest() : PublishDistanceSensorRequest(nullptr) {} - ~PublishDistanceSensorRequest() PROTOBUF_FINAL; + inline PublishBatteryRequest() : PublishBatteryRequest(nullptr) {} + ~PublishBatteryRequest() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishDistanceSensorRequest* msg, std::destroying_delete_t) { + void operator delete(PublishBatteryRequest* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishDistanceSensorRequest)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishBatteryRequest)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishDistanceSensorRequest( + explicit PROTOBUF_CONSTEXPR PublishBatteryRequest( ::google::protobuf::internal::ConstantInitialized); - inline PublishDistanceSensorRequest(const PublishDistanceSensorRequest& from) : PublishDistanceSensorRequest(nullptr, from) {} - inline PublishDistanceSensorRequest(PublishDistanceSensorRequest&& from) noexcept - : PublishDistanceSensorRequest(nullptr, std::move(from)) {} - inline PublishDistanceSensorRequest& operator=(const PublishDistanceSensorRequest& from) { + inline PublishBatteryRequest(const PublishBatteryRequest& from) : PublishBatteryRequest(nullptr, from) {} + inline PublishBatteryRequest(PublishBatteryRequest&& from) noexcept + : PublishBatteryRequest(nullptr, std::move(from)) {} + inline PublishBatteryRequest& operator=(const PublishBatteryRequest& from) { CopyFrom(from); return *this; } - inline PublishDistanceSensorRequest& operator=(PublishDistanceSensorRequest&& from) noexcept { + inline PublishBatteryRequest& operator=(PublishBatteryRequest&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -11070,16 +11906,16 @@ class PublishDistanceSensorRequest final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishDistanceSensorRequest& default_instance() { + static const PublishBatteryRequest& default_instance() { return *internal_default_instance(); } - static inline const PublishDistanceSensorRequest* internal_default_instance() { - return reinterpret_cast( - &_PublishDistanceSensorRequest_default_instance_); + static inline const PublishBatteryRequest* internal_default_instance() { + return reinterpret_cast( + &_PublishBatteryRequest_default_instance_); } - static constexpr int kIndexInFileMessages = 17; - friend void swap(PublishDistanceSensorRequest& a, PublishDistanceSensorRequest& b) { a.Swap(&b); } - inline void Swap(PublishDistanceSensorRequest* other) { + static constexpr int kIndexInFileMessages = 7; + friend void swap(PublishBatteryRequest& a, PublishBatteryRequest& b) { a.Swap(&b); } + inline void Swap(PublishBatteryRequest* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -11087,7 +11923,7 @@ class PublishDistanceSensorRequest final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishDistanceSensorRequest* other) { + void UnsafeArenaSwap(PublishBatteryRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -11095,13 +11931,13 @@ class PublishDistanceSensorRequest final // implements Message ---------------------------------------------- - PublishDistanceSensorRequest* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishBatteryRequest* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishDistanceSensorRequest& from); + void CopyFrom(const PublishBatteryRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishDistanceSensorRequest& from) { PublishDistanceSensorRequest::MergeImpl(*this, from); } + void MergeFrom(const PublishBatteryRequest& from) { PublishBatteryRequest::MergeImpl(*this, from); } private: static void MergeImpl( @@ -11138,18 +11974,18 @@ class PublishDistanceSensorRequest final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishDistanceSensorRequest* other); + void InternalSwap(PublishBatteryRequest* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishBatteryRequest"; } protected: - explicit PublishDistanceSensorRequest(::google::protobuf::Arena* arena); - PublishDistanceSensorRequest(::google::protobuf::Arena* arena, const PublishDistanceSensorRequest& from); - PublishDistanceSensorRequest(::google::protobuf::Arena* arena, PublishDistanceSensorRequest&& from) noexcept - : PublishDistanceSensorRequest(arena) { + explicit PublishBatteryRequest(::google::protobuf::Arena* arena); + PublishBatteryRequest(::google::protobuf::Arena* arena, const PublishBatteryRequest& from); + PublishBatteryRequest(::google::protobuf::Arena* arena, PublishBatteryRequest&& from) noexcept + : PublishBatteryRequest(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -11164,24 +12000,24 @@ class PublishDistanceSensorRequest final // accessors ------------------------------------------------------- enum : int { - kDistanceSensorFieldNumber = 1, + kBatteryFieldNumber = 1, }; - // .mavsdk.rpc.telemetry_server.DistanceSensor distance_sensor = 1; - bool has_distance_sensor() const; - void clear_distance_sensor() ; - const ::mavsdk::rpc::telemetry_server::DistanceSensor& distance_sensor() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::DistanceSensor* release_distance_sensor(); - ::mavsdk::rpc::telemetry_server::DistanceSensor* mutable_distance_sensor(); - void set_allocated_distance_sensor(::mavsdk::rpc::telemetry_server::DistanceSensor* value); - void unsafe_arena_set_allocated_distance_sensor(::mavsdk::rpc::telemetry_server::DistanceSensor* value); - ::mavsdk::rpc::telemetry_server::DistanceSensor* unsafe_arena_release_distance_sensor(); + // .mavsdk.rpc.telemetry_server.Battery battery = 1; + bool has_battery() const; + void clear_battery() ; + const ::mavsdk::rpc::telemetry_server::Battery& battery() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::Battery* release_battery(); + ::mavsdk::rpc::telemetry_server::Battery* mutable_battery(); + void set_allocated_battery(::mavsdk::rpc::telemetry_server::Battery* value); + void unsafe_arena_set_allocated_battery(::mavsdk::rpc::telemetry_server::Battery* value); + ::mavsdk::rpc::telemetry_server::Battery* unsafe_arena_release_battery(); private: - const ::mavsdk::rpc::telemetry_server::DistanceSensor& _internal_distance_sensor() const; - ::mavsdk::rpc::telemetry_server::DistanceSensor* _internal_mutable_distance_sensor(); + const ::mavsdk::rpc::telemetry_server::Battery& _internal_battery() const; + ::mavsdk::rpc::telemetry_server::Battery* _internal_mutable_battery(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishBatteryRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -11203,10 +12039,10 @@ class PublishDistanceSensorRequest final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishDistanceSensorRequest& from_msg); + const PublishBatteryRequest& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry_server::DistanceSensor* distance_sensor_; + ::mavsdk::rpc::telemetry_server::Battery* battery_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -11214,32 +12050,32 @@ class PublishDistanceSensorRequest final }; // ------------------------------------------------------------------- -class PublishBatteryResponse final +class PublishAttitudeResponse final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishBatteryResponse) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishAttitudeResponse) */ { public: - inline PublishBatteryResponse() : PublishBatteryResponse(nullptr) {} - ~PublishBatteryResponse() PROTOBUF_FINAL; + inline PublishAttitudeResponse() : PublishAttitudeResponse(nullptr) {} + ~PublishAttitudeResponse() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishBatteryResponse* msg, std::destroying_delete_t) { + void operator delete(PublishAttitudeResponse* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishBatteryResponse)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishAttitudeResponse)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishBatteryResponse( + explicit PROTOBUF_CONSTEXPR PublishAttitudeResponse( ::google::protobuf::internal::ConstantInitialized); - inline PublishBatteryResponse(const PublishBatteryResponse& from) : PublishBatteryResponse(nullptr, from) {} - inline PublishBatteryResponse(PublishBatteryResponse&& from) noexcept - : PublishBatteryResponse(nullptr, std::move(from)) {} - inline PublishBatteryResponse& operator=(const PublishBatteryResponse& from) { + inline PublishAttitudeResponse(const PublishAttitudeResponse& from) : PublishAttitudeResponse(nullptr, from) {} + inline PublishAttitudeResponse(PublishAttitudeResponse&& from) noexcept + : PublishAttitudeResponse(nullptr, std::move(from)) {} + inline PublishAttitudeResponse& operator=(const PublishAttitudeResponse& from) { CopyFrom(from); return *this; } - inline PublishBatteryResponse& operator=(PublishBatteryResponse&& from) noexcept { + inline PublishAttitudeResponse& operator=(PublishAttitudeResponse&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -11267,16 +12103,16 @@ class PublishBatteryResponse final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishBatteryResponse& default_instance() { + static const PublishAttitudeResponse& default_instance() { return *internal_default_instance(); } - static inline const PublishBatteryResponse* internal_default_instance() { - return reinterpret_cast( - &_PublishBatteryResponse_default_instance_); + static inline const PublishAttitudeResponse* internal_default_instance() { + return reinterpret_cast( + &_PublishAttitudeResponse_default_instance_); } - static constexpr int kIndexInFileMessages = 23; - friend void swap(PublishBatteryResponse& a, PublishBatteryResponse& b) { a.Swap(&b); } - inline void Swap(PublishBatteryResponse* other) { + static constexpr int kIndexInFileMessages = 35; + friend void swap(PublishAttitudeResponse& a, PublishAttitudeResponse& b) { a.Swap(&b); } + inline void Swap(PublishAttitudeResponse* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -11284,7 +12120,7 @@ class PublishBatteryResponse final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishBatteryResponse* other) { + void UnsafeArenaSwap(PublishAttitudeResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -11292,13 +12128,13 @@ class PublishBatteryResponse final // implements Message ---------------------------------------------- - PublishBatteryResponse* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishAttitudeResponse* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishBatteryResponse& from); + void CopyFrom(const PublishAttitudeResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishBatteryResponse& from) { PublishBatteryResponse::MergeImpl(*this, from); } + void MergeFrom(const PublishAttitudeResponse& from) { PublishAttitudeResponse::MergeImpl(*this, from); } private: static void MergeImpl( @@ -11335,18 +12171,18 @@ class PublishBatteryResponse final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishBatteryResponse* other); + void InternalSwap(PublishAttitudeResponse* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishBatteryResponse"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishAttitudeResponse"; } protected: - explicit PublishBatteryResponse(::google::protobuf::Arena* arena); - PublishBatteryResponse(::google::protobuf::Arena* arena, const PublishBatteryResponse& from); - PublishBatteryResponse(::google::protobuf::Arena* arena, PublishBatteryResponse&& from) noexcept - : PublishBatteryResponse(arena) { + explicit PublishAttitudeResponse(::google::protobuf::Arena* arena); + PublishAttitudeResponse(::google::protobuf::Arena* arena, const PublishAttitudeResponse& from); + PublishAttitudeResponse(::google::protobuf::Arena* arena, PublishAttitudeResponse&& from) noexcept + : PublishAttitudeResponse(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -11378,7 +12214,7 @@ class PublishBatteryResponse final ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _internal_mutable_telemetry_server_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishBatteryResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishAttitudeResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; @@ -11400,7 +12236,7 @@ class PublishBatteryResponse final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishBatteryResponse& from_msg); + const PublishAttitudeResponse& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; ::mavsdk::rpc::telemetry_server::TelemetryServerResult* telemetry_server_result_; @@ -11411,32 +12247,32 @@ class PublishBatteryResponse final }; // ------------------------------------------------------------------- -class PublishBatteryRequest final +class PublishAttitudeRequest final : public ::google::protobuf::Message -/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishBatteryRequest) */ { +/* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry_server.PublishAttitudeRequest) */ { public: - inline PublishBatteryRequest() : PublishBatteryRequest(nullptr) {} - ~PublishBatteryRequest() PROTOBUF_FINAL; + inline PublishAttitudeRequest() : PublishAttitudeRequest(nullptr) {} + ~PublishAttitudeRequest() PROTOBUF_FINAL; #if defined(PROTOBUF_CUSTOM_VTABLE) - void operator delete(PublishBatteryRequest* msg, std::destroying_delete_t) { + void operator delete(PublishAttitudeRequest* msg, std::destroying_delete_t) { SharedDtor(*msg); - ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishBatteryRequest)); + ::google::protobuf::internal::SizedDelete(msg, sizeof(PublishAttitudeRequest)); } #endif template - explicit PROTOBUF_CONSTEXPR PublishBatteryRequest( + explicit PROTOBUF_CONSTEXPR PublishAttitudeRequest( ::google::protobuf::internal::ConstantInitialized); - inline PublishBatteryRequest(const PublishBatteryRequest& from) : PublishBatteryRequest(nullptr, from) {} - inline PublishBatteryRequest(PublishBatteryRequest&& from) noexcept - : PublishBatteryRequest(nullptr, std::move(from)) {} - inline PublishBatteryRequest& operator=(const PublishBatteryRequest& from) { + inline PublishAttitudeRequest(const PublishAttitudeRequest& from) : PublishAttitudeRequest(nullptr, from) {} + inline PublishAttitudeRequest(PublishAttitudeRequest&& from) noexcept + : PublishAttitudeRequest(nullptr, std::move(from)) {} + inline PublishAttitudeRequest& operator=(const PublishAttitudeRequest& from) { CopyFrom(from); return *this; } - inline PublishBatteryRequest& operator=(PublishBatteryRequest&& from) noexcept { + inline PublishAttitudeRequest& operator=(PublishAttitudeRequest&& from) noexcept { if (this == &from) return *this; if (::google::protobuf::internal::CanMoveWithInternalSwap(GetArena(), from.GetArena())) { InternalSwap(&from); @@ -11464,16 +12300,16 @@ class PublishBatteryRequest final static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const PublishBatteryRequest& default_instance() { + static const PublishAttitudeRequest& default_instance() { return *internal_default_instance(); } - static inline const PublishBatteryRequest* internal_default_instance() { - return reinterpret_cast( - &_PublishBatteryRequest_default_instance_); - } - static constexpr int kIndexInFileMessages = 7; - friend void swap(PublishBatteryRequest& a, PublishBatteryRequest& b) { a.Swap(&b); } - inline void Swap(PublishBatteryRequest* other) { + static inline const PublishAttitudeRequest* internal_default_instance() { + return reinterpret_cast( + &_PublishAttitudeRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = 18; + friend void swap(PublishAttitudeRequest& a, PublishAttitudeRequest& b) { a.Swap(&b); } + inline void Swap(PublishAttitudeRequest* other) { if (other == this) return; if (::google::protobuf::internal::CanUseInternalSwap(GetArena(), other->GetArena())) { InternalSwap(other); @@ -11481,7 +12317,7 @@ class PublishBatteryRequest final ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(PublishBatteryRequest* other) { + void UnsafeArenaSwap(PublishAttitudeRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -11489,13 +12325,13 @@ class PublishBatteryRequest final // implements Message ---------------------------------------------- - PublishBatteryRequest* New(::google::protobuf::Arena* arena = nullptr) const { - return ::google::protobuf::Message::DefaultConstruct(arena); + PublishAttitudeRequest* New(::google::protobuf::Arena* arena = nullptr) const { + return ::google::protobuf::Message::DefaultConstruct(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const PublishBatteryRequest& from); + void CopyFrom(const PublishAttitudeRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom(const PublishBatteryRequest& from) { PublishBatteryRequest::MergeImpl(*this, from); } + void MergeFrom(const PublishAttitudeRequest& from) { PublishAttitudeRequest::MergeImpl(*this, from); } private: static void MergeImpl( @@ -11532,18 +12368,18 @@ class PublishBatteryRequest final private: void SharedCtor(::google::protobuf::Arena* arena); static void SharedDtor(MessageLite& self); - void InternalSwap(PublishBatteryRequest* other); + void InternalSwap(PublishAttitudeRequest* other); private: template friend ::absl::string_view( ::google::protobuf::internal::GetAnyMessageName)(); - static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishBatteryRequest"; } + static ::absl::string_view FullMessageName() { return "mavsdk.rpc.telemetry_server.PublishAttitudeRequest"; } protected: - explicit PublishBatteryRequest(::google::protobuf::Arena* arena); - PublishBatteryRequest(::google::protobuf::Arena* arena, const PublishBatteryRequest& from); - PublishBatteryRequest(::google::protobuf::Arena* arena, PublishBatteryRequest&& from) noexcept - : PublishBatteryRequest(arena) { + explicit PublishAttitudeRequest(::google::protobuf::Arena* arena); + PublishAttitudeRequest(::google::protobuf::Arena* arena, const PublishAttitudeRequest& from); + PublishAttitudeRequest(::google::protobuf::Arena* arena, PublishAttitudeRequest&& from) noexcept + : PublishAttitudeRequest(arena) { *this = ::std::move(from); } const ::google::protobuf::internal::ClassData* GetClassData() const PROTOBUF_FINAL; @@ -11558,29 +12394,45 @@ class PublishBatteryRequest final // accessors ------------------------------------------------------- enum : int { - kBatteryFieldNumber = 1, + kAngleFieldNumber = 1, + kAngularVelocityFieldNumber = 2, }; - // .mavsdk.rpc.telemetry_server.Battery battery = 1; - bool has_battery() const; - void clear_battery() ; - const ::mavsdk::rpc::telemetry_server::Battery& battery() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::Battery* release_battery(); - ::mavsdk::rpc::telemetry_server::Battery* mutable_battery(); - void set_allocated_battery(::mavsdk::rpc::telemetry_server::Battery* value); - void unsafe_arena_set_allocated_battery(::mavsdk::rpc::telemetry_server::Battery* value); - ::mavsdk::rpc::telemetry_server::Battery* unsafe_arena_release_battery(); + // .mavsdk.rpc.telemetry_server.EulerAngle angle = 1; + bool has_angle() const; + void clear_angle() ; + const ::mavsdk::rpc::telemetry_server::EulerAngle& angle() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::EulerAngle* release_angle(); + ::mavsdk::rpc::telemetry_server::EulerAngle* mutable_angle(); + void set_allocated_angle(::mavsdk::rpc::telemetry_server::EulerAngle* value); + void unsafe_arena_set_allocated_angle(::mavsdk::rpc::telemetry_server::EulerAngle* value); + ::mavsdk::rpc::telemetry_server::EulerAngle* unsafe_arena_release_angle(); private: - const ::mavsdk::rpc::telemetry_server::Battery& _internal_battery() const; - ::mavsdk::rpc::telemetry_server::Battery* _internal_mutable_battery(); + const ::mavsdk::rpc::telemetry_server::EulerAngle& _internal_angle() const; + ::mavsdk::rpc::telemetry_server::EulerAngle* _internal_mutable_angle(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishBatteryRequest) + // .mavsdk.rpc.telemetry_server.AngularVelocityBody angular_velocity = 2; + bool has_angular_velocity() const; + void clear_angular_velocity() ; + const ::mavsdk::rpc::telemetry_server::AngularVelocityBody& angular_velocity() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::telemetry_server::AngularVelocityBody* release_angular_velocity(); + ::mavsdk::rpc::telemetry_server::AngularVelocityBody* mutable_angular_velocity(); + void set_allocated_angular_velocity(::mavsdk::rpc::telemetry_server::AngularVelocityBody* value); + void unsafe_arena_set_allocated_angular_velocity(::mavsdk::rpc::telemetry_server::AngularVelocityBody* value); + ::mavsdk::rpc::telemetry_server::AngularVelocityBody* unsafe_arena_release_angular_velocity(); + + private: + const ::mavsdk::rpc::telemetry_server::AngularVelocityBody& _internal_angular_velocity() const; + ::mavsdk::rpc::telemetry_server::AngularVelocityBody* _internal_mutable_angular_velocity(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry_server.PublishAttitudeRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 1, 2, 2, 0, 2> _table_; @@ -11597,10 +12449,11 @@ class PublishBatteryRequest final ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from, - const PublishBatteryRequest& from_msg); + const PublishAttitudeRequest& from_msg); ::google::protobuf::internal::HasBits<1> _has_bits_; ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::telemetry_server::Battery* battery_; + ::mavsdk::rpc::telemetry_server::EulerAngle* angle_; + ::mavsdk::rpc::telemetry_server::AngularVelocityBody* angular_velocity_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; @@ -11668,7 +12521,7 @@ class PositionVelocityNed final return reinterpret_cast( &_PositionVelocityNed_default_instance_); } - static constexpr int kIndexInFileMessages = 53; + static constexpr int kIndexInFileMessages = 57; friend void swap(PositionVelocityNed& a, PositionVelocityNed& b) { a.Swap(&b); } inline void Swap(PositionVelocityNed* other) { if (other == this) return; @@ -11882,7 +12735,7 @@ class Odometry final return reinterpret_cast( &_Odometry_default_instance_); } - static constexpr int kIndexInFileMessages = 48; + static constexpr int kIndexInFileMessages = 52; friend void swap(Odometry& a, Odometry& b) { a.Swap(&b); } inline void Swap(Odometry* other) { if (other == this) return; @@ -12221,7 +13074,7 @@ class Imu final return reinterpret_cast( &_Imu_default_instance_); } - static constexpr int kIndexInFileMessages = 59; + static constexpr int kIndexInFileMessages = 63; friend void swap(Imu& a, Imu& b) { a.Swap(&b); } inline void Swap(Imu* other) { if (other == this) return; @@ -15231,54 +16084,350 @@ inline ::uint64_t PublishUnixEpochTimeRequest::_internal_time_us() const { ::google::protobuf::internal::TSanRead(&_impl_); return _impl_.time_us_; } -inline void PublishUnixEpochTimeRequest::_internal_set_time_us(::uint64_t value) { +inline void PublishUnixEpochTimeRequest::_internal_set_time_us(::uint64_t value) { + ::google::protobuf::internal::TSanWrite(&_impl_); + _impl_.time_us_ = value; +} + +// ------------------------------------------------------------------- + +// PublishDistanceSensorRequest + +// .mavsdk.rpc.telemetry_server.DistanceSensor distance_sensor = 1; +inline bool PublishDistanceSensorRequest::has_distance_sensor() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.distance_sensor_ != nullptr); + return value; +} +inline void PublishDistanceSensorRequest::clear_distance_sensor() { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (_impl_.distance_sensor_ != nullptr) _impl_.distance_sensor_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::telemetry_server::DistanceSensor& PublishDistanceSensorRequest::_internal_distance_sensor() const { + ::google::protobuf::internal::TSanRead(&_impl_); + const ::mavsdk::rpc::telemetry_server::DistanceSensor* p = _impl_.distance_sensor_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::telemetry_server::_DistanceSensor_default_instance_); +} +inline const ::mavsdk::rpc::telemetry_server::DistanceSensor& PublishDistanceSensorRequest::distance_sensor() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest.distance_sensor) + return _internal_distance_sensor(); +} +inline void PublishDistanceSensorRequest::unsafe_arena_set_allocated_distance_sensor(::mavsdk::rpc::telemetry_server::DistanceSensor* value) { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.distance_sensor_); + } + _impl_.distance_sensor_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::DistanceSensor*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest.distance_sensor) +} +inline ::mavsdk::rpc::telemetry_server::DistanceSensor* PublishDistanceSensorRequest::release_distance_sensor() { + ::google::protobuf::internal::TSanWrite(&_impl_); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::telemetry_server::DistanceSensor* released = _impl_.distance_sensor_; + _impl_.distance_sensor_ = nullptr; + if (::google::protobuf::internal::DebugHardenForceCopyInRelease()) { + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } + } else { + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } + } + return released; +} +inline ::mavsdk::rpc::telemetry_server::DistanceSensor* PublishDistanceSensorRequest::unsafe_arena_release_distance_sensor() { + ::google::protobuf::internal::TSanWrite(&_impl_); + // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest.distance_sensor) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::telemetry_server::DistanceSensor* temp = _impl_.distance_sensor_; + _impl_.distance_sensor_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::telemetry_server::DistanceSensor* PublishDistanceSensorRequest::_internal_mutable_distance_sensor() { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (_impl_.distance_sensor_ == nullptr) { + auto* p = ::google::protobuf::Message::DefaultConstruct<::mavsdk::rpc::telemetry_server::DistanceSensor>(GetArena()); + _impl_.distance_sensor_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::DistanceSensor*>(p); + } + return _impl_.distance_sensor_; +} +inline ::mavsdk::rpc::telemetry_server::DistanceSensor* PublishDistanceSensorRequest::mutable_distance_sensor() ABSL_ATTRIBUTE_LIFETIME_BOUND { + _impl_._has_bits_[0] |= 0x00000001u; + ::mavsdk::rpc::telemetry_server::DistanceSensor* _msg = _internal_mutable_distance_sensor(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest.distance_sensor) + return _msg; +} +inline void PublishDistanceSensorRequest::set_allocated_distance_sensor(::mavsdk::rpc::telemetry_server::DistanceSensor* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + ::google::protobuf::internal::TSanWrite(&_impl_); + if (message_arena == nullptr) { + delete (_impl_.distance_sensor_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = (value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + + _impl_.distance_sensor_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::DistanceSensor*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest.distance_sensor) +} + +// ------------------------------------------------------------------- + +// PublishAttitudeRequest + +// .mavsdk.rpc.telemetry_server.EulerAngle angle = 1; +inline bool PublishAttitudeRequest::has_angle() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.angle_ != nullptr); + return value; +} +inline void PublishAttitudeRequest::clear_angle() { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (_impl_.angle_ != nullptr) _impl_.angle_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::telemetry_server::EulerAngle& PublishAttitudeRequest::_internal_angle() const { + ::google::protobuf::internal::TSanRead(&_impl_); + const ::mavsdk::rpc::telemetry_server::EulerAngle* p = _impl_.angle_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::telemetry_server::_EulerAngle_default_instance_); +} +inline const ::mavsdk::rpc::telemetry_server::EulerAngle& PublishAttitudeRequest::angle() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry_server.PublishAttitudeRequest.angle) + return _internal_angle(); +} +inline void PublishAttitudeRequest::unsafe_arena_set_allocated_angle(::mavsdk::rpc::telemetry_server::EulerAngle* value) { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.angle_); + } + _impl_.angle_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::EulerAngle*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry_server.PublishAttitudeRequest.angle) +} +inline ::mavsdk::rpc::telemetry_server::EulerAngle* PublishAttitudeRequest::release_angle() { + ::google::protobuf::internal::TSanWrite(&_impl_); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::telemetry_server::EulerAngle* released = _impl_.angle_; + _impl_.angle_ = nullptr; + if (::google::protobuf::internal::DebugHardenForceCopyInRelease()) { + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } + } else { + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } + } + return released; +} +inline ::mavsdk::rpc::telemetry_server::EulerAngle* PublishAttitudeRequest::unsafe_arena_release_angle() { + ::google::protobuf::internal::TSanWrite(&_impl_); + // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry_server.PublishAttitudeRequest.angle) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::telemetry_server::EulerAngle* temp = _impl_.angle_; + _impl_.angle_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::telemetry_server::EulerAngle* PublishAttitudeRequest::_internal_mutable_angle() { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (_impl_.angle_ == nullptr) { + auto* p = ::google::protobuf::Message::DefaultConstruct<::mavsdk::rpc::telemetry_server::EulerAngle>(GetArena()); + _impl_.angle_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::EulerAngle*>(p); + } + return _impl_.angle_; +} +inline ::mavsdk::rpc::telemetry_server::EulerAngle* PublishAttitudeRequest::mutable_angle() ABSL_ATTRIBUTE_LIFETIME_BOUND { + _impl_._has_bits_[0] |= 0x00000001u; + ::mavsdk::rpc::telemetry_server::EulerAngle* _msg = _internal_mutable_angle(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry_server.PublishAttitudeRequest.angle) + return _msg; +} +inline void PublishAttitudeRequest::set_allocated_angle(::mavsdk::rpc::telemetry_server::EulerAngle* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + ::google::protobuf::internal::TSanWrite(&_impl_); + if (message_arena == nullptr) { + delete (_impl_.angle_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = (value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + + _impl_.angle_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::EulerAngle*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry_server.PublishAttitudeRequest.angle) +} + +// .mavsdk.rpc.telemetry_server.AngularVelocityBody angular_velocity = 2; +inline bool PublishAttitudeRequest::has_angular_velocity() const { + bool value = (_impl_._has_bits_[0] & 0x00000002u) != 0; + PROTOBUF_ASSUME(!value || _impl_.angular_velocity_ != nullptr); + return value; +} +inline void PublishAttitudeRequest::clear_angular_velocity() { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (_impl_.angular_velocity_ != nullptr) _impl_.angular_velocity_->Clear(); + _impl_._has_bits_[0] &= ~0x00000002u; +} +inline const ::mavsdk::rpc::telemetry_server::AngularVelocityBody& PublishAttitudeRequest::_internal_angular_velocity() const { + ::google::protobuf::internal::TSanRead(&_impl_); + const ::mavsdk::rpc::telemetry_server::AngularVelocityBody* p = _impl_.angular_velocity_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::telemetry_server::_AngularVelocityBody_default_instance_); +} +inline const ::mavsdk::rpc::telemetry_server::AngularVelocityBody& PublishAttitudeRequest::angular_velocity() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry_server.PublishAttitudeRequest.angular_velocity) + return _internal_angular_velocity(); +} +inline void PublishAttitudeRequest::unsafe_arena_set_allocated_angular_velocity(::mavsdk::rpc::telemetry_server::AngularVelocityBody* value) { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.angular_velocity_); + } + _impl_.angular_velocity_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::AngularVelocityBody*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000002u; + } else { + _impl_._has_bits_[0] &= ~0x00000002u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry_server.PublishAttitudeRequest.angular_velocity) +} +inline ::mavsdk::rpc::telemetry_server::AngularVelocityBody* PublishAttitudeRequest::release_angular_velocity() { + ::google::protobuf::internal::TSanWrite(&_impl_); + + _impl_._has_bits_[0] &= ~0x00000002u; + ::mavsdk::rpc::telemetry_server::AngularVelocityBody* released = _impl_.angular_velocity_; + _impl_.angular_velocity_ = nullptr; + if (::google::protobuf::internal::DebugHardenForceCopyInRelease()) { + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } + } else { + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } + } + return released; +} +inline ::mavsdk::rpc::telemetry_server::AngularVelocityBody* PublishAttitudeRequest::unsafe_arena_release_angular_velocity() { + ::google::protobuf::internal::TSanWrite(&_impl_); + // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry_server.PublishAttitudeRequest.angular_velocity) + + _impl_._has_bits_[0] &= ~0x00000002u; + ::mavsdk::rpc::telemetry_server::AngularVelocityBody* temp = _impl_.angular_velocity_; + _impl_.angular_velocity_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::telemetry_server::AngularVelocityBody* PublishAttitudeRequest::_internal_mutable_angular_velocity() { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (_impl_.angular_velocity_ == nullptr) { + auto* p = ::google::protobuf::Message::DefaultConstruct<::mavsdk::rpc::telemetry_server::AngularVelocityBody>(GetArena()); + _impl_.angular_velocity_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::AngularVelocityBody*>(p); + } + return _impl_.angular_velocity_; +} +inline ::mavsdk::rpc::telemetry_server::AngularVelocityBody* PublishAttitudeRequest::mutable_angular_velocity() ABSL_ATTRIBUTE_LIFETIME_BOUND { + _impl_._has_bits_[0] |= 0x00000002u; + ::mavsdk::rpc::telemetry_server::AngularVelocityBody* _msg = _internal_mutable_angular_velocity(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry_server.PublishAttitudeRequest.angular_velocity) + return _msg; +} +inline void PublishAttitudeRequest::set_allocated_angular_velocity(::mavsdk::rpc::telemetry_server::AngularVelocityBody* value) { + ::google::protobuf::Arena* message_arena = GetArena(); ::google::protobuf::internal::TSanWrite(&_impl_); - _impl_.time_us_ = value; + if (message_arena == nullptr) { + delete (_impl_.angular_velocity_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = (value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000002u; + } else { + _impl_._has_bits_[0] &= ~0x00000002u; + } + + _impl_.angular_velocity_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::AngularVelocityBody*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry_server.PublishAttitudeRequest.angular_velocity) } // ------------------------------------------------------------------- -// PublishDistanceSensorRequest +// PublishVisualFlightRulesHudRequest -// .mavsdk.rpc.telemetry_server.DistanceSensor distance_sensor = 1; -inline bool PublishDistanceSensorRequest::has_distance_sensor() const { +// .mavsdk.rpc.telemetry_server.FixedwingMetrics fixed_wing_metrics = 1; +inline bool PublishVisualFlightRulesHudRequest::has_fixed_wing_metrics() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.distance_sensor_ != nullptr); + PROTOBUF_ASSUME(!value || _impl_.fixed_wing_metrics_ != nullptr); return value; } -inline void PublishDistanceSensorRequest::clear_distance_sensor() { +inline void PublishVisualFlightRulesHudRequest::clear_fixed_wing_metrics() { ::google::protobuf::internal::TSanWrite(&_impl_); - if (_impl_.distance_sensor_ != nullptr) _impl_.distance_sensor_->Clear(); + if (_impl_.fixed_wing_metrics_ != nullptr) _impl_.fixed_wing_metrics_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::telemetry_server::DistanceSensor& PublishDistanceSensorRequest::_internal_distance_sensor() const { +inline const ::mavsdk::rpc::telemetry_server::FixedwingMetrics& PublishVisualFlightRulesHudRequest::_internal_fixed_wing_metrics() const { ::google::protobuf::internal::TSanRead(&_impl_); - const ::mavsdk::rpc::telemetry_server::DistanceSensor* p = _impl_.distance_sensor_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::telemetry_server::_DistanceSensor_default_instance_); + const ::mavsdk::rpc::telemetry_server::FixedwingMetrics* p = _impl_.fixed_wing_metrics_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::telemetry_server::_FixedwingMetrics_default_instance_); } -inline const ::mavsdk::rpc::telemetry_server::DistanceSensor& PublishDistanceSensorRequest::distance_sensor() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest.distance_sensor) - return _internal_distance_sensor(); +inline const ::mavsdk::rpc::telemetry_server::FixedwingMetrics& PublishVisualFlightRulesHudRequest::fixed_wing_metrics() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest.fixed_wing_metrics) + return _internal_fixed_wing_metrics(); } -inline void PublishDistanceSensorRequest::unsafe_arena_set_allocated_distance_sensor(::mavsdk::rpc::telemetry_server::DistanceSensor* value) { +inline void PublishVisualFlightRulesHudRequest::unsafe_arena_set_allocated_fixed_wing_metrics(::mavsdk::rpc::telemetry_server::FixedwingMetrics* value) { ::google::protobuf::internal::TSanWrite(&_impl_); if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.distance_sensor_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.fixed_wing_metrics_); } - _impl_.distance_sensor_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::DistanceSensor*>(value); + _impl_.fixed_wing_metrics_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::FixedwingMetrics*>(value); if (value != nullptr) { _impl_._has_bits_[0] |= 0x00000001u; } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest.distance_sensor) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest.fixed_wing_metrics) } -inline ::mavsdk::rpc::telemetry_server::DistanceSensor* PublishDistanceSensorRequest::release_distance_sensor() { +inline ::mavsdk::rpc::telemetry_server::FixedwingMetrics* PublishVisualFlightRulesHudRequest::release_fixed_wing_metrics() { ::google::protobuf::internal::TSanWrite(&_impl_); _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::telemetry_server::DistanceSensor* released = _impl_.distance_sensor_; - _impl_.distance_sensor_ = nullptr; + ::mavsdk::rpc::telemetry_server::FixedwingMetrics* released = _impl_.fixed_wing_metrics_; + _impl_.fixed_wing_metrics_ = nullptr; if (::google::protobuf::internal::DebugHardenForceCopyInRelease()) { auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); released = ::google::protobuf::internal::DuplicateIfNonNull(released); @@ -15292,34 +16441,34 @@ inline ::mavsdk::rpc::telemetry_server::DistanceSensor* PublishDistanceSensorReq } return released; } -inline ::mavsdk::rpc::telemetry_server::DistanceSensor* PublishDistanceSensorRequest::unsafe_arena_release_distance_sensor() { +inline ::mavsdk::rpc::telemetry_server::FixedwingMetrics* PublishVisualFlightRulesHudRequest::unsafe_arena_release_fixed_wing_metrics() { ::google::protobuf::internal::TSanWrite(&_impl_); - // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest.distance_sensor) + // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest.fixed_wing_metrics) _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::telemetry_server::DistanceSensor* temp = _impl_.distance_sensor_; - _impl_.distance_sensor_ = nullptr; + ::mavsdk::rpc::telemetry_server::FixedwingMetrics* temp = _impl_.fixed_wing_metrics_; + _impl_.fixed_wing_metrics_ = nullptr; return temp; } -inline ::mavsdk::rpc::telemetry_server::DistanceSensor* PublishDistanceSensorRequest::_internal_mutable_distance_sensor() { +inline ::mavsdk::rpc::telemetry_server::FixedwingMetrics* PublishVisualFlightRulesHudRequest::_internal_mutable_fixed_wing_metrics() { ::google::protobuf::internal::TSanWrite(&_impl_); - if (_impl_.distance_sensor_ == nullptr) { - auto* p = ::google::protobuf::Message::DefaultConstruct<::mavsdk::rpc::telemetry_server::DistanceSensor>(GetArena()); - _impl_.distance_sensor_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::DistanceSensor*>(p); + if (_impl_.fixed_wing_metrics_ == nullptr) { + auto* p = ::google::protobuf::Message::DefaultConstruct<::mavsdk::rpc::telemetry_server::FixedwingMetrics>(GetArena()); + _impl_.fixed_wing_metrics_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::FixedwingMetrics*>(p); } - return _impl_.distance_sensor_; + return _impl_.fixed_wing_metrics_; } -inline ::mavsdk::rpc::telemetry_server::DistanceSensor* PublishDistanceSensorRequest::mutable_distance_sensor() ABSL_ATTRIBUTE_LIFETIME_BOUND { +inline ::mavsdk::rpc::telemetry_server::FixedwingMetrics* PublishVisualFlightRulesHudRequest::mutable_fixed_wing_metrics() ABSL_ATTRIBUTE_LIFETIME_BOUND { _impl_._has_bits_[0] |= 0x00000001u; - ::mavsdk::rpc::telemetry_server::DistanceSensor* _msg = _internal_mutable_distance_sensor(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest.distance_sensor) + ::mavsdk::rpc::telemetry_server::FixedwingMetrics* _msg = _internal_mutable_fixed_wing_metrics(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest.fixed_wing_metrics) return _msg; } -inline void PublishDistanceSensorRequest::set_allocated_distance_sensor(::mavsdk::rpc::telemetry_server::DistanceSensor* value) { +inline void PublishVisualFlightRulesHudRequest::set_allocated_fixed_wing_metrics(::mavsdk::rpc::telemetry_server::FixedwingMetrics* value) { ::google::protobuf::Arena* message_arena = GetArena(); ::google::protobuf::internal::TSanWrite(&_impl_); if (message_arena == nullptr) { - delete (_impl_.distance_sensor_); + delete (_impl_.fixed_wing_metrics_); } if (value != nullptr) { @@ -15332,8 +16481,8 @@ inline void PublishDistanceSensorRequest::set_allocated_distance_sensor(::mavsdk _impl_._has_bits_[0] &= ~0x00000001u; } - _impl_.distance_sensor_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::DistanceSensor*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry_server.PublishDistanceSensorRequest.distance_sensor) + _impl_.fixed_wing_metrics_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::FixedwingMetrics*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudRequest.fixed_wing_metrics) } // ------------------------------------------------------------------- @@ -16838,6 +17987,206 @@ inline void PublishDistanceSensorResponse::set_allocated_telemetry_server_result // ------------------------------------------------------------------- +// PublishAttitudeResponse + +// .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; +inline bool PublishAttitudeResponse::has_telemetry_server_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.telemetry_server_result_ != nullptr); + return value; +} +inline void PublishAttitudeResponse::clear_telemetry_server_result() { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (_impl_.telemetry_server_result_ != nullptr) _impl_.telemetry_server_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& PublishAttitudeResponse::_internal_telemetry_server_result() const { + ::google::protobuf::internal::TSanRead(&_impl_); + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult* p = _impl_.telemetry_server_result_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::telemetry_server::_TelemetryServerResult_default_instance_); +} +inline const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& PublishAttitudeResponse::telemetry_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry_server.PublishAttitudeResponse.telemetry_server_result) + return _internal_telemetry_server_result(); +} +inline void PublishAttitudeResponse::unsafe_arena_set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value) { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.telemetry_server_result_); + } + _impl_.telemetry_server_result_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::TelemetryServerResult*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry_server.PublishAttitudeResponse.telemetry_server_result) +} +inline ::mavsdk::rpc::telemetry_server::TelemetryServerResult* PublishAttitudeResponse::release_telemetry_server_result() { + ::google::protobuf::internal::TSanWrite(&_impl_); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* released = _impl_.telemetry_server_result_; + _impl_.telemetry_server_result_ = nullptr; + if (::google::protobuf::internal::DebugHardenForceCopyInRelease()) { + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } + } else { + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } + } + return released; +} +inline ::mavsdk::rpc::telemetry_server::TelemetryServerResult* PublishAttitudeResponse::unsafe_arena_release_telemetry_server_result() { + ::google::protobuf::internal::TSanWrite(&_impl_); + // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry_server.PublishAttitudeResponse.telemetry_server_result) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* temp = _impl_.telemetry_server_result_; + _impl_.telemetry_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::telemetry_server::TelemetryServerResult* PublishAttitudeResponse::_internal_mutable_telemetry_server_result() { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (_impl_.telemetry_server_result_ == nullptr) { + auto* p = ::google::protobuf::Message::DefaultConstruct<::mavsdk::rpc::telemetry_server::TelemetryServerResult>(GetArena()); + _impl_.telemetry_server_result_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::TelemetryServerResult*>(p); + } + return _impl_.telemetry_server_result_; +} +inline ::mavsdk::rpc::telemetry_server::TelemetryServerResult* PublishAttitudeResponse::mutable_telemetry_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { + _impl_._has_bits_[0] |= 0x00000001u; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _msg = _internal_mutable_telemetry_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry_server.PublishAttitudeResponse.telemetry_server_result) + return _msg; +} +inline void PublishAttitudeResponse::set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + ::google::protobuf::internal::TSanWrite(&_impl_); + if (message_arena == nullptr) { + delete (_impl_.telemetry_server_result_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = (value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + + _impl_.telemetry_server_result_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::TelemetryServerResult*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry_server.PublishAttitudeResponse.telemetry_server_result) +} + +// ------------------------------------------------------------------- + +// PublishVisualFlightRulesHudResponse + +// .mavsdk.rpc.telemetry_server.TelemetryServerResult telemetry_server_result = 1; +inline bool PublishVisualFlightRulesHudResponse::has_telemetry_server_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.telemetry_server_result_ != nullptr); + return value; +} +inline void PublishVisualFlightRulesHudResponse::clear_telemetry_server_result() { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (_impl_.telemetry_server_result_ != nullptr) _impl_.telemetry_server_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& PublishVisualFlightRulesHudResponse::_internal_telemetry_server_result() const { + ::google::protobuf::internal::TSanRead(&_impl_); + const ::mavsdk::rpc::telemetry_server::TelemetryServerResult* p = _impl_.telemetry_server_result_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::telemetry_server::_TelemetryServerResult_default_instance_); +} +inline const ::mavsdk::rpc::telemetry_server::TelemetryServerResult& PublishVisualFlightRulesHudResponse::telemetry_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse.telemetry_server_result) + return _internal_telemetry_server_result(); +} +inline void PublishVisualFlightRulesHudResponse::unsafe_arena_set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value) { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.telemetry_server_result_); + } + _impl_.telemetry_server_result_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::TelemetryServerResult*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse.telemetry_server_result) +} +inline ::mavsdk::rpc::telemetry_server::TelemetryServerResult* PublishVisualFlightRulesHudResponse::release_telemetry_server_result() { + ::google::protobuf::internal::TSanWrite(&_impl_); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* released = _impl_.telemetry_server_result_; + _impl_.telemetry_server_result_ = nullptr; + if (::google::protobuf::internal::DebugHardenForceCopyInRelease()) { + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } + } else { + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } + } + return released; +} +inline ::mavsdk::rpc::telemetry_server::TelemetryServerResult* PublishVisualFlightRulesHudResponse::unsafe_arena_release_telemetry_server_result() { + ::google::protobuf::internal::TSanWrite(&_impl_); + // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse.telemetry_server_result) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* temp = _impl_.telemetry_server_result_; + _impl_.telemetry_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::telemetry_server::TelemetryServerResult* PublishVisualFlightRulesHudResponse::_internal_mutable_telemetry_server_result() { + ::google::protobuf::internal::TSanWrite(&_impl_); + if (_impl_.telemetry_server_result_ == nullptr) { + auto* p = ::google::protobuf::Message::DefaultConstruct<::mavsdk::rpc::telemetry_server::TelemetryServerResult>(GetArena()); + _impl_.telemetry_server_result_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::TelemetryServerResult*>(p); + } + return _impl_.telemetry_server_result_; +} +inline ::mavsdk::rpc::telemetry_server::TelemetryServerResult* PublishVisualFlightRulesHudResponse::mutable_telemetry_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { + _impl_._has_bits_[0] |= 0x00000001u; + ::mavsdk::rpc::telemetry_server::TelemetryServerResult* _msg = _internal_mutable_telemetry_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse.telemetry_server_result) + return _msg; +} +inline void PublishVisualFlightRulesHudResponse::set_allocated_telemetry_server_result(::mavsdk::rpc::telemetry_server::TelemetryServerResult* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + ::google::protobuf::internal::TSanWrite(&_impl_); + if (message_arena == nullptr) { + delete (_impl_.telemetry_server_result_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = (value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + + _impl_.telemetry_server_result_ = reinterpret_cast<::mavsdk::rpc::telemetry_server::TelemetryServerResult*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry_server.PublishVisualFlightRulesHudResponse.telemetry_server_result) +} + +// ------------------------------------------------------------------- + // Position // double latitude_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; @@ -19419,6 +20768,72 @@ inline void FixedwingMetrics::_internal_set_climb_rate_m_s(float value) { _impl_.climb_rate_m_s_ = value; } +// float groundspeed_m_s = 4 [(.mavsdk.options.default_value) = "NaN"]; +inline void FixedwingMetrics::clear_groundspeed_m_s() { + ::google::protobuf::internal::TSanWrite(&_impl_); + _impl_.groundspeed_m_s_ = 0; +} +inline float FixedwingMetrics::groundspeed_m_s() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry_server.FixedwingMetrics.groundspeed_m_s) + return _internal_groundspeed_m_s(); +} +inline void FixedwingMetrics::set_groundspeed_m_s(float value) { + _internal_set_groundspeed_m_s(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry_server.FixedwingMetrics.groundspeed_m_s) +} +inline float FixedwingMetrics::_internal_groundspeed_m_s() const { + ::google::protobuf::internal::TSanRead(&_impl_); + return _impl_.groundspeed_m_s_; +} +inline void FixedwingMetrics::_internal_set_groundspeed_m_s(float value) { + ::google::protobuf::internal::TSanWrite(&_impl_); + _impl_.groundspeed_m_s_ = value; +} + +// float heading_deg = 5 [(.mavsdk.options.default_value) = "NaN"]; +inline void FixedwingMetrics::clear_heading_deg() { + ::google::protobuf::internal::TSanWrite(&_impl_); + _impl_.heading_deg_ = 0; +} +inline float FixedwingMetrics::heading_deg() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry_server.FixedwingMetrics.heading_deg) + return _internal_heading_deg(); +} +inline void FixedwingMetrics::set_heading_deg(float value) { + _internal_set_heading_deg(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry_server.FixedwingMetrics.heading_deg) +} +inline float FixedwingMetrics::_internal_heading_deg() const { + ::google::protobuf::internal::TSanRead(&_impl_); + return _impl_.heading_deg_; +} +inline void FixedwingMetrics::_internal_set_heading_deg(float value) { + ::google::protobuf::internal::TSanWrite(&_impl_); + _impl_.heading_deg_ = value; +} + +// float absolute_altitude_m = 6 [(.mavsdk.options.default_value) = "NaN"]; +inline void FixedwingMetrics::clear_absolute_altitude_m() { + ::google::protobuf::internal::TSanWrite(&_impl_); + _impl_.absolute_altitude_m_ = 0; +} +inline float FixedwingMetrics::absolute_altitude_m() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry_server.FixedwingMetrics.absolute_altitude_m) + return _internal_absolute_altitude_m(); +} +inline void FixedwingMetrics::set_absolute_altitude_m(float value) { + _internal_set_absolute_altitude_m(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry_server.FixedwingMetrics.absolute_altitude_m) +} +inline float FixedwingMetrics::_internal_absolute_altitude_m() const { + ::google::protobuf::internal::TSanRead(&_impl_); + return _impl_.absolute_altitude_m_; +} +inline void FixedwingMetrics::_internal_set_absolute_altitude_m(float value) { + ::google::protobuf::internal::TSanWrite(&_impl_); + _impl_.absolute_altitude_m_ = value; +} + // ------------------------------------------------------------------- // AccelerationFrd diff --git a/src/mavsdk_server/src/plugins/telemetry/telemetry_service_impl.h b/src/mavsdk_server/src/plugins/telemetry/telemetry_service_impl.h index aaf4e7be91..2463f59ff7 100644 --- a/src/mavsdk_server/src/plugins/telemetry/telemetry_service_impl.h +++ b/src/mavsdk_server/src/plugins/telemetry/telemetry_service_impl.h @@ -1104,6 +1104,12 @@ class TelemetryServiceImpl final : public rpc::telemetry::TelemetryService::Serv rpc_obj->set_climb_rate_m_s(fixedwing_metrics.climb_rate_m_s); + rpc_obj->set_groundspeed_m_s(fixedwing_metrics.groundspeed_m_s); + + rpc_obj->set_heading_deg(fixedwing_metrics.heading_deg); + + rpc_obj->set_absolute_altitude_m(fixedwing_metrics.absolute_altitude_m); + return rpc_obj; } @@ -1118,6 +1124,12 @@ class TelemetryServiceImpl final : public rpc::telemetry::TelemetryService::Serv obj.climb_rate_m_s = fixedwing_metrics.climb_rate_m_s(); + obj.groundspeed_m_s = fixedwing_metrics.groundspeed_m_s(); + + obj.heading_deg = fixedwing_metrics.heading_deg(); + + obj.absolute_altitude_m = fixedwing_metrics.absolute_altitude_m(); + return obj; } diff --git a/src/mavsdk_server/src/plugins/telemetry_server/telemetry_server_service_impl.h b/src/mavsdk_server/src/plugins/telemetry_server/telemetry_server_service_impl.h index b3373204ac..4b36a47bce 100644 --- a/src/mavsdk_server/src/plugins/telemetry_server/telemetry_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/telemetry_server/telemetry_server_service_impl.h @@ -970,6 +970,12 @@ class TelemetryServerServiceImpl final rpc_obj->set_climb_rate_m_s(fixedwing_metrics.climb_rate_m_s); + rpc_obj->set_groundspeed_m_s(fixedwing_metrics.groundspeed_m_s); + + rpc_obj->set_heading_deg(fixedwing_metrics.heading_deg); + + rpc_obj->set_absolute_altitude_m(fixedwing_metrics.absolute_altitude_m); + return rpc_obj; } @@ -984,6 +990,12 @@ class TelemetryServerServiceImpl final obj.climb_rate_m_s = fixedwing_metrics.climb_rate_m_s(); + obj.groundspeed_m_s = fixedwing_metrics.groundspeed_m_s(); + + obj.heading_deg = fixedwing_metrics.heading_deg(); + + obj.absolute_altitude_m = fixedwing_metrics.absolute_altitude_m(); + return obj; } @@ -1634,6 +1646,69 @@ class TelemetryServerServiceImpl final return grpc::Status::OK; } + grpc::Status PublishAttitude( + grpc::ServerContext* /* context */, + const rpc::telemetry_server::PublishAttitudeRequest* request, + rpc::telemetry_server::PublishAttitudeResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::TelemetryServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "PublishAttitude sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->publish_attitude( + translateFromRpcEulerAngle(request->angle()), + translateFromRpcAngularVelocityBody(request->angular_velocity())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + grpc::Status PublishVisualFlightRulesHud( + grpc::ServerContext* /* context */, + const rpc::telemetry_server::PublishVisualFlightRulesHudRequest* request, + rpc::telemetry_server::PublishVisualFlightRulesHudResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::TelemetryServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "PublishVisualFlightRulesHud sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->publish_visual_flight_rules_hud( + translateFromRpcFixedwingMetrics(request->fixed_wing_metrics())); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + void stop() { _stopped.store(true);