From 23c70901a3bdfc346b6bf73aece20401bf822b93 Mon Sep 17 00:00:00 2001 From: Ildar Sadykov Date: Thu, 8 Aug 2019 17:06:19 +0300 Subject: [PATCH 1/5] Added telemetry subscriptions. Added: 1. AttitudeAngularSpeed: current angular speed from ATTITUDE_QUATERNION message. See https://mavlink.io/en/messages/common.html#ATTITUDE_QUATERNION 2. ActuatorControlTarget: current vehicle attitude and body angular rates. See https://mavlink.io/en/messages/common.html#SET_ACTUATOR_CONTROL_TARGET 3. ActuatorOutputStatus: current raw values of the actuator outputs. See https://mavlink.io/en/messages/common.html#ACTUATOR_OUTPUT_STATUS --- .../telemetry/telemetry_service_impl.h | 85 ++++++ .../test/telemetry_service_impl_test.cpp | 282 ++++++++++++++++++ src/integration_tests/telemetry_async.cpp | 56 ++++ src/integration_tests/telemetry_sync.cpp | 19 ++ .../include/plugins/telemetry/telemetry.h | 191 +++++++++++- src/plugins/telemetry/mocks/telemetry_mock.h | 6 + src/plugins/telemetry/telemetry.cpp | 117 ++++++++ src/plugins/telemetry/telemetry_impl.cpp | 137 +++++++++ src/plugins/telemetry/telemetry_impl.h | 29 ++ 9 files changed, 921 insertions(+), 1 deletion(-) diff --git a/src/backend/src/plugins/telemetry/telemetry_service_impl.h b/src/backend/src/plugins/telemetry/telemetry_service_impl.h index 17cd1dbb4e..a388f3f4de 100644 --- a/src/backend/src/plugins/telemetry/telemetry_service_impl.h +++ b/src/backend/src/plugins/telemetry/telemetry_service_impl.h @@ -314,6 +314,31 @@ class TelemetryServiceImpl final : public mavsdk::rpc::telemetry::TelemetryServi return grpc::Status::OK; } + grpc::Status SubscribeAttitudeAngularSpeed( + grpc::ServerContext* /* context */, + const mavsdk::rpc::telemetry::SubscribeAttitudeAngularSpeedRequest* /* request */, + grpc::ServerWriter* writer) override + { + std::mutex attitude_angular_speed_mutex{}; + + _telemetry.attitude_angular_speed_async([&writer, &attitude_angular_speed_mutex]( + mavsdk::Telemetry::AngularSpeed angular_speed) { + auto rpc_angular_speed = new mavsdk::rpc::telemetry::AngularSpeed(); + rpc_angular_speed->set_rollspeed(angular_speed.rollspeed); + rpc_angular_speed->set_pitchspeed(angular_speed.pitchspeed); + rpc_angular_speed->set_yawspeed(angular_speed.yawspeed); + + mavsdk::rpc::telemetry::AttitudeAngularSpeedResponse rpc_angular_speed_response; + rpc_angular_speed_response.set_allocated_attitude_angular_speed(rpc_angular_speed); + + std::lock_guard lock(attitude_angular_speed_mutex); + writer->Write(rpc_angular_speed_response); + }); + + _stop_future.wait(); + return grpc::Status::OK; + } + grpc::Status SubscribeAttitudeEuler( grpc::ServerContext* /* context */, const mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest* /* request */, @@ -440,6 +465,66 @@ class TelemetryServiceImpl final : public mavsdk::rpc::telemetry::TelemetryServi return grpc::Status::OK; } + grpc::Status SubscribeActuatorControlTarget( + grpc::ServerContext* /* context */, + const mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* /* request */, + grpc::ServerWriter* writer) override + { + std::mutex actuator_control_target_mutex{}; + + _telemetry.actuator_control_target_async( + [&writer, &actuator_control_target_mutex]( + mavsdk::Telemetry::ActuatorControlTarget actuator_control_target) { + auto rpc_actuator_control_target = + new mavsdk::rpc::telemetry::ActuatorControlTarget(); + rpc_actuator_control_target->set_group(actuator_control_target.group); + for (int i = 0; i < 8; i++) { + rpc_actuator_control_target->add_controls(actuator_control_target.controls[i]); + } + + mavsdk::rpc::telemetry::ActuatorControlTargetResponse + rpc_actuator_control_target_response; + rpc_actuator_control_target_response.set_allocated_actuator_control_target( + rpc_actuator_control_target); + + std::lock_guard lock(actuator_control_target_mutex); + writer->Write(rpc_actuator_control_target_response); + }); + + _stop_future.wait(); + return grpc::Status::OK; + } + + grpc::Status SubscribeActuatorOutputStatus( + grpc::ServerContext* /* context */, + const mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* /* request */, + grpc::ServerWriter* writer) override + { + std::mutex actuator_output_status_mutex{}; + + _telemetry.actuator_output_status_async( + [&writer, &actuator_output_status_mutex]( + mavsdk::Telemetry::ActuatorOutputStatus actuator_output_status) { + auto rpc_actuator_output_status = + new mavsdk::rpc::telemetry::ActuatorOutputStatus(); + rpc_actuator_output_status->set_active(actuator_output_status.active); + for (unsigned i = 0; i < actuator_output_status.active; i++) { + rpc_actuator_output_status->add_actuator(actuator_output_status.actuator[i]); + } + + mavsdk::rpc::telemetry::ActuatorOutputStatusResponse + rpc_actuator_output_status_response; + rpc_actuator_output_status_response.set_allocated_actuator_output_status( + rpc_actuator_output_status); + + std::lock_guard lock(actuator_output_status_mutex); + writer->Write(rpc_actuator_output_status_response); + }); + + _stop_future.wait(); + return grpc::Status::OK; + } + void stop() { _stop_promise.set_value(); } private: diff --git a/src/backend/test/telemetry_service_impl_test.cpp b/src/backend/test/telemetry_service_impl_test.cpp index 7fa77019f5..82632ffa5e 100644 --- a/src/backend/test/telemetry_service_impl_test.cpp +++ b/src/backend/test/telemetry_service_impl_test.cpp @@ -37,10 +37,16 @@ using Quaternion = mavsdk::Telemetry::Quaternion; using EulerAngle = mavsdk::Telemetry::EulerAngle; +using AngularSpeed = mavsdk::Telemetry::AngularSpeed; + using GroundSpeedNed = mavsdk::Telemetry::GroundSpeedNED; using RcStatus = mavsdk::Telemetry::RCStatus; +using ActuatorControlTarget = mavsdk::Telemetry::ActuatorControlTarget; + +using ActuatorOutputStatus = mavsdk::Telemetry::ActuatorOutputStatus; + class TelemetryServiceImplTest : public ::testing::Test { protected: virtual void SetUp() @@ -99,6 +105,12 @@ class TelemetryServiceImplTest : public ::testing::Test { Quaternion createQuaternion(const float w, const float x, const float y, const float z) const; std::future subscribeAttitudeQuaternionAsync(std::vector& quaternions) const; + void checkSendsAttitudeAngularSpeeds(const std::vector& angular_speeds) const; + AngularSpeed + createAngularSpeed(const float rollspeed, const float pitchspeed, const float yawspeed) const; + std::future + subscribeAttitudeAngularSpeedAsync(std::vector& angular_speeds) const; + void checkSendsAttitudeEulerAngles(const std::vector& euler_angles) const; EulerAngle createEulerAngle(const float roll_deg, const float pitch_deg, const float yaw_deg) const; @@ -125,6 +137,20 @@ class TelemetryServiceImplTest : public ::testing::Test { const float signal_strength_percent) const; std::future subscribeRcStatusAsync(std::vector& rc_status_events) const; + void checkSendsActuatorControlTargetEvents( + const std::vector& actuator_control_target_events) const; + ActuatorControlTarget + createActuatorControlTarget(const uint8_t group, const float* controls) const; + std::future subscribeActuatorControlTargetAsync( + std::vector& actuator_control_target_events) const; + + void checkSendsActuatorOutputStatusEvents( + const std::vector& actuator_output_status_events) const; + ActuatorOutputStatus + createActuatorOutputStatus(const uint8_t group, const float* controls) const; + std::future subscribeActuatorOutputStatusAsync( + std::vector& actuator_output_status_events) const; + std::unique_ptr _server{}; std::unique_ptr _stub{}; std::unique_ptr _telemetry{}; @@ -964,6 +990,17 @@ TEST_F(TelemetryServiceImplTest, registersToTelemetryAttitudeQuaternionAsync) quaternion_stream_future.wait(); } +TEST_F(TelemetryServiceImplTest, registersToTelemetryAttitudeAngularSpeedAsync) +{ + EXPECT_CALL(*_telemetry, attitude_angular_speed_async(_)).Times(1); + + std::vector angular_speeds; + auto angular_speed_stream_future = subscribeAttitudeAngularSpeedAsync(angular_speeds); + + _telemetry_service->stop(); + angular_speed_stream_future.wait(); +} + std::future TelemetryServiceImplTest::subscribeAttitudeQuaternionAsync( std::vector& quaternions) const { @@ -1000,6 +1037,41 @@ TEST_F(TelemetryServiceImplTest, doesNotSendAttitudeQuaternionIfCallbackNotCalle EXPECT_EQ(0, quaternions.size()); } +std::future TelemetryServiceImplTest::subscribeAttitudeAngularSpeedAsync( + std::vector& angular_speeds) const +{ + return std::async(std::launch::async, [&]() { + grpc::ClientContext context; + mavsdk::rpc::telemetry::SubscribeAttitudeAngularSpeedRequest request; + auto response_reader = _stub->SubscribeAttitudeAngularSpeed(&context, request); + + mavsdk::rpc::telemetry::AttitudeAngularSpeedResponse response; + while (response_reader->Read(&response)) { + auto angular_speed_rpc = response.attitude_angular_speed(); + + AngularSpeed angular_speed; + angular_speed.rollspeed = angular_speed_rpc.rollspeed(); + angular_speed.pitchspeed = angular_speed_rpc.pitchspeed(); + angular_speed.yawspeed = angular_speed_rpc.yawspeed(); + + angular_speeds.push_back(angular_speed); + } + + response_reader->Finish(); + }); +} + +TEST_F(TelemetryServiceImplTest, doesNotSendAttitudeAngularSpeedIfCallbackNotCalled) +{ + std::vector angular_speeds; + auto angular_speed_stream_future = subscribeAttitudeAngularSpeedAsync(angular_speeds); + + _telemetry_service->stop(); + angular_speed_stream_future.wait(); + + EXPECT_EQ(0, angular_speeds.size()); +} + TEST_F(TelemetryServiceImplTest, sendsOneAttitudeQuaternion) { std::vector quaternions; @@ -1008,6 +1080,14 @@ TEST_F(TelemetryServiceImplTest, sendsOneAttitudeQuaternion) checkSendsAttitudeQuaternions(quaternions); } +TEST_F(TelemetryServiceImplTest, sendsOneAttitudeAngularSpeed) +{ + std::vector angular_speed; + angular_speed.push_back(createAngularSpeed(0.1f, 0.2f, 0.3f)); + + checkSendsAttitudeAngularSpeeds(angular_speed); +} + Quaternion TelemetryServiceImplTest::createQuaternion( const float w, const float x, const float y, const float z) const { @@ -1021,6 +1101,18 @@ Quaternion TelemetryServiceImplTest::createQuaternion( return quaternion; } +AngularSpeed TelemetryServiceImplTest::createAngularSpeed( + const float rollspeed, const float pitchspeed, const float yawspeed) const +{ + mavsdk::Telemetry::AngularSpeed angular_speed; + + angular_speed.rollspeed = rollspeed; + angular_speed.pitchspeed = pitchspeed; + angular_speed.yawspeed = yawspeed; + + return angular_speed; +} + void TelemetryServiceImplTest::checkSendsAttitudeQuaternions( const std::vector& quaternions) const { @@ -1045,6 +1137,30 @@ void TelemetryServiceImplTest::checkSendsAttitudeQuaternions( } } +void TelemetryServiceImplTest::checkSendsAttitudeAngularSpeeds( + const std::vector& angular_speeds) const +{ + std::promise subscription_promise; + auto subscription_future = subscription_promise.get_future(); + mavsdk::Telemetry::attitude_angular_speed_callback_t attitude_angular_speed_callback; + EXPECT_CALL(*_telemetry, attitude_angular_speed_async(_)) + .WillOnce(SaveCallback(&attitude_angular_speed_callback, &subscription_promise)); + + std::vector received_angular_speeds; + auto angular_speed_stream_future = subscribeAttitudeAngularSpeedAsync(received_angular_speeds); + subscription_future.wait(); + for (const auto angular_speed : angular_speeds) { + attitude_angular_speed_callback(angular_speed); + } + _telemetry_service->stop(); + angular_speed_stream_future.wait(); + + ASSERT_EQ(angular_speeds.size(), received_angular_speeds.size()); + for (size_t i = 0; i < angular_speeds.size(); i++) { + EXPECT_EQ(angular_speeds.at(i), received_angular_speeds.at(i)); + } +} + TEST_F(TelemetryServiceImplTest, sendsMultipleAttitudeQuaternions) { std::vector quaternions; @@ -1055,6 +1171,16 @@ TEST_F(TelemetryServiceImplTest, sendsMultipleAttitudeQuaternions) checkSendsAttitudeQuaternions(quaternions); } +TEST_F(TelemetryServiceImplTest, sendsMultipleAttitudeAngularSpeeds) +{ + std::vector angular_speed; + angular_speed.push_back(createAngularSpeed(0.1f, 0.2f, 0.3f)); + angular_speed.push_back(createAngularSpeed(2.1f, 0.4f, -2.2f)); + angular_speed.push_back(createAngularSpeed(5.2f, 5.9f, 1.1f)); + + checkSendsAttitudeAngularSpeeds(angular_speed); +} + TEST_F(TelemetryServiceImplTest, registersToTelemetryAttitudeEulerAsync) { EXPECT_CALL(*_telemetry, attitude_euler_angle_async(_)).Times(1); @@ -1523,6 +1649,58 @@ void TelemetryServiceImplTest::checkSendsRcStatusEvents( } } +std::future TelemetryServiceImplTest::subscribeActuatorControlTargetAsync( + std::vector& actuator_control_target_events) const +{ + return std::async(std::launch::async, [&]() { + grpc::ClientContext context; + mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest request; + auto response_reader = _stub->SubscribeActuatorControlTarget(&context, request); + + mavsdk::rpc::telemetry::ActuatorControlTargetResponse response; + while (response_reader->Read(&response)) { + auto actuator_control_target_rpc = response.actuator_control_target(); + + ActuatorControlTarget actuator_control_target{}; + actuator_control_target.group = actuator_control_target_rpc.group(); + int num_controls = std::min(8, actuator_control_target_rpc.controls_size()); + for (int i = 0; i < num_controls; i++) { + actuator_control_target.controls[i] = actuator_control_target_rpc.controls(i); + } + + actuator_control_target_events.push_back(actuator_control_target); + } + + response_reader->Finish(); + }); +} + +std::future TelemetryServiceImplTest::subscribeActuatorOutputStatusAsync( + std::vector& actuator_output_status_events) const +{ + return std::async(std::launch::async, [&]() { + grpc::ClientContext context; + mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest request; + auto response_reader = _stub->SubscribeActuatorOutputStatus(&context, request); + + mavsdk::rpc::telemetry::ActuatorOutputStatusResponse response; + while (response_reader->Read(&response)) { + auto actuator_output_status_rpc = response.actuator_output_status(); + + ActuatorOutputStatus actuator_output_status{}; + actuator_output_status.active = actuator_output_status_rpc.active(); + int num_actuators = std::min(32, actuator_output_status_rpc.actuator_size()); + for (int i = 0; i < num_actuators; i++) { + actuator_output_status.actuator[i] = actuator_output_status_rpc.actuator(i); + } + + actuator_output_status_events.push_back(actuator_output_status); + } + + response_reader->Finish(); + }); +} + TEST_F(TelemetryServiceImplTest, sendsMultipleRcStatusEvents) { std::vector rc_status_events; @@ -1533,4 +1711,108 @@ TEST_F(TelemetryServiceImplTest, sendsMultipleRcStatusEvents) checkSendsRcStatusEvents(rc_status_events); } +ActuatorControlTarget TelemetryServiceImplTest::createActuatorControlTarget( + const uint8_t group, const float* controls) const +{ + ActuatorControlTarget actuator_control_target; + + actuator_control_target.group = group; + std::copy(controls, controls + 8, actuator_control_target.controls); + + return actuator_control_target; +} + +ActuatorOutputStatus TelemetryServiceImplTest::createActuatorOutputStatus( + const uint8_t active, const float* actuators) const +{ + ActuatorOutputStatus actuator_output_status; + + actuator_output_status.active = active; + std::copy(actuators, actuators + active, actuator_output_status.actuator); + + return actuator_output_status; +} + +void TelemetryServiceImplTest::checkSendsActuatorControlTargetEvents( + const std::vector& actuator_control_target_events) const +{ + std::promise subscription_promise; + auto subscription_future = subscription_promise.get_future(); + mavsdk::Telemetry::actuator_control_target_callback_t actuator_control_target_callback; + EXPECT_CALL(*_telemetry, actuator_control_target_async(_)) + .WillOnce(SaveCallback(&actuator_control_target_callback, &subscription_promise)); + + std::vector received_actuator_control_target_events; + auto actuator_control_target_stream_future = + subscribeActuatorControlTargetAsync(received_actuator_control_target_events); + subscription_future.wait(); + for (const auto actuator_control_target : actuator_control_target_events) { + actuator_control_target_callback(actuator_control_target); + } + _telemetry_service->stop(); + actuator_control_target_stream_future.wait(); + + ASSERT_EQ( + actuator_control_target_events.size(), received_actuator_control_target_events.size()); + for (size_t i = 0; i < actuator_control_target_events.size(); i++) { + EXPECT_EQ( + actuator_control_target_events.at(i), received_actuator_control_target_events.at(i)); + } +} + +void TelemetryServiceImplTest::checkSendsActuatorOutputStatusEvents( + const std::vector& actuator_output_status_events) const +{ + std::promise subscription_promise; + auto subscription_future = subscription_promise.get_future(); + mavsdk::Telemetry::actuator_output_status_callback_t actuator_output_status_callback; + EXPECT_CALL(*_telemetry, actuator_output_status_async(_)) + .WillOnce(SaveCallback(&actuator_output_status_callback, &subscription_promise)); + + std::vector received_actuator_output_status_events; + auto actuator_output_status_stream_future = + subscribeActuatorOutputStatusAsync(received_actuator_output_status_events); + subscription_future.wait(); + for (const auto actuator_output_status : actuator_output_status_events) { + actuator_output_status_callback(actuator_output_status); + } + _telemetry_service->stop(); + actuator_output_status_stream_future.wait(); + + ASSERT_EQ(actuator_output_status_events.size(), received_actuator_output_status_events.size()); + for (size_t i = 0; i < actuator_output_status_events.size(); i++) { + EXPECT_EQ( + actuator_output_status_events.at(i), received_actuator_output_status_events.at(i)); + } +} + +TEST_F(TelemetryServiceImplTest, sendsMultipleActuatorControlTargetEvents) +{ + std::vector actuator_control_target_events; + const float controls[8] = {0.0f, 0.1, 0.2f, 0.3f, 0.4f, 0.5f, 0.6f, 0.7f}; + actuator_control_target_events.push_back(createActuatorControlTarget(0, controls)); + actuator_control_target_events.push_back(createActuatorControlTarget(1, controls)); + actuator_control_target_events.push_back(createActuatorControlTarget(2, controls)); + actuator_control_target_events.push_back(createActuatorControlTarget(3, controls)); + + checkSendsActuatorControlTargetEvents(actuator_control_target_events); +} + +TEST_F(TelemetryServiceImplTest, sendsMultipleActuatorOutputStatusEvents) +{ + std::vector actuator_output_status_events; + + float actuators[32]{}; + for (int i = 0; i < 32; i++) { + actuators[i] = i * 2; + }; + + actuator_output_status_events.push_back(createActuatorOutputStatus(8, actuators)); + actuator_output_status_events.push_back(createActuatorOutputStatus(10, actuators)); + actuator_output_status_events.push_back(createActuatorOutputStatus(17, actuators)); + actuator_output_status_events.push_back(createActuatorOutputStatus(32, actuators)); + + checkSendsActuatorOutputStatusEvents(actuator_output_status_events); +} + } // namespace diff --git a/src/integration_tests/telemetry_async.cpp b/src/integration_tests/telemetry_async.cpp index 23bf2ba9e3..41d2d805cb 100644 --- a/src/integration_tests/telemetry_async.cpp +++ b/src/integration_tests/telemetry_async.cpp @@ -17,6 +17,7 @@ static void print_in_air(bool in_air); static void print_armed(bool armed); static void print_quaternion(Telemetry::Quaternion quaternion); static void print_euler_angle(Telemetry::EulerAngle euler_angle); +static void print_angular_speed(Telemetry::AngularSpeed angular_speed); #if CAMERA_AVAILABLE == 1 static void print_camera_quaternion(Telemetry::Quaternion quaternion); static void print_camera_euler_angle(Telemetry::EulerAngle euler_angle); @@ -28,6 +29,8 @@ static void print_battery(Telemetry::Battery battery); static void print_rc_status(Telemetry::RCStatus rc_status); static void print_position_velocity_ned(Telemetry::PositionVelocityNED position_velocity_ned); static void print_unix_epoch_time_us(uint64_t time_us); +static void print_actuator_control_target(Telemetry::ActuatorControlTarget actuator_control_target); +static void print_actuator_output_status(Telemetry::ActuatorOutputStatus actuator_output_status); static bool _set_rate_error = false; static bool _received_position = false; @@ -36,6 +39,7 @@ static bool _received_in_air = false; static bool _received_armed = false; static bool _received_quaternion = false; static bool _received_euler_angle = false; +static bool _received_angular_speed = false; #if CAMERA_AVAILABLE == 1 static bool _received_camera_quaternion = false; static bool _received_camera_euler_angle = false; @@ -46,6 +50,8 @@ static bool _received_gps_info = false; static bool _received_battery = false; static bool _received_rc_status = false; static bool _received_position_velocity_ned = false; +static bool _received_actuator_control_target = false; +static bool _received_actuator_output_status = false; TEST_F(SitlTest, TelemetryAsync) { @@ -95,6 +101,9 @@ TEST_F(SitlTest, TelemetryAsync) telemetry->set_rate_battery_async(10.0, std::bind(&receive_result, _1)); std::this_thread::sleep_for(std::chrono::milliseconds(100)); + telemetry->set_rate_actuator_control_target_async(10.0, std::bind(&receive_result, _1)); + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + telemetry->position_async(std::bind(&print_position, _1)); telemetry->home_position_async(std::bind(&print_home_position, _1)); @@ -107,6 +116,8 @@ TEST_F(SitlTest, TelemetryAsync) telemetry->attitude_euler_angle_async(std::bind(&print_euler_angle, _1)); + telemetry->attitude_angular_speed_async(std::bind(&print_angular_speed, _1)); + #if CAMERA_AVAILABLE == 1 telemetry->camera_attitude_quaternion_async(std::bind(&print_camera_quaternion, _1)); @@ -127,6 +138,10 @@ TEST_F(SitlTest, TelemetryAsync) telemetry->unix_epoch_time_async(std::bind(&print_unix_epoch_time_us, _1)); + telemetry->actuator_control_target_async(std::bind(&print_actuator_control_target, _1)); + + telemetry->actuator_output_status_async(std::bind(&print_actuator_output_status, _1)); + std::this_thread::sleep_for(std::chrono::seconds(10)); EXPECT_FALSE(_set_rate_error); @@ -135,6 +150,7 @@ TEST_F(SitlTest, TelemetryAsync) EXPECT_TRUE(_received_in_air); EXPECT_TRUE(_received_armed); EXPECT_TRUE(_received_quaternion); + EXPECT_TRUE(_received_angular_speed); EXPECT_TRUE(_received_euler_angle); #if CAMERA_AVAILABLE == 1 EXPECT_TRUE(_received_camera_quaternion); @@ -146,6 +162,8 @@ TEST_F(SitlTest, TelemetryAsync) EXPECT_TRUE(_received_battery); // EXPECT_TRUE(_received_rc_status); // No RC is sent in SITL. EXPECT_TRUE(_received_position_velocity_ned); + // EXPECT_TRUE(_received_actuator_control_target); TODO check is that sent in SITL. + // EXPECT_TRUE(_received_actuator_output_status); TODO check is that sent in SITL. } void receive_result(Telemetry::Result result) @@ -201,6 +219,14 @@ void print_euler_angle(Telemetry::EulerAngle euler_angle) _received_euler_angle = true; } +void print_angular_speed(Telemetry::AngularSpeed angular_speed) +{ + std::cout << "Angular speed: [ " << angular_speed.rollspeed << ", " << angular_speed.pitchspeed + << ", " << angular_speed.yawspeed << " ] rad/s" << std::endl; + + _received_angular_speed = true; +} + #if CAMERA_AVAILABLE == 1 void print_camera_quaternion(Telemetry::Quaternion quaternion) { @@ -293,3 +319,33 @@ void print_unix_epoch_time_us(uint64_t time_us) LogInfo() << time_string; #endif } + +static void print_actuator_control_target(Telemetry::ActuatorControlTarget actuator_control_target) +{ + std::cout << "Group: " << static_cast(actuator_control_target.group) << ", Controls: ["; + for (int i = 0; i < 8; i++) { + std::cout << actuator_control_target.controls[i]; + if (i != 7) { + std::cout << ", "; + } else { + std::cout << "]" << std::endl; + } + } + + _received_actuator_control_target = true; +} + +static void print_actuator_output_status(Telemetry::ActuatorOutputStatus actuator_output_status) +{ + std::cout << "Active: " << actuator_output_status.active << ", Actuators: ["; + for (unsigned i = 0; i < actuator_output_status.active; i++) { + std::cout << actuator_output_status.actuator[i]; + if (i != (actuator_output_status.active - 1)) { + std::cout << ", "; + } else { + std::cout << "]" << std::endl; + } + } + + _received_actuator_output_status = true; +} \ No newline at end of file diff --git a/src/integration_tests/telemetry_sync.cpp b/src/integration_tests/telemetry_sync.cpp index 95cf1a2769..abba753803 100644 --- a/src/integration_tests/telemetry_sync.cpp +++ b/src/integration_tests/telemetry_sync.cpp @@ -36,6 +36,8 @@ TEST_F(SitlTest, TelemetrySync) ASSERT_EQ(result, Telemetry::Result::SUCCESS); result = telemetry->set_rate_battery(10.0); ASSERT_EQ(result, Telemetry::Result::SUCCESS); + result = telemetry->set_rate_actuator_control_target(10.0); + ASSERT_EQ(result, Telemetry::Result::SUCCESS); // Print 3s of telemetry. for (unsigned i = 0; i < 50; ++i) { @@ -63,6 +65,10 @@ TEST_F(SitlTest, TelemetrySync) std::cout << "Euler: (" << euler_angle.roll_deg << " deg, " << euler_angle.pitch_deg << " deg," << euler_angle.yaw_deg << " deg)" << std::endl; + const Telemetry::AngularSpeed& angular_speed = telemetry->attitude_angular_speed(); + std::cout << "Angular speed: (" << angular_speed.rollspeed << ", " + << angular_speed.pitchspeed << "," << angular_speed.yawspeed << ")" << std::endl; + const Telemetry::GroundSpeedNED& ground_speed_ned = telemetry->ground_speed_ned(); std::cout << "Speed: (" << ground_speed_ned.velocity_north_m_s << " m/s, " << ground_speed_ned.velocity_east_m_s << " m/s," @@ -76,6 +82,19 @@ TEST_F(SitlTest, TelemetrySync) std::cout << "Battery voltage: " << battery.voltage_v << " v, " << "remaining: " << battery.remaining_percent * 100.0f << " %" << std::endl; + const Telemetry::ActuatorControlTarget& actuator_control_target = + telemetry->actuator_control_target(); + std::cout << "Actuator control target: group: " << actuator_control_target.group + << ", controls: ["; + for (int k = 0; k < 8; k++) { + std::cout << actuator_control_target.controls[i]; + if (k < 7) { + std::cout << ", "; + } else { + std::cout << "]" << std::endl; + } + } + std::this_thread::sleep_for(std::chrono::milliseconds(30)); } } diff --git a/src/plugins/telemetry/include/plugins/telemetry/telemetry.h b/src/plugins/telemetry/include/plugins/telemetry/telemetry.h index a65689900f..44a36165e7 100644 --- a/src/plugins/telemetry/include/plugins/telemetry/telemetry.h +++ b/src/plugins/telemetry/include/plugins/telemetry/telemetry.h @@ -109,6 +109,17 @@ class Telemetry : public PluginBase { float yaw_deg; /**< @brief Yaw angle in degrees, positive is clock-wise seen from above. */ }; + /** + * @brief Angular speed type. + * + * The angular speed of vehicle body in radians/second. + */ + struct AngularSpeed { + float rollspeed; /**< @brief Roll angular speed */ + float pitchspeed; /**< @brief Pitch angular speed */ + float yawspeed; /**< @brief Yaw angular speed */ + }; + /** * @brief Ground speed type. * @@ -249,7 +260,34 @@ class Telemetry : public PluginBase { bool available_once; /**< @brief true if an RC signal has been available once. */ bool available; /**< @brief true if the RC signal is available now. */ float signal_strength_percent; /**< @brief Signal strength as a percentage (range: 0 to - 100). */ + 100). */ + }; + + /** + * @brief The vehicle actuator's rate control type. + * + * An actuator's control group is e.g. attitude, for the core flight controls, or gimbal for + * payload. For more information about PX4 groups, check out + * https://dev.px4.io/v1.9.0/en/concept/mixing.html#control-pipeline + * + * Actuator controls normed to -1..+1 where 0 is neutral position. Throttle for single rotation + * direction motors is 0..1, negative range for reverse direction. + * + * For more information about controls, check out + * https://mavlink.io/en/messages/common.html#SET_ACTUATOR_CONTROL_TARGET + * + */ + struct ActuatorControlTarget { + uint8_t group; /**< @brief Actuator group. */ + float controls[8]; /**< @brief Actuator controls. */ + }; + + /** + * @brief The raw values of the actuator outputs type. + */ + struct ActuatorOutputStatus { + uint32_t active; /**< @brief Active outputs */ + float actuator[32]; /**< @brief Servo / motor output array values. */ }; /** @@ -389,6 +427,26 @@ class Telemetry : public PluginBase { */ Result set_rate_rc_status(double rate_hz); + /** + * @brief Set rate of actuator controls updates (synchronous). + * + * @note To stop sending it completely, use a rate_hz of -1, for default rate use 0. + * + * @param rate_hz Rate in Hz. + * @return Result of request. + */ + Result set_rate_actuator_control_target(double rate_hz); + + /** + * @brief Set rate of actuator output status updates (synchronous). + * + * @note o stop sending it completely, use a rate_hz of -1, for default rate use 0. + * + * @param rate_hz Rate in Hz. + * @return Result of request. + */ + Result set_rate_actuator_output_status(double rate_hz); + /** * @brief Set rate of kinematic (position and velocity) updates (asynchronous). * @@ -499,6 +557,26 @@ class Telemetry : public PluginBase { */ void set_rate_rc_status_async(double rate_hz, result_callback_t callback); + /** + * @brief Set rate of actuator control target updates (asynchronous). + * + * @note To stop sending it completely, use a rate_hz of -1, for default rate use 0. + * + * @param rate_hz Rate in Hz. + * @return callback Callback to receive request result. + */ + void set_rate_actuator_control_target_async(double rate_hz, result_callback_t callback); + + /** + * @brief et rate of actuator control target updates (asynchronous). + * + * @note To stop sending it completely, use a rate_hz of -1, for default rate use 0. + * + * @param rate_hz Rate in Hz. + * @return callback Callback to receive request result. + */ + void set_rate_actuator_output_status_async(double rate_hz, result_callback_t callback); + /** * @brief Set rate of Unix Epoch Time update (asynchronous). * @@ -563,6 +641,13 @@ class Telemetry : public PluginBase { */ EulerAngle attitude_euler_angle() const; + /** + * @brief Get the current angular speed in rad/s (synchronous). + * + * @return Angular speed. + */ + AngularSpeed attitude_angular_speed() const; + /** * @brief Get the camera's attitude in quaternions (synchronous). * @@ -635,6 +720,20 @@ class Telemetry : public PluginBase { */ RCStatus rc_status() const; + /** + * @brief Get the actuator control target (synchronous). + * + * @return Actuator control target + */ + ActuatorControlTarget actuator_control_target() const; + + /** + * @brief Get the actuator output status (synchronous). + * + * @return Actuator output status + */ + ActuatorOutputStatus actuator_output_status() const; + /** * @brief Callback type for kinematic (position and velocity) updates. */ @@ -738,6 +837,20 @@ class Telemetry : public PluginBase { */ void attitude_euler_angle_async(attitude_euler_angle_callback_t callback); + /** + * @brief Callback type for angular speed updates in quaternion. + * + * @param angular_speed Angular speed. + */ + typedef std::function attitude_angular_speed_callback_t; + + /** + * @brief Subscribe to attitude updates in angular speed (asynchronous). + * + * @param callback Function to call with updates. + */ + void attitude_angular_speed_async(attitude_angular_speed_callback_t callback); + /** * @brief Subscribe to camera attitude updates in quaternion (asynchronous). * @@ -870,6 +983,36 @@ class Telemetry : public PluginBase { */ typedef std::function unix_epoch_time_callback_t; + /** + * @brief Callback type for actuator control target updates (asynchronous). + * + * @param actuator_control_target Actuator control target. + */ + typedef std::function + actuator_control_target_callback_t; + + /** + * @brief Subscribe to actuator control target updates (asynchronous). + * + * @param callback Function to call with updates. + */ + void actuator_control_target_async(actuator_control_target_callback_t callback); + + /** + * @brief Callback type for actuator output status target updates (asynchronous). + * + * @param callback Function to call with updates. + */ + typedef std::function + actuator_output_status_callback_t; + + /** + * @brief Subscribe to actuator output status target updates (asynchronous). + * + * @param callback Function to call with updates. + */ + void actuator_output_status_async(actuator_output_status_callback_t callback); + /** * @brief Subscribe to RC status updates (asynchronous). * @@ -1049,6 +1192,20 @@ bool operator==(const Telemetry::EulerAngle& lhs, const Telemetry::EulerAngle& r */ std::ostream& operator<<(std::ostream& str, Telemetry::EulerAngle const& euler_angle); +/** + * @brief Equal operator to compare two `Telemetry::AngularSpeed` objects. + * + * @return `true` if items are equal. + */ +bool operator==(const Telemetry::AngularSpeed& lhs, const Telemetry::AngularSpeed& rhs); + +/** + * @brief Stream operator to print information about a `Telemetry::AngularSpeed`. + * + * @return A reference to the stream. + */ +std::ostream& operator<<(std::ostream& str, Telemetry::AngularSpeed const& angular_speed); + /** * @brief Equal operator to compare two `Telemetry::GroundSpeedNED` objects. * @@ -1084,4 +1241,36 @@ std::ostream& operator<<(std::ostream& str, Telemetry::RCStatus const& rc_status */ std::ostream& operator<<(std::ostream& str, Telemetry::StatusText const& status_text); +/** + * @brief Equal operator to compare two `Telemetry::ActuatorControlTarget` objects. + * + * @return `true` if items are equal. + */ +bool operator==( + const Telemetry::ActuatorControlTarget& lhs, const Telemetry::ActuatorControlTarget& rhs); + +/** + * @brief Stream operator to print information about a `Telemetry::ActuatorControlTarget`. + * + * @returns A reference to the stream. + */ +std::ostream& +operator<<(std::ostream& str, Telemetry::ActuatorControlTarget const& actuator_control_target); + +/** + * @brief Equal operator to compare two `Telemetry::ActuatorOutputStatus` objects. + * + * @return `true` if items are equal. + */ +bool operator==( + const Telemetry::ActuatorOutputStatus& lhs, const Telemetry::ActuatorOutputStatus& rhs); + +/** + * @brief Stream operator to print information about a `Telemetry::ActuatorControlTarget`. + * + * @returns A reference to the stream. + */ +std::ostream& +operator<<(std::ostream& str, Telemetry::ActuatorOutputStatus const& actuator_output_status); + } // namespace mavsdk diff --git a/src/plugins/telemetry/mocks/telemetry_mock.h b/src/plugins/telemetry/mocks/telemetry_mock.h index 1d24a1d8db..db9f96920b 100644 --- a/src/plugins/telemetry/mocks/telemetry_mock.h +++ b/src/plugins/telemetry/mocks/telemetry_mock.h @@ -18,6 +18,8 @@ class MockTelemetry { MOCK_CONST_METHOD1(flight_mode_async, void(Telemetry::flight_mode_callback_t)){}; MOCK_CONST_METHOD1( attitude_quaternion_async, void(Telemetry::attitude_quaternion_callback_t)){}; + MOCK_CONST_METHOD1( + attitude_angular_speed_async, void(Telemetry::attitude_angular_speed_callback_t)){}; MOCK_CONST_METHOD1( attitude_euler_angle_async, void(Telemetry::attitude_euler_angle_callback_t)){}; MOCK_CONST_METHOD1( @@ -26,6 +28,10 @@ class MockTelemetry { camera_attitude_euler_angle_async, void(Telemetry::attitude_euler_angle_callback_t)){}; MOCK_CONST_METHOD1(ground_speed_ned_async, void(Telemetry::ground_speed_ned_callback_t)){}; MOCK_CONST_METHOD1(rc_status_async, void(Telemetry::rc_status_callback_t)){}; + MOCK_CONST_METHOD1( + actuator_control_target_async, void(Telemetry::actuator_control_target_callback_t)){}; + MOCK_CONST_METHOD1( + actuator_output_status_async, void(Telemetry::actuator_output_status_callback_t)){}; }; } // namespace testing diff --git a/src/plugins/telemetry/telemetry.cpp b/src/plugins/telemetry/telemetry.cpp index 737f18477f..f89caf8b6b 100644 --- a/src/plugins/telemetry/telemetry.cpp +++ b/src/plugins/telemetry/telemetry.cpp @@ -65,6 +65,16 @@ Telemetry::Result Telemetry::set_rate_rc_status(double rate_hz) return _impl->set_rate_rc_status(rate_hz); } +Telemetry::Result Telemetry::set_rate_actuator_control_target(double rate_hz) +{ + return _impl->set_rate_actuator_control_target(rate_hz); +} + +Telemetry::Result Telemetry::set_rate_actuator_output_status(double rate_hz) +{ + return _impl->set_rate_actuator_output_status(rate_hz); +} + void Telemetry::set_rate_position_velocity_ned_async(double rate_hz, result_callback_t callback) { _impl->set_rate_position_velocity_ned_async(rate_hz, callback); @@ -125,6 +135,16 @@ void Telemetry::set_unix_epoch_time_async(double rate_hz, result_callback_t call _impl->set_rate_unix_epoch_time_async(rate_hz, callback); } +void Telemetry::set_rate_actuator_control_target_async(double rate_hz, result_callback_t callback) +{ + _impl->set_rate_actuator_control_target_async(rate_hz, callback); +} + +void Telemetry::set_rate_actuator_output_status_async(double rate_hz, result_callback_t callback) +{ + _impl->set_rate_actuator_output_status_async(rate_hz, callback); +} + Telemetry::PositionVelocityNED Telemetry::position_velocity_ned() const { return _impl->get_position_velocity_ned(); @@ -165,6 +185,11 @@ Telemetry::EulerAngle Telemetry::attitude_euler_angle() const return _impl->get_attitude_euler_angle(); } +Telemetry::AngularSpeed Telemetry::attitude_angular_speed() const +{ + return _impl->get_attitude_angular_speed(); +} + Telemetry::Quaternion Telemetry::camera_attitude_quaternion() const { return _impl->get_camera_attitude_quaternion(); @@ -215,6 +240,16 @@ Telemetry::RCStatus Telemetry::rc_status() const return _impl->get_rc_status(); } +Telemetry::ActuatorControlTarget Telemetry::actuator_control_target() const +{ + return _impl->get_actuator_control_target(); +} + +Telemetry::ActuatorOutputStatus Telemetry::actuator_output_status() const +{ + return _impl->get_actuator_output_status(); +} + void Telemetry::position_velocity_ned_async(position_velocity_ned_callback_t callback) { return _impl->position_velocity_ned_async(callback); @@ -255,6 +290,11 @@ void Telemetry::attitude_euler_angle_async(attitude_euler_angle_callback_t callb return _impl->attitude_euler_angle_async(callback); } +void Telemetry::attitude_angular_speed_async(attitude_angular_speed_callback_t callback) +{ + return _impl->attitude_angular_speed_async(callback); +} + void Telemetry::camera_attitude_quaternion_async(attitude_quaternion_callback_t callback) { return _impl->camera_attitude_quaternion_async(callback); @@ -290,6 +330,16 @@ void Telemetry::flight_mode_async(flight_mode_callback_t callback) return _impl->flight_mode_async(callback); } +void Telemetry::actuator_control_target_async(actuator_control_target_callback_t callback) +{ + return _impl->actuator_control_target_async(callback); +} + +void Telemetry::actuator_output_status_async(actuator_output_status_callback_t callback) +{ + return _impl->actuator_output_status_async(callback); +} + std::string Telemetry::flight_mode_str(FlightMode flight_mode) { switch (flight_mode) { @@ -546,6 +596,19 @@ std::ostream& operator<<(std::ostream& str, Telemetry::EulerAngle const& euler_a << ", yaw_deg: " << euler_angle.yaw_deg << "]"; } +bool operator==(const Telemetry::AngularSpeed& lhs, const Telemetry::AngularSpeed& rhs) +{ + return lhs.rollspeed == rhs.rollspeed && lhs.pitchspeed == rhs.pitchspeed && + lhs.yawspeed == rhs.yawspeed; +} + +std::ostream& operator<<(std::ostream& str, Telemetry::AngularSpeed const& angular_speed) +{ + return str << "[rollspeed: " << angular_speed.rollspeed + << ", pitchspeed: " << angular_speed.pitchspeed + << ", yawspeed: " << angular_speed.yawspeed << "]"; +} + bool operator==(const Telemetry::GroundSpeedNED& lhs, const Telemetry::GroundSpeedNED& rhs) { return lhs.velocity_north_m_s == rhs.velocity_north_m_s && @@ -583,4 +646,58 @@ std::ostream& operator<<(std::ostream& str, Telemetry::StatusText const& status_ return str << "[statustext: " << status_text.text << "]"; } +bool operator==( + const Telemetry::ActuatorControlTarget& lhs, const Telemetry::ActuatorControlTarget& rhs) +{ + if (lhs.group != rhs.group) + return false; + for (int i = 0; i < 8; i++) { + if (lhs.controls[i] != rhs.controls[i]) + return false; + } + return true; +} + +std::ostream& +operator<<(std::ostream& str, Telemetry::ActuatorControlTarget const& actuator_control_target) +{ + str << "Group: " << static_cast(actuator_control_target.group) << ", Controls: ["; + for (int i = 0; i < 8; i++) { + str << actuator_control_target.controls[i]; + if (i != 7) { + str << ", "; + } else { + str << "]"; + } + } + return str; +} + +bool operator==( + const Telemetry::ActuatorOutputStatus& lhs, const Telemetry::ActuatorOutputStatus& rhs) +{ + if (lhs.active != rhs.active) + return false; + for (unsigned i = 0; i < lhs.active; i++) { + if (lhs.actuator[i] != rhs.actuator[i]) + return false; + } + return true; +} + +std::ostream& +operator<<(std::ostream& str, Telemetry::ActuatorOutputStatus const& actuator_output_status) +{ + str << "Active: " << actuator_output_status.active << ", Actuators: ["; + for (unsigned i = 0; i < actuator_output_status.active; i++) { + str << actuator_output_status.actuator[i]; + if (i != (actuator_output_status.active - 1)) { + str << ", "; + } else { + str << "]" << std::endl; + } + } + return str; +} + } // namespace mavsdk diff --git a/src/plugins/telemetry/telemetry_impl.cpp b/src/plugins/telemetry/telemetry_impl.cpp index 797a1228f0..a256f526d3 100644 --- a/src/plugins/telemetry/telemetry_impl.cpp +++ b/src/plugins/telemetry/telemetry_impl.cpp @@ -68,6 +68,16 @@ void TelemetryImpl::init() _parent->register_mavlink_message_handler( MAVLINK_MSG_ID_RC_CHANNELS, std::bind(&TelemetryImpl::process_rc_channels, this, _1), this); + _parent->register_mavlink_message_handler( + MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, + std::bind(&TelemetryImpl::process_actuator_control_target, this, _1), + this); + + _parent->register_mavlink_message_handler( + MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, + std::bind(&TelemetryImpl::process_actuator_output_status, this, _1), + this); + _parent->register_mavlink_message_handler( MAVLINK_MSG_ID_UTM_GLOBAL_POSITION, std::bind(&TelemetryImpl::process_unix_epoch_time, this, _1), @@ -231,6 +241,18 @@ Telemetry::Result TelemetryImpl::set_rate_rc_status(double rate_hz) _parent->set_msg_rate(MAVLINK_MSG_ID_RC_CHANNELS, rate_hz)); } +Telemetry::Result TelemetryImpl::set_rate_actuator_control_target(double rate_hz) +{ + return telemetry_result_from_command_result( + _parent->set_msg_rate(MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, rate_hz)); +} + +Telemetry::Result TelemetryImpl::set_rate_actuator_output_status(double rate_hz) +{ + return telemetry_result_from_command_result( + _parent->set_msg_rate(MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, rate_hz)); +} + void TelemetryImpl::set_rate_position_velocity_ned_async( double rate_hz, Telemetry::result_callback_t callback) { @@ -339,6 +361,24 @@ void TelemetryImpl::set_rate_unix_epoch_time_async( std::bind(&TelemetryImpl::command_result_callback, std::placeholders::_1, callback)); } +void TelemetryImpl::set_rate_actuator_control_target_async( + double rate_hz, Telemetry::result_callback_t callback) +{ + _parent->set_msg_rate_async( + MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, + rate_hz, + std::bind(&TelemetryImpl::command_result_callback, std::placeholders::_1, callback)); +} + +void TelemetryImpl::set_rate_actuator_output_status_async( + double rate_hz, Telemetry::result_callback_t callback) +{ + _parent->set_msg_rate_async( + MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, + rate_hz, + std::bind(&TelemetryImpl::command_result_callback, std::placeholders::_1, callback)); +} + Telemetry::Result TelemetryImpl::telemetry_result_from_command_result(MAVLinkCommands::Result command_result) { @@ -440,8 +480,14 @@ void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message attitude_quaternion.q3, attitude_quaternion.q4}; + Telemetry::AngularSpeed angular_speed{attitude_quaternion.rollspeed, + attitude_quaternion.pitchspeed, + attitude_quaternion.yawspeed}; + set_attitude_quaternion(quaternion); + set_attitude_angular_speed(angular_speed); + if (_attitude_quaternion_subscription) { auto callback = _attitude_quaternion_subscription; auto arg = get_attitude_quaternion(); @@ -453,6 +499,12 @@ void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message auto arg = get_attitude_euler_angle(); _parent->call_user_callback([callback, arg]() { callback(arg); }); } + + if (_attitude_angular_speed_subscription) { + auto callback = _attitude_angular_speed_subscription; + auto arg = get_attitude_angular_speed(); + _parent->call_user_callback([callback, arg]() { callback(arg); }); + } } void TelemetryImpl::process_mount_orientation(const mavlink_message_t& message) @@ -671,6 +723,35 @@ void TelemetryImpl::process_unix_epoch_time(const mavlink_message_t& message) _parent->refresh_timeout_handler(_unix_epoch_timeout_cookie); } +void TelemetryImpl::process_actuator_control_target(const mavlink_message_t& message) +{ + mavlink_actuator_control_target_t actuator_control_target; + mavlink_msg_actuator_control_target_decode(&message, &actuator_control_target); + + set_actuator_control_target( + actuator_control_target.group_mlx, actuator_control_target.controls); + + if (_actuator_control_target_subscription) { + auto callback = _actuator_control_target_subscription; + auto arg = get_actuator_control_target(); + _parent->call_user_callback([callback, arg]() { callback(arg); }); + } +} + +void TelemetryImpl::process_actuator_output_status(const mavlink_message_t& message) +{ + mavlink_actuator_output_status_t actuator_output_status; + mavlink_msg_actuator_output_status_decode(&message, &actuator_output_status); + + set_actuator_output_status(actuator_output_status.active, actuator_output_status.actuator); + + if (_actuator_output_status_subscription) { + auto callback = _actuator_output_status_subscription; + auto arg = get_actuator_output_status(); + _parent->call_user_callback([callback, arg]() { callback(arg); }); + } +} + Telemetry::FlightMode TelemetryImpl::to_flight_mode_from_custom_mode(uint32_t custom_mode) { px4::px4_custom_mode px4_custom_mode; @@ -862,6 +943,12 @@ Telemetry::Quaternion TelemetryImpl::get_attitude_quaternion() const return _attitude_quaternion; } +Telemetry::AngularSpeed TelemetryImpl::get_attitude_angular_speed() const +{ + std::lock_guard lock(_attitude_angular_speed_mutex); + return _attitude_angular_speed; +} + Telemetry::EulerAngle TelemetryImpl::get_attitude_euler_angle() const { std::lock_guard lock(_attitude_quaternion_mutex); @@ -876,6 +963,12 @@ void TelemetryImpl::set_attitude_quaternion(Telemetry::Quaternion quaternion) _attitude_quaternion = quaternion; } +void TelemetryImpl::set_attitude_angular_speed(Telemetry::AngularSpeed angular_speed) +{ + std::lock_guard lock(_attitude_quaternion_mutex); + _attitude_angular_speed = angular_speed; +} + Telemetry::Quaternion TelemetryImpl::get_camera_attitude_quaternion() const { std::lock_guard lock(_camera_attitude_euler_angle_mutex); @@ -987,6 +1080,18 @@ uint64_t TelemetryImpl::get_unix_epoch_time_us() const return _unix_epoch_time_us; } +Telemetry::ActuatorControlTarget TelemetryImpl::get_actuator_control_target() const +{ + std::lock_guard lock(_actuator_control_target_mutex); + return _actuator_control_target; +} + +Telemetry::ActuatorOutputStatus TelemetryImpl::get_actuator_output_status() const +{ + std::lock_guard lock(_actuator_output_status_mutex); + return _actuator_output_status; +} + void TelemetryImpl::set_health_local_position(bool ok) { std::lock_guard lock(_health_mutex); @@ -1049,6 +1154,20 @@ void TelemetryImpl::set_unix_epoch_time_us(uint64_t time_us) _unix_epoch_time_us = time_us; } +void TelemetryImpl::set_actuator_control_target(uint8_t group, const float* controls) +{ + std::lock_guard lock(_actuator_control_target_mutex); + _actuator_control_target.group = group; + std::copy(controls, controls + 8, _actuator_control_target.controls); +} + +void TelemetryImpl::set_actuator_output_status(uint32_t active, const float* actuators) +{ + std::lock_guard lock(_actuator_output_status_mutex); + _actuator_output_status.active = active; + std::copy(actuators, actuators + active, _actuator_output_status.actuator); +} + void TelemetryImpl::position_velocity_ned_async( Telemetry::position_velocity_ned_callback_t& callback) { @@ -1090,6 +1209,12 @@ void TelemetryImpl::attitude_euler_angle_async(Telemetry::attitude_euler_angle_c _attitude_euler_angle_subscription = callback; } +void TelemetryImpl::attitude_angular_speed_async( + Telemetry::attitude_angular_speed_callback_t& callback) +{ + _attitude_angular_speed_subscription = callback; +} + void TelemetryImpl::camera_attitude_quaternion_async( Telemetry::attitude_quaternion_callback_t& callback) { @@ -1147,6 +1272,18 @@ void TelemetryImpl::unix_epoch_time_async(Telemetry::unix_epoch_time_callback_t& _unix_epoch_time_subscription = callback; } +void TelemetryImpl::actuator_control_target_async( + Telemetry::actuator_control_target_callback_t& callback) +{ + _actuator_control_target_subscription = callback; +} + +void TelemetryImpl::actuator_output_status_async( + Telemetry::actuator_output_status_callback_t& callback) +{ + _actuator_output_status_subscription = callback; +} + void TelemetryImpl::process_parameter_update(const std::string& name) { if (name.compare("CAL_GYRO0_ID") == 0) { diff --git a/src/plugins/telemetry/telemetry_impl.h b/src/plugins/telemetry/telemetry_impl.h index b802872371..fc8e2df145 100644 --- a/src/plugins/telemetry/telemetry_impl.h +++ b/src/plugins/telemetry/telemetry_impl.h @@ -38,6 +38,8 @@ class TelemetryImpl : public PluginImplBase { Telemetry::Result set_rate_gps_info(double rate_hz); Telemetry::Result set_rate_battery(double rate_hz); Telemetry::Result set_rate_rc_status(double rate_hz); + Telemetry::Result set_rate_actuator_control_target(double rate_hz); + Telemetry::Result set_rate_actuator_output_status(double rate_hz); void set_rate_position_velocity_ned_async(double rate_hz, Telemetry::result_callback_t callback); @@ -51,6 +53,10 @@ class TelemetryImpl : public PluginImplBase { void set_rate_gps_info_async(double rate_hz, Telemetry::result_callback_t callback); void set_rate_battery_async(double rate_hz, Telemetry::result_callback_t callback); void set_rate_rc_status_async(double rate_hz, Telemetry::result_callback_t callback); + void + set_rate_actuator_control_target_async(double rate_hz, Telemetry::result_callback_t callback); + void + set_rate_actuator_output_status_async(double rate_hz, Telemetry::result_callback_t callback); void set_rate_unix_epoch_time_async(double rate_hz, Telemetry::result_callback_t callback); Telemetry::PositionVelocityNED get_position_velocity_ned() const; @@ -61,6 +67,7 @@ class TelemetryImpl : public PluginImplBase { Telemetry::StatusText get_status_text() const; Telemetry::EulerAngle get_attitude_euler_angle() const; Telemetry::Quaternion get_attitude_quaternion() const; + Telemetry::AngularSpeed get_attitude_angular_speed() const; Telemetry::EulerAngle get_camera_attitude_euler_angle() const; Telemetry::Quaternion get_camera_attitude_quaternion() const; Telemetry::GroundSpeedNED get_ground_speed_ned() const; @@ -71,6 +78,8 @@ class TelemetryImpl : public PluginImplBase { Telemetry::Health get_health() const; bool get_health_all_ok() const; Telemetry::RCStatus get_rc_status() const; + Telemetry::ActuatorControlTarget get_actuator_control_target() const; + Telemetry::ActuatorOutputStatus get_actuator_output_status() const; uint64_t get_unix_epoch_time_us() const; void position_velocity_ned_async(Telemetry::position_velocity_ned_callback_t& callback); @@ -81,6 +90,7 @@ class TelemetryImpl : public PluginImplBase { void armed_async(Telemetry::armed_callback_t& callback); void attitude_quaternion_async(Telemetry::attitude_quaternion_callback_t& callback); void attitude_euler_angle_async(Telemetry::attitude_euler_angle_callback_t& callback); + void attitude_angular_speed_async(Telemetry::attitude_angular_speed_callback_t& callback); void camera_attitude_quaternion_async(Telemetry::attitude_quaternion_callback_t& callback); void camera_attitude_euler_angle_async(Telemetry::attitude_euler_angle_callback_t& callback); void ground_speed_ned_async(Telemetry::ground_speed_ned_callback_t& callback); @@ -92,6 +102,8 @@ class TelemetryImpl : public PluginImplBase { void health_all_ok_async(Telemetry::health_all_ok_callback_t& callback); void rc_status_async(Telemetry::rc_status_callback_t& callback); void unix_epoch_time_async(Telemetry::unix_epoch_time_callback_t& callback); + void actuator_control_target_async(Telemetry::actuator_control_target_callback_t& callback); + void actuator_output_status_async(Telemetry::actuator_output_status_callback_t& callback); TelemetryImpl(const TelemetryImpl&) = delete; TelemetryImpl& operator=(const TelemetryImpl&) = delete; @@ -104,6 +116,7 @@ class TelemetryImpl : public PluginImplBase { void set_status_text(Telemetry::StatusText status_text); void set_armed(bool armed); void set_attitude_quaternion(Telemetry::Quaternion quaternion); + void set_attitude_angular_speed(Telemetry::AngularSpeed angular_speed); void set_camera_attitude_euler_angle(Telemetry::EulerAngle euler_angle); void set_ground_speed_ned(Telemetry::GroundSpeedNED ground_speed_ned); void set_imu_reading_ned(Telemetry::IMUReadingNED imu_reading_ned); @@ -119,6 +132,8 @@ class TelemetryImpl : public PluginImplBase { void set_health_level_calibration(bool ok); void set_rc_status(bool available, float signal_strength_percent); void set_unix_epoch_time_us(uint64_t time_us); + void set_actuator_control_target(uint8_t group, const float* controls); + void set_actuator_output_status(uint32_t active, const float* actuators); void process_position_velocity_ned(const mavlink_message_t& message); void process_global_position_int(const mavlink_message_t& message); @@ -133,6 +148,8 @@ class TelemetryImpl : public PluginImplBase { void process_statustext(const mavlink_message_t& message); void process_rc_channels(const mavlink_message_t& message); void process_unix_epoch_time(const mavlink_message_t& message); + void process_actuator_control_target(const mavlink_message_t& message); + void process_actuator_output_status(const mavlink_message_t& message); void receive_param_cal_gyro(MAVLinkParameters::Result result, int value); void receive_param_cal_accel(MAVLinkParameters::Result result, int value); void receive_param_cal_mag(MAVLinkParameters::Result result, int value); @@ -180,6 +197,9 @@ class TelemetryImpl : public PluginImplBase { mutable std::mutex _camera_attitude_euler_angle_mutex{}; Telemetry::EulerAngle _camera_attitude_euler_angle{NAN, NAN, NAN}; + mutable std::mutex _attitude_angular_speed_mutex{}; + Telemetry::AngularSpeed _attitude_angular_speed{NAN, NAN, NAN}; + mutable std::mutex _ground_speed_ned_mutex{}; Telemetry::GroundSpeedNED _ground_speed_ned{NAN, NAN, NAN}; @@ -205,6 +225,12 @@ class TelemetryImpl : public PluginImplBase { mutable std::mutex _unix_epoch_time_mutex{}; uint64_t _unix_epoch_time_us{}; + mutable std::mutex _actuator_control_target_mutex{}; + Telemetry::ActuatorControlTarget _actuator_control_target{0, {0.0f}}; + + mutable std::mutex _actuator_output_status_mutex{}; + Telemetry::ActuatorOutputStatus _actuator_output_status{0, {0.0f}}; + std::atomic _hitl_enabled{false}; Telemetry::position_velocity_ned_callback_t _position_velocity_ned_subscription{nullptr}; @@ -214,6 +240,7 @@ class TelemetryImpl : public PluginImplBase { Telemetry::status_text_callback_t _status_text_subscription{nullptr}; Telemetry::armed_callback_t _armed_subscription{nullptr}; Telemetry::attitude_quaternion_callback_t _attitude_quaternion_subscription{nullptr}; + Telemetry::attitude_angular_speed_callback_t _attitude_angular_speed_subscription{nullptr}; Telemetry::attitude_euler_angle_callback_t _attitude_euler_angle_subscription{nullptr}; Telemetry::attitude_quaternion_callback_t _camera_attitude_quaternion_subscription{nullptr}; Telemetry::attitude_euler_angle_callback_t _camera_attitude_euler_angle_subscription{nullptr}; @@ -226,6 +253,8 @@ class TelemetryImpl : public PluginImplBase { Telemetry::health_all_ok_callback_t _health_all_ok_subscription{nullptr}; Telemetry::rc_status_callback_t _rc_status_subscription{nullptr}; Telemetry::unix_epoch_time_callback_t _unix_epoch_time_subscription{nullptr}; + Telemetry::actuator_control_target_callback_t _actuator_control_target_subscription{nullptr}; + Telemetry::actuator_output_status_callback_t _actuator_output_status_subscription{nullptr}; // The ground speed and position are coupled to the same message, therefore, we just use // the faster between the two. From 26b81fefdeffc70361b0cfd09024d4a655a0097e Mon Sep 17 00:00:00 2001 From: Ildar Sadykov Date: Fri, 9 Aug 2019 14:39:36 +0300 Subject: [PATCH 2/5] Arrays to vectors in tests --- .../test/telemetry_service_impl_test.cpp | 37 ++++++++++--------- 1 file changed, 20 insertions(+), 17 deletions(-) diff --git a/src/backend/test/telemetry_service_impl_test.cpp b/src/backend/test/telemetry_service_impl_test.cpp index 82632ffa5e..882fa5e659 100644 --- a/src/backend/test/telemetry_service_impl_test.cpp +++ b/src/backend/test/telemetry_service_impl_test.cpp @@ -140,14 +140,13 @@ class TelemetryServiceImplTest : public ::testing::Test { void checkSendsActuatorControlTargetEvents( const std::vector& actuator_control_target_events) const; ActuatorControlTarget - createActuatorControlTarget(const uint8_t group, const float* controls) const; + createActuatorControlTarget(const uint8_t group, const std::vector& controls) const; std::future subscribeActuatorControlTargetAsync( std::vector& actuator_control_target_events) const; void checkSendsActuatorOutputStatusEvents( const std::vector& actuator_output_status_events) const; - ActuatorOutputStatus - createActuatorOutputStatus(const uint8_t group, const float* controls) const; + ActuatorOutputStatus createActuatorOutputStatus(const std::vector& actuators) const; std::future subscribeActuatorOutputStatusAsync( std::vector& actuator_output_status_events) const; @@ -1712,23 +1711,24 @@ TEST_F(TelemetryServiceImplTest, sendsMultipleRcStatusEvents) } ActuatorControlTarget TelemetryServiceImplTest::createActuatorControlTarget( - const uint8_t group, const float* controls) const + const uint8_t group, const std::vector& controls) const { - ActuatorControlTarget actuator_control_target; + ActuatorControlTarget actuator_control_target{}; actuator_control_target.group = group; - std::copy(controls, controls + 8, actuator_control_target.controls); + int controls_len = std::min(8, controls.size()); + std::copy_n(controls.begin(), controls_len, actuator_control_target.controls); return actuator_control_target; } -ActuatorOutputStatus TelemetryServiceImplTest::createActuatorOutputStatus( - const uint8_t active, const float* actuators) const +ActuatorOutputStatus +TelemetryServiceImplTest::createActuatorOutputStatus(const std::vector& actuators) const { ActuatorOutputStatus actuator_output_status; - actuator_output_status.active = active; - std::copy(actuators, actuators + active, actuator_output_status.actuator); + actuator_output_status.active = std::min(32, actuators.size()); + std::copy_n(actuators.begin(), actuator_output_status.active, actuator_output_status.actuator); return actuator_output_status; } @@ -1789,7 +1789,7 @@ void TelemetryServiceImplTest::checkSendsActuatorOutputStatusEvents( TEST_F(TelemetryServiceImplTest, sendsMultipleActuatorControlTargetEvents) { std::vector actuator_control_target_events; - const float controls[8] = {0.0f, 0.1, 0.2f, 0.3f, 0.4f, 0.5f, 0.6f, 0.7f}; + std::vector controls{0.0f, 0.1, 0.2f, 0.3f, 0.4f, 0.5f, 0.6f, 0.7f}; actuator_control_target_events.push_back(createActuatorControlTarget(0, controls)); actuator_control_target_events.push_back(createActuatorControlTarget(1, controls)); actuator_control_target_events.push_back(createActuatorControlTarget(2, controls)); @@ -1802,15 +1802,18 @@ TEST_F(TelemetryServiceImplTest, sendsMultipleActuatorOutputStatusEvents) { std::vector actuator_output_status_events; - float actuators[32]{}; + std::vector actuators; for (int i = 0; i < 32; i++) { - actuators[i] = i * 2; + actuators.push_back(i * 2); }; - actuator_output_status_events.push_back(createActuatorOutputStatus(8, actuators)); - actuator_output_status_events.push_back(createActuatorOutputStatus(10, actuators)); - actuator_output_status_events.push_back(createActuatorOutputStatus(17, actuators)); - actuator_output_status_events.push_back(createActuatorOutputStatus(32, actuators)); + actuator_output_status_events.push_back(createActuatorOutputStatus(actuators)); + actuators.resize(27); + actuator_output_status_events.push_back(createActuatorOutputStatus(actuators)); + actuators.resize(16); + actuator_output_status_events.push_back(createActuatorOutputStatus(actuators)); + actuators.resize(5); + actuator_output_status_events.push_back(createActuatorOutputStatus(actuators)); checkSendsActuatorOutputStatusEvents(actuator_output_status_events); } From 6351b11b4e2ef0cccdaeceaf4a0dce99138533f0 Mon Sep 17 00:00:00 2001 From: Ildar Sadykov Date: Mon, 12 Aug 2019 16:52:25 +0300 Subject: [PATCH 3/5] AngularSpeed -> AngularVelocityBody --- .../telemetry/telemetry_service_impl.h | 39 +++--- .../test/telemetry_service_impl_test.cpp | 121 +++++++++--------- src/integration_tests/telemetry_async.cpp | 17 +-- src/integration_tests/telemetry_sync.cpp | 8 +- .../include/plugins/telemetry/telemetry.h | 35 ++--- src/plugins/telemetry/mocks/telemetry_mock.h | 3 +- src/plugins/telemetry/telemetry.cpp | 25 ++-- src/plugins/telemetry/telemetry_impl.cpp | 31 ++--- src/plugins/telemetry/telemetry_impl.h | 14 +- 9 files changed, 157 insertions(+), 136 deletions(-) diff --git a/src/backend/src/plugins/telemetry/telemetry_service_impl.h b/src/backend/src/plugins/telemetry/telemetry_service_impl.h index a388f3f4de..7afa27a869 100644 --- a/src/backend/src/plugins/telemetry/telemetry_service_impl.h +++ b/src/backend/src/plugins/telemetry/telemetry_service_impl.h @@ -314,26 +314,29 @@ class TelemetryServiceImpl final : public mavsdk::rpc::telemetry::TelemetryServi return grpc::Status::OK; } - grpc::Status SubscribeAttitudeAngularSpeed( + grpc::Status SubscribeAttitudeAngularVelocityBody( grpc::ServerContext* /* context */, - const mavsdk::rpc::telemetry::SubscribeAttitudeAngularSpeedRequest* /* request */, - grpc::ServerWriter* writer) override + const mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* /* request */, + grpc::ServerWriter* writer) override { - std::mutex attitude_angular_speed_mutex{}; - - _telemetry.attitude_angular_speed_async([&writer, &attitude_angular_speed_mutex]( - mavsdk::Telemetry::AngularSpeed angular_speed) { - auto rpc_angular_speed = new mavsdk::rpc::telemetry::AngularSpeed(); - rpc_angular_speed->set_rollspeed(angular_speed.rollspeed); - rpc_angular_speed->set_pitchspeed(angular_speed.pitchspeed); - rpc_angular_speed->set_yawspeed(angular_speed.yawspeed); - - mavsdk::rpc::telemetry::AttitudeAngularSpeedResponse rpc_angular_speed_response; - rpc_angular_speed_response.set_allocated_attitude_angular_speed(rpc_angular_speed); - - std::lock_guard lock(attitude_angular_speed_mutex); - writer->Write(rpc_angular_speed_response); - }); + std::mutex attitude_angular_velocity_body_mutex{}; + + _telemetry.attitude_angular_velocity_body_async( + [&writer, &attitude_angular_velocity_body_mutex]( + mavsdk::Telemetry::AngularVelocityBody angular_velocity_body) { + auto rpc_angular_velocity_body = new mavsdk::rpc::telemetry::AngularVelocityBody(); + rpc_angular_velocity_body->set_roll_rad_s(angular_velocity_body.roll_rad_s); + rpc_angular_velocity_body->set_pitch_rad_s(angular_velocity_body.pitch_rad_s); + rpc_angular_velocity_body->set_yaw_rad_s(angular_velocity_body.yaw_rad_s); + + mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse + rpc_angular_velocity_body_response; + rpc_angular_velocity_body_response.set_allocated_attitude_angular_velocity_body( + rpc_angular_velocity_body); + + std::lock_guard lock(attitude_angular_velocity_body_mutex); + writer->Write(rpc_angular_velocity_body_response); + }); _stop_future.wait(); return grpc::Status::OK; diff --git a/src/backend/test/telemetry_service_impl_test.cpp b/src/backend/test/telemetry_service_impl_test.cpp index 882fa5e659..1bf553277a 100644 --- a/src/backend/test/telemetry_service_impl_test.cpp +++ b/src/backend/test/telemetry_service_impl_test.cpp @@ -37,7 +37,7 @@ using Quaternion = mavsdk::Telemetry::Quaternion; using EulerAngle = mavsdk::Telemetry::EulerAngle; -using AngularSpeed = mavsdk::Telemetry::AngularSpeed; +using AngularVelocityBody = mavsdk::Telemetry::AngularVelocityBody; using GroundSpeedNed = mavsdk::Telemetry::GroundSpeedNED; @@ -105,11 +105,12 @@ class TelemetryServiceImplTest : public ::testing::Test { Quaternion createQuaternion(const float w, const float x, const float y, const float z) const; std::future subscribeAttitudeQuaternionAsync(std::vector& quaternions) const; - void checkSendsAttitudeAngularSpeeds(const std::vector& angular_speeds) const; - AngularSpeed - createAngularSpeed(const float rollspeed, const float pitchspeed, const float yawspeed) const; - std::future - subscribeAttitudeAngularSpeedAsync(std::vector& angular_speeds) const; + void checkSendsAttitudeAngularVelocitiesBody( + const std::vector& angular_velocities_body) const; + AngularVelocityBody createAngularVelocityBody( + const float roll_rad_s, const float pitch_rad_s, const float yaw_rad_s) const; + std::future subscribeAttitudeAngularVelocityBodyAsync( + std::vector& angular_velocities_body) const; void checkSendsAttitudeEulerAngles(const std::vector& euler_angles) const; EulerAngle @@ -989,15 +990,16 @@ TEST_F(TelemetryServiceImplTest, registersToTelemetryAttitudeQuaternionAsync) quaternion_stream_future.wait(); } -TEST_F(TelemetryServiceImplTest, registersToTelemetryAttitudeAngularSpeedAsync) +TEST_F(TelemetryServiceImplTest, registersToTelemetryAttitudeAngularVelocityBodyAsync) { - EXPECT_CALL(*_telemetry, attitude_angular_speed_async(_)).Times(1); + EXPECT_CALL(*_telemetry, attitude_angular_velocity_body_async(_)).Times(1); - std::vector angular_speeds; - auto angular_speed_stream_future = subscribeAttitudeAngularSpeedAsync(angular_speeds); + std::vector angular_velocities_body; + auto angular_velocity_body_stream_future = + subscribeAttitudeAngularVelocityBodyAsync(angular_velocities_body); _telemetry_service->stop(); - angular_speed_stream_future.wait(); + angular_velocity_body_stream_future.wait(); } std::future TelemetryServiceImplTest::subscribeAttitudeQuaternionAsync( @@ -1036,39 +1038,40 @@ TEST_F(TelemetryServiceImplTest, doesNotSendAttitudeQuaternionIfCallbackNotCalle EXPECT_EQ(0, quaternions.size()); } -std::future TelemetryServiceImplTest::subscribeAttitudeAngularSpeedAsync( - std::vector& angular_speeds) const +std::future TelemetryServiceImplTest::subscribeAttitudeAngularVelocityBodyAsync( + std::vector& angular_velocities_body) const { return std::async(std::launch::async, [&]() { grpc::ClientContext context; - mavsdk::rpc::telemetry::SubscribeAttitudeAngularSpeedRequest request; - auto response_reader = _stub->SubscribeAttitudeAngularSpeed(&context, request); + mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest request; + auto response_reader = _stub->SubscribeAttitudeAngularVelocityBody(&context, request); - mavsdk::rpc::telemetry::AttitudeAngularSpeedResponse response; + mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse response; while (response_reader->Read(&response)) { - auto angular_speed_rpc = response.attitude_angular_speed(); + auto angular_velocity_body_rpc = response.attitude_angular_velocity_body(); - AngularSpeed angular_speed; - angular_speed.rollspeed = angular_speed_rpc.rollspeed(); - angular_speed.pitchspeed = angular_speed_rpc.pitchspeed(); - angular_speed.yawspeed = angular_speed_rpc.yawspeed(); + AngularVelocityBody angular_velocity_body; + angular_velocity_body.roll_rad_s = angular_velocity_body_rpc.roll_rad_s(); + angular_velocity_body.pitch_rad_s = angular_velocity_body_rpc.pitch_rad_s(); + angular_velocity_body.yaw_rad_s = angular_velocity_body_rpc.yaw_rad_s(); - angular_speeds.push_back(angular_speed); + angular_velocities_body.push_back(angular_velocity_body); } response_reader->Finish(); }); } -TEST_F(TelemetryServiceImplTest, doesNotSendAttitudeAngularSpeedIfCallbackNotCalled) +TEST_F(TelemetryServiceImplTest, doesNotSendAttitudeAngularVelocityBodyIfCallbackNotCalled) { - std::vector angular_speeds; - auto angular_speed_stream_future = subscribeAttitudeAngularSpeedAsync(angular_speeds); + std::vector angular_velocities_body; + auto angular_velocity_body_stream_future = + subscribeAttitudeAngularVelocityBodyAsync(angular_velocities_body); _telemetry_service->stop(); - angular_speed_stream_future.wait(); + angular_velocity_body_stream_future.wait(); - EXPECT_EQ(0, angular_speeds.size()); + EXPECT_EQ(0, angular_velocities_body.size()); } TEST_F(TelemetryServiceImplTest, sendsOneAttitudeQuaternion) @@ -1079,12 +1082,12 @@ TEST_F(TelemetryServiceImplTest, sendsOneAttitudeQuaternion) checkSendsAttitudeQuaternions(quaternions); } -TEST_F(TelemetryServiceImplTest, sendsOneAttitudeAngularSpeed) +TEST_F(TelemetryServiceImplTest, sendsOneAttitudeAngularVelocityBody) { - std::vector angular_speed; - angular_speed.push_back(createAngularSpeed(0.1f, 0.2f, 0.3f)); + std::vector angular_velocity_body; + angular_velocity_body.push_back(createAngularVelocityBody(0.1f, 0.2f, 0.3f)); - checkSendsAttitudeAngularSpeeds(angular_speed); + checkSendsAttitudeAngularVelocitiesBody(angular_velocity_body); } Quaternion TelemetryServiceImplTest::createQuaternion( @@ -1100,16 +1103,16 @@ Quaternion TelemetryServiceImplTest::createQuaternion( return quaternion; } -AngularSpeed TelemetryServiceImplTest::createAngularSpeed( - const float rollspeed, const float pitchspeed, const float yawspeed) const +AngularVelocityBody TelemetryServiceImplTest::createAngularVelocityBody( + const float roll_rad_s, const float pitch_rad_s, const float yaw_rad_s) const { - mavsdk::Telemetry::AngularSpeed angular_speed; + mavsdk::Telemetry::AngularVelocityBody angular_velocity_body; - angular_speed.rollspeed = rollspeed; - angular_speed.pitchspeed = pitchspeed; - angular_speed.yawspeed = yawspeed; + angular_velocity_body.roll_rad_s = roll_rad_s; + angular_velocity_body.pitch_rad_s = pitch_rad_s; + angular_velocity_body.yaw_rad_s = yaw_rad_s; - return angular_speed; + return angular_velocity_body; } void TelemetryServiceImplTest::checkSendsAttitudeQuaternions( @@ -1136,27 +1139,29 @@ void TelemetryServiceImplTest::checkSendsAttitudeQuaternions( } } -void TelemetryServiceImplTest::checkSendsAttitudeAngularSpeeds( - const std::vector& angular_speeds) const +void TelemetryServiceImplTest::checkSendsAttitudeAngularVelocitiesBody( + const std::vector& angular_velocities_body) const { std::promise subscription_promise; auto subscription_future = subscription_promise.get_future(); - mavsdk::Telemetry::attitude_angular_speed_callback_t attitude_angular_speed_callback; - EXPECT_CALL(*_telemetry, attitude_angular_speed_async(_)) - .WillOnce(SaveCallback(&attitude_angular_speed_callback, &subscription_promise)); - - std::vector received_angular_speeds; - auto angular_speed_stream_future = subscribeAttitudeAngularSpeedAsync(received_angular_speeds); + mavsdk::Telemetry::attitude_angular_velocity_body_callback_t + attitude_angular_velocity_body_callback; + EXPECT_CALL(*_telemetry, attitude_angular_velocity_body_async(_)) + .WillOnce(SaveCallback(&attitude_angular_velocity_body_callback, &subscription_promise)); + + std::vector received_angular_velocities_body; + auto angular_velocity_body_stream_future = + subscribeAttitudeAngularVelocityBodyAsync(received_angular_velocities_body); subscription_future.wait(); - for (const auto angular_speed : angular_speeds) { - attitude_angular_speed_callback(angular_speed); + for (const auto angular_velocity_body : angular_velocities_body) { + attitude_angular_velocity_body_callback(angular_velocity_body); } _telemetry_service->stop(); - angular_speed_stream_future.wait(); + angular_velocity_body_stream_future.wait(); - ASSERT_EQ(angular_speeds.size(), received_angular_speeds.size()); - for (size_t i = 0; i < angular_speeds.size(); i++) { - EXPECT_EQ(angular_speeds.at(i), received_angular_speeds.at(i)); + ASSERT_EQ(angular_velocities_body.size(), received_angular_velocities_body.size()); + for (size_t i = 0; i < angular_velocities_body.size(); i++) { + EXPECT_EQ(angular_velocities_body.at(i), received_angular_velocities_body.at(i)); } } @@ -1170,14 +1175,14 @@ TEST_F(TelemetryServiceImplTest, sendsMultipleAttitudeQuaternions) checkSendsAttitudeQuaternions(quaternions); } -TEST_F(TelemetryServiceImplTest, sendsMultipleAttitudeAngularSpeeds) +TEST_F(TelemetryServiceImplTest, sendsMultipleAttitudeAngularVelocityBodys) { - std::vector angular_speed; - angular_speed.push_back(createAngularSpeed(0.1f, 0.2f, 0.3f)); - angular_speed.push_back(createAngularSpeed(2.1f, 0.4f, -2.2f)); - angular_speed.push_back(createAngularSpeed(5.2f, 5.9f, 1.1f)); + std::vector angular_velocities_body; + angular_velocities_body.push_back(createAngularVelocityBody(0.1f, 0.2f, 0.3f)); + angular_velocities_body.push_back(createAngularVelocityBody(2.1f, 0.4f, -2.2f)); + angular_velocities_body.push_back(createAngularVelocityBody(5.2f, 5.9f, 1.1f)); - checkSendsAttitudeAngularSpeeds(angular_speed); + checkSendsAttitudeAngularVelocitiesBody(angular_velocities_body); } TEST_F(TelemetryServiceImplTest, registersToTelemetryAttitudeEulerAsync) diff --git a/src/integration_tests/telemetry_async.cpp b/src/integration_tests/telemetry_async.cpp index 41d2d805cb..86854581bc 100644 --- a/src/integration_tests/telemetry_async.cpp +++ b/src/integration_tests/telemetry_async.cpp @@ -17,7 +17,7 @@ static void print_in_air(bool in_air); static void print_armed(bool armed); static void print_quaternion(Telemetry::Quaternion quaternion); static void print_euler_angle(Telemetry::EulerAngle euler_angle); -static void print_angular_speed(Telemetry::AngularSpeed angular_speed); +static void print_angular_velocity_body(Telemetry::AngularVelocityBody angular_velocity_body); #if CAMERA_AVAILABLE == 1 static void print_camera_quaternion(Telemetry::Quaternion quaternion); static void print_camera_euler_angle(Telemetry::EulerAngle euler_angle); @@ -39,7 +39,7 @@ static bool _received_in_air = false; static bool _received_armed = false; static bool _received_quaternion = false; static bool _received_euler_angle = false; -static bool _received_angular_speed = false; +static bool _received_angular_velocity_body = false; #if CAMERA_AVAILABLE == 1 static bool _received_camera_quaternion = false; static bool _received_camera_euler_angle = false; @@ -116,7 +116,7 @@ TEST_F(SitlTest, TelemetryAsync) telemetry->attitude_euler_angle_async(std::bind(&print_euler_angle, _1)); - telemetry->attitude_angular_speed_async(std::bind(&print_angular_speed, _1)); + telemetry->attitude_angular_velocity_body_async(std::bind(&print_angular_velocity_body, _1)); #if CAMERA_AVAILABLE == 1 telemetry->camera_attitude_quaternion_async(std::bind(&print_camera_quaternion, _1)); @@ -150,7 +150,7 @@ TEST_F(SitlTest, TelemetryAsync) EXPECT_TRUE(_received_in_air); EXPECT_TRUE(_received_armed); EXPECT_TRUE(_received_quaternion); - EXPECT_TRUE(_received_angular_speed); + EXPECT_TRUE(_received_angular_velocity_body); EXPECT_TRUE(_received_euler_angle); #if CAMERA_AVAILABLE == 1 EXPECT_TRUE(_received_camera_quaternion); @@ -219,12 +219,13 @@ void print_euler_angle(Telemetry::EulerAngle euler_angle) _received_euler_angle = true; } -void print_angular_speed(Telemetry::AngularSpeed angular_speed) +void print_angular_velocity_body(Telemetry::AngularVelocityBody angular_velocity_body) { - std::cout << "Angular speed: [ " << angular_speed.rollspeed << ", " << angular_speed.pitchspeed - << ", " << angular_speed.yawspeed << " ] rad/s" << std::endl; + std::cout << "Angular velocity: [ " << angular_velocity_body.roll_rad_s << ", " + << angular_velocity_body.pitch_rad_s << ", " << angular_velocity_body.yaw_rad_s + << " ] rad/s" << std::endl; - _received_angular_speed = true; + _received_angular_velocity_body = true; } #if CAMERA_AVAILABLE == 1 diff --git a/src/integration_tests/telemetry_sync.cpp b/src/integration_tests/telemetry_sync.cpp index abba753803..ba74bd209b 100644 --- a/src/integration_tests/telemetry_sync.cpp +++ b/src/integration_tests/telemetry_sync.cpp @@ -65,9 +65,11 @@ TEST_F(SitlTest, TelemetrySync) std::cout << "Euler: (" << euler_angle.roll_deg << " deg, " << euler_angle.pitch_deg << " deg," << euler_angle.yaw_deg << " deg)" << std::endl; - const Telemetry::AngularSpeed& angular_speed = telemetry->attitude_angular_speed(); - std::cout << "Angular speed: (" << angular_speed.rollspeed << ", " - << angular_speed.pitchspeed << "," << angular_speed.yawspeed << ")" << std::endl; + const Telemetry::AngularVelocityBody& angular_velocity_body = + telemetry->attitude_angular_velocity_body(); + std::cout << "Angular velocity: (" << angular_velocity_body.roll_rad_s << ", " + << angular_velocity_body.pitch_rad_s << "," << angular_velocity_body.yaw_rad_s + << ")" << std::endl; const Telemetry::GroundSpeedNED& ground_speed_ned = telemetry->ground_speed_ned(); std::cout << "Speed: (" << ground_speed_ned.velocity_north_m_s << " m/s, " diff --git a/src/plugins/telemetry/include/plugins/telemetry/telemetry.h b/src/plugins/telemetry/include/plugins/telemetry/telemetry.h index 44a36165e7..42cdf5b750 100644 --- a/src/plugins/telemetry/include/plugins/telemetry/telemetry.h +++ b/src/plugins/telemetry/include/plugins/telemetry/telemetry.h @@ -110,14 +110,14 @@ class Telemetry : public PluginBase { }; /** - * @brief Angular speed type. + * @brief Angular velocity type. * - * The angular speed of vehicle body in radians/second. + * The angular velocity of vehicle body in radians/second. */ - struct AngularSpeed { - float rollspeed; /**< @brief Roll angular speed */ - float pitchspeed; /**< @brief Pitch angular speed */ - float yawspeed; /**< @brief Yaw angular speed */ + struct AngularVelocityBody { + float roll_rad_s; /**< @brief Roll angular velocity */ + float pitch_rad_s; /**< @brief Pitch angular velocity */ + float yaw_rad_s; /**< @brief Yaw angular velocity */ }; /** @@ -646,7 +646,7 @@ class Telemetry : public PluginBase { * * @return Angular speed. */ - AngularSpeed attitude_angular_speed() const; + AngularVelocityBody attitude_angular_velocity_body() const; /** * @brief Get the camera's attitude in quaternions (synchronous). @@ -838,18 +838,19 @@ class Telemetry : public PluginBase { void attitude_euler_angle_async(attitude_euler_angle_callback_t callback); /** - * @brief Callback type for angular speed updates in quaternion. + * @brief Callback type for angular velocity updates in quaternion. * - * @param angular_speed Angular speed. + * @param angular_velocity_body Angular velocity. */ - typedef std::function attitude_angular_speed_callback_t; + typedef std::function + attitude_angular_velocity_body_callback_t; /** - * @brief Subscribe to attitude updates in angular speed (asynchronous). + * @brief Subscribe to attitude updates in angular velocity (asynchronous). * * @param callback Function to call with updates. */ - void attitude_angular_speed_async(attitude_angular_speed_callback_t callback); + void attitude_angular_velocity_body_async(attitude_angular_velocity_body_callback_t callback); /** * @brief Subscribe to camera attitude updates in quaternion (asynchronous). @@ -1193,18 +1194,20 @@ bool operator==(const Telemetry::EulerAngle& lhs, const Telemetry::EulerAngle& r std::ostream& operator<<(std::ostream& str, Telemetry::EulerAngle const& euler_angle); /** - * @brief Equal operator to compare two `Telemetry::AngularSpeed` objects. + * @brief Equal operator to compare two `Telemetry::AngularVelocityBody` objects. * * @return `true` if items are equal. */ -bool operator==(const Telemetry::AngularSpeed& lhs, const Telemetry::AngularSpeed& rhs); +bool operator==( + const Telemetry::AngularVelocityBody& lhs, const Telemetry::AngularVelocityBody& rhs); /** - * @brief Stream operator to print information about a `Telemetry::AngularSpeed`. + * @brief Stream operator to print information about a `Telemetry::AngularVelocityBody`. * * @return A reference to the stream. */ -std::ostream& operator<<(std::ostream& str, Telemetry::AngularSpeed const& angular_speed); +std::ostream& +operator<<(std::ostream& str, Telemetry::AngularVelocityBody const& angular_velocity_body); /** * @brief Equal operator to compare two `Telemetry::GroundSpeedNED` objects. diff --git a/src/plugins/telemetry/mocks/telemetry_mock.h b/src/plugins/telemetry/mocks/telemetry_mock.h index db9f96920b..4ef5b23f26 100644 --- a/src/plugins/telemetry/mocks/telemetry_mock.h +++ b/src/plugins/telemetry/mocks/telemetry_mock.h @@ -19,7 +19,8 @@ class MockTelemetry { MOCK_CONST_METHOD1( attitude_quaternion_async, void(Telemetry::attitude_quaternion_callback_t)){}; MOCK_CONST_METHOD1( - attitude_angular_speed_async, void(Telemetry::attitude_angular_speed_callback_t)){}; + attitude_angular_velocity_body_async, + void(Telemetry::attitude_angular_velocity_body_callback_t)){}; MOCK_CONST_METHOD1( attitude_euler_angle_async, void(Telemetry::attitude_euler_angle_callback_t)){}; MOCK_CONST_METHOD1( diff --git a/src/plugins/telemetry/telemetry.cpp b/src/plugins/telemetry/telemetry.cpp index f89caf8b6b..45657df11a 100644 --- a/src/plugins/telemetry/telemetry.cpp +++ b/src/plugins/telemetry/telemetry.cpp @@ -185,9 +185,9 @@ Telemetry::EulerAngle Telemetry::attitude_euler_angle() const return _impl->get_attitude_euler_angle(); } -Telemetry::AngularSpeed Telemetry::attitude_angular_speed() const +Telemetry::AngularVelocityBody Telemetry::attitude_angular_velocity_body() const { - return _impl->get_attitude_angular_speed(); + return _impl->get_attitude_angular_velocity_body(); } Telemetry::Quaternion Telemetry::camera_attitude_quaternion() const @@ -290,9 +290,10 @@ void Telemetry::attitude_euler_angle_async(attitude_euler_angle_callback_t callb return _impl->attitude_euler_angle_async(callback); } -void Telemetry::attitude_angular_speed_async(attitude_angular_speed_callback_t callback) +void Telemetry::attitude_angular_velocity_body_async( + attitude_angular_velocity_body_callback_t callback) { - return _impl->attitude_angular_speed_async(callback); + return _impl->attitude_angular_velocity_body_async(callback); } void Telemetry::camera_attitude_quaternion_async(attitude_quaternion_callback_t callback) @@ -596,17 +597,19 @@ std::ostream& operator<<(std::ostream& str, Telemetry::EulerAngle const& euler_a << ", yaw_deg: " << euler_angle.yaw_deg << "]"; } -bool operator==(const Telemetry::AngularSpeed& lhs, const Telemetry::AngularSpeed& rhs) +bool operator==( + const Telemetry::AngularVelocityBody& lhs, const Telemetry::AngularVelocityBody& rhs) { - return lhs.rollspeed == rhs.rollspeed && lhs.pitchspeed == rhs.pitchspeed && - lhs.yawspeed == rhs.yawspeed; + return lhs.roll_rad_s == rhs.roll_rad_s && lhs.pitch_rad_s == rhs.pitch_rad_s && + lhs.yaw_rad_s == rhs.yaw_rad_s; } -std::ostream& operator<<(std::ostream& str, Telemetry::AngularSpeed const& angular_speed) +std::ostream& +operator<<(std::ostream& str, Telemetry::AngularVelocityBody const& angular_velocity_body) { - return str << "[rollspeed: " << angular_speed.rollspeed - << ", pitchspeed: " << angular_speed.pitchspeed - << ", yawspeed: " << angular_speed.yawspeed << "]"; + return str << "[angular_velocity_body_roll_rad_s: " << angular_velocity_body.roll_rad_s + << ", angular_velocity_body_pitch_rad_s: " << angular_velocity_body.pitch_rad_s + << ", angular_velocity_body_yaw_rad_s: " << angular_velocity_body.yaw_rad_s << "]"; } bool operator==(const Telemetry::GroundSpeedNED& lhs, const Telemetry::GroundSpeedNED& rhs) diff --git a/src/plugins/telemetry/telemetry_impl.cpp b/src/plugins/telemetry/telemetry_impl.cpp index a256f526d3..575bbce172 100644 --- a/src/plugins/telemetry/telemetry_impl.cpp +++ b/src/plugins/telemetry/telemetry_impl.cpp @@ -480,13 +480,13 @@ void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message attitude_quaternion.q3, attitude_quaternion.q4}; - Telemetry::AngularSpeed angular_speed{attitude_quaternion.rollspeed, - attitude_quaternion.pitchspeed, - attitude_quaternion.yawspeed}; + Telemetry::AngularVelocityBody angular_velocity_body{attitude_quaternion.rollspeed, + attitude_quaternion.pitchspeed, + attitude_quaternion.yawspeed}; set_attitude_quaternion(quaternion); - set_attitude_angular_speed(angular_speed); + set_attitude_angular_velocity_body(angular_velocity_body); if (_attitude_quaternion_subscription) { auto callback = _attitude_quaternion_subscription; @@ -500,9 +500,9 @@ void TelemetryImpl::process_attitude_quaternion(const mavlink_message_t& message _parent->call_user_callback([callback, arg]() { callback(arg); }); } - if (_attitude_angular_speed_subscription) { - auto callback = _attitude_angular_speed_subscription; - auto arg = get_attitude_angular_speed(); + if (_attitude_angular_velocity_body_subscription) { + auto callback = _attitude_angular_velocity_body_subscription; + auto arg = get_attitude_angular_velocity_body(); _parent->call_user_callback([callback, arg]() { callback(arg); }); } } @@ -943,10 +943,10 @@ Telemetry::Quaternion TelemetryImpl::get_attitude_quaternion() const return _attitude_quaternion; } -Telemetry::AngularSpeed TelemetryImpl::get_attitude_angular_speed() const +Telemetry::AngularVelocityBody TelemetryImpl::get_attitude_angular_velocity_body() const { - std::lock_guard lock(_attitude_angular_speed_mutex); - return _attitude_angular_speed; + std::lock_guard lock(_attitude_angular_velocity_body_mutex); + return _attitude_angular_velocity_body; } Telemetry::EulerAngle TelemetryImpl::get_attitude_euler_angle() const @@ -963,10 +963,11 @@ void TelemetryImpl::set_attitude_quaternion(Telemetry::Quaternion quaternion) _attitude_quaternion = quaternion; } -void TelemetryImpl::set_attitude_angular_speed(Telemetry::AngularSpeed angular_speed) +void TelemetryImpl::set_attitude_angular_velocity_body( + Telemetry::AngularVelocityBody angular_velocity_body) { std::lock_guard lock(_attitude_quaternion_mutex); - _attitude_angular_speed = angular_speed; + _attitude_angular_velocity_body = angular_velocity_body; } Telemetry::Quaternion TelemetryImpl::get_camera_attitude_quaternion() const @@ -1209,10 +1210,10 @@ void TelemetryImpl::attitude_euler_angle_async(Telemetry::attitude_euler_angle_c _attitude_euler_angle_subscription = callback; } -void TelemetryImpl::attitude_angular_speed_async( - Telemetry::attitude_angular_speed_callback_t& callback) +void TelemetryImpl::attitude_angular_velocity_body_async( + Telemetry::attitude_angular_velocity_body_callback_t& callback) { - _attitude_angular_speed_subscription = callback; + _attitude_angular_velocity_body_subscription = callback; } void TelemetryImpl::camera_attitude_quaternion_async( diff --git a/src/plugins/telemetry/telemetry_impl.h b/src/plugins/telemetry/telemetry_impl.h index fc8e2df145..1140b23882 100644 --- a/src/plugins/telemetry/telemetry_impl.h +++ b/src/plugins/telemetry/telemetry_impl.h @@ -67,7 +67,7 @@ class TelemetryImpl : public PluginImplBase { Telemetry::StatusText get_status_text() const; Telemetry::EulerAngle get_attitude_euler_angle() const; Telemetry::Quaternion get_attitude_quaternion() const; - Telemetry::AngularSpeed get_attitude_angular_speed() const; + Telemetry::AngularVelocityBody get_attitude_angular_velocity_body() const; Telemetry::EulerAngle get_camera_attitude_euler_angle() const; Telemetry::Quaternion get_camera_attitude_quaternion() const; Telemetry::GroundSpeedNED get_ground_speed_ned() const; @@ -90,7 +90,8 @@ class TelemetryImpl : public PluginImplBase { void armed_async(Telemetry::armed_callback_t& callback); void attitude_quaternion_async(Telemetry::attitude_quaternion_callback_t& callback); void attitude_euler_angle_async(Telemetry::attitude_euler_angle_callback_t& callback); - void attitude_angular_speed_async(Telemetry::attitude_angular_speed_callback_t& callback); + void attitude_angular_velocity_body_async( + Telemetry::attitude_angular_velocity_body_callback_t& callback); void camera_attitude_quaternion_async(Telemetry::attitude_quaternion_callback_t& callback); void camera_attitude_euler_angle_async(Telemetry::attitude_euler_angle_callback_t& callback); void ground_speed_ned_async(Telemetry::ground_speed_ned_callback_t& callback); @@ -116,7 +117,7 @@ class TelemetryImpl : public PluginImplBase { void set_status_text(Telemetry::StatusText status_text); void set_armed(bool armed); void set_attitude_quaternion(Telemetry::Quaternion quaternion); - void set_attitude_angular_speed(Telemetry::AngularSpeed angular_speed); + void set_attitude_angular_velocity_body(Telemetry::AngularVelocityBody angular_velocity_body); void set_camera_attitude_euler_angle(Telemetry::EulerAngle euler_angle); void set_ground_speed_ned(Telemetry::GroundSpeedNED ground_speed_ned); void set_imu_reading_ned(Telemetry::IMUReadingNED imu_reading_ned); @@ -197,8 +198,8 @@ class TelemetryImpl : public PluginImplBase { mutable std::mutex _camera_attitude_euler_angle_mutex{}; Telemetry::EulerAngle _camera_attitude_euler_angle{NAN, NAN, NAN}; - mutable std::mutex _attitude_angular_speed_mutex{}; - Telemetry::AngularSpeed _attitude_angular_speed{NAN, NAN, NAN}; + mutable std::mutex _attitude_angular_velocity_body_mutex{}; + Telemetry::AngularVelocityBody _attitude_angular_velocity_body{NAN, NAN, NAN}; mutable std::mutex _ground_speed_ned_mutex{}; Telemetry::GroundSpeedNED _ground_speed_ned{NAN, NAN, NAN}; @@ -240,7 +241,8 @@ class TelemetryImpl : public PluginImplBase { Telemetry::status_text_callback_t _status_text_subscription{nullptr}; Telemetry::armed_callback_t _armed_subscription{nullptr}; Telemetry::attitude_quaternion_callback_t _attitude_quaternion_subscription{nullptr}; - Telemetry::attitude_angular_speed_callback_t _attitude_angular_speed_subscription{nullptr}; + Telemetry::attitude_angular_velocity_body_callback_t + _attitude_angular_velocity_body_subscription{nullptr}; Telemetry::attitude_euler_angle_callback_t _attitude_euler_angle_subscription{nullptr}; Telemetry::attitude_quaternion_callback_t _camera_attitude_quaternion_subscription{nullptr}; Telemetry::attitude_euler_angle_callback_t _camera_attitude_euler_angle_subscription{nullptr}; From ce857a16499c32f949461cac3a9cdd85a401f384 Mon Sep 17 00:00:00 2001 From: Ildar Sadykov Date: Wed, 14 Aug 2019 14:16:04 +0300 Subject: [PATCH 4/5] Proto submodule updated to support new subscriptions 1. Updated proto submodule rev, 2. Updated generated grpc modules, 3. Fixed 'proto_dir' in 'generate_from_protos.sh' tool. --- proto | 2 +- .../generated/telemetry/telemetry.grpc.pb.cc | 124 +- .../generated/telemetry/telemetry.grpc.pb.h | 599 +- .../src/generated/telemetry/telemetry.pb.cc | 8484 +++++++++++------ .../src/generated/telemetry/telemetry.pb.h | 2355 ++++- tools/generate_from_protos.sh | 2 +- 6 files changed, 8167 insertions(+), 3399 deletions(-) diff --git a/proto b/proto index 766f93e7f7..0eb3e19987 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 766f93e7f7508c924632181faf5fbe5a6a57d14b +Subproject commit 0eb3e1998772507baddd5738577c70ac9717c27f diff --git a/src/backend/src/generated/telemetry/telemetry.grpc.pb.cc b/src/backend/src/generated/telemetry/telemetry.grpc.pb.cc index 6c13e030de..ba448ac36f 100644 --- a/src/backend/src/generated/telemetry/telemetry.grpc.pb.cc +++ b/src/backend/src/generated/telemetry/telemetry.grpc.pb.cc @@ -27,6 +27,7 @@ static const char* TelemetryService_method_names[] = { "/mavsdk.rpc.telemetry.TelemetryService/SubscribeArmed", "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeQuaternion", "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeEuler", + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeAttitudeAngularVelocityBody", "/mavsdk.rpc.telemetry.TelemetryService/SubscribeCameraAttitudeQuaternion", "/mavsdk.rpc.telemetry.TelemetryService/SubscribeCameraAttitudeEuler", "/mavsdk.rpc.telemetry.TelemetryService/SubscribeGroundSpeedNed", @@ -36,6 +37,8 @@ static const char* TelemetryService_method_names[] = { "/mavsdk.rpc.telemetry.TelemetryService/SubscribeHealth", "/mavsdk.rpc.telemetry.TelemetryService/SubscribeRcStatus", "/mavsdk.rpc.telemetry.TelemetryService/SubscribeStatusText", + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorControlTarget", + "/mavsdk.rpc.telemetry.TelemetryService/SubscribeActuatorOutputStatus", }; std::unique_ptr< TelemetryService::Stub> TelemetryService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -51,15 +54,18 @@ TelemetryService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& c , rpcmethod_SubscribeArmed_(TelemetryService_method_names[3], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_SubscribeAttitudeQuaternion_(TelemetryService_method_names[4], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) , rpcmethod_SubscribeAttitudeEuler_(TelemetryService_method_names[5], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeCameraAttitudeQuaternion_(TelemetryService_method_names[6], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeCameraAttitudeEuler_(TelemetryService_method_names[7], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeGroundSpeedNed_(TelemetryService_method_names[8], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeGpsInfo_(TelemetryService_method_names[9], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeBattery_(TelemetryService_method_names[10], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeFlightMode_(TelemetryService_method_names[11], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeHealth_(TelemetryService_method_names[12], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeRcStatus_(TelemetryService_method_names[13], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeStatusText_(TelemetryService_method_names[14], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeAttitudeAngularVelocityBody_(TelemetryService_method_names[6], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeCameraAttitudeQuaternion_(TelemetryService_method_names[7], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeCameraAttitudeEuler_(TelemetryService_method_names[8], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeGroundSpeedNed_(TelemetryService_method_names[9], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeGpsInfo_(TelemetryService_method_names[10], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeBattery_(TelemetryService_method_names[11], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeFlightMode_(TelemetryService_method_names[12], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeHealth_(TelemetryService_method_names[13], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeRcStatus_(TelemetryService_method_names[14], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeStatusText_(TelemetryService_method_names[15], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeActuatorControlTarget_(TelemetryService_method_names[16], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeActuatorOutputStatus_(TelemetryService_method_names[17], ::grpc::internal::RpcMethod::SERVER_STREAMING, channel) {} ::grpc::ClientReader< ::mavsdk::rpc::telemetry::PositionResponse>* TelemetryService::Stub::SubscribePositionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribePositionRequest& request) { @@ -158,6 +164,22 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>* Tel return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeAttitudeEuler_, context, request, false, nullptr); } +::grpc::ClientReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* TelemetryService::Stub::SubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>::Create(channel_.get(), rpcmethod_SubscribeAttitudeAngularVelocityBody_, context, request); +} + +void TelemetryService::Stub::experimental_async::SubscribeAttitudeAngularVelocityBody(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeAttitudeAngularVelocityBody_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* TelemetryService::Stub::AsyncSubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeAttitudeAngularVelocityBody_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* TelemetryService::Stub::PrepareAsyncSubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeAttitudeAngularVelocityBody_, context, request, false, nullptr); +} + ::grpc::ClientReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* TelemetryService::Stub::SubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request) { return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>::Create(channel_.get(), rpcmethod_SubscribeCameraAttitudeQuaternion_, context, request); } @@ -302,6 +324,38 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::StatusTextResponse>* Teleme return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::StatusTextResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeStatusText_, context, request, false, nullptr); } +::grpc::ClientReader< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* TelemetryService::Stub::SubscribeActuatorControlTargetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>::Create(channel_.get(), rpcmethod_SubscribeActuatorControlTarget_, context, request); +} + +void TelemetryService::Stub::experimental_async::SubscribeActuatorControlTarget(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeActuatorControlTarget_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* TelemetryService::Stub::AsyncSubscribeActuatorControlTargetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeActuatorControlTarget_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* TelemetryService::Stub::PrepareAsyncSubscribeActuatorControlTargetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeActuatorControlTarget_, context, request, false, nullptr); +} + +::grpc::ClientReader< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* TelemetryService::Stub::SubscribeActuatorOutputStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>::Create(channel_.get(), rpcmethod_SubscribeActuatorOutputStatus_, context, request); +} + +void TelemetryService::Stub::experimental_async::SubscribeActuatorOutputStatus(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeActuatorOutputStatus_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* TelemetryService::Stub::AsyncSubscribeActuatorOutputStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeActuatorOutputStatus_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* TelemetryService::Stub::PrepareAsyncSubscribeActuatorOutputStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeActuatorOutputStatus_, context, request, false, nullptr); +} + TelemetryService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( TelemetryService_method_names[0], @@ -336,48 +390,63 @@ TelemetryService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( TelemetryService_method_names[6], ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest, ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>( + std::mem_fn(&TelemetryService::Service::SubscribeAttitudeAngularVelocityBody), this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + TelemetryService_method_names[7], + ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest, ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>( std::mem_fn(&TelemetryService::Service::SubscribeCameraAttitudeQuaternion), this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[7], + TelemetryService_method_names[8], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest, ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>( std::mem_fn(&TelemetryService::Service::SubscribeCameraAttitudeEuler), this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[8], + TelemetryService_method_names[9], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeGroundSpeedNedRequest, ::mavsdk::rpc::telemetry::GroundSpeedNedResponse>( std::mem_fn(&TelemetryService::Service::SubscribeGroundSpeedNed), this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[9], + TelemetryService_method_names[10], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest, ::mavsdk::rpc::telemetry::GpsInfoResponse>( std::mem_fn(&TelemetryService::Service::SubscribeGpsInfo), this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[10], + TelemetryService_method_names[11], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeBatteryRequest, ::mavsdk::rpc::telemetry::BatteryResponse>( std::mem_fn(&TelemetryService::Service::SubscribeBattery), this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[11], + TelemetryService_method_names[12], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeFlightModeRequest, ::mavsdk::rpc::telemetry::FlightModeResponse>( std::mem_fn(&TelemetryService::Service::SubscribeFlightMode), this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[12], + TelemetryService_method_names[13], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeHealthRequest, ::mavsdk::rpc::telemetry::HealthResponse>( std::mem_fn(&TelemetryService::Service::SubscribeHealth), this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[13], + TelemetryService_method_names[14], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeRcStatusRequest, ::mavsdk::rpc::telemetry::RcStatusResponse>( std::mem_fn(&TelemetryService::Service::SubscribeRcStatus), this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - TelemetryService_method_names[14], + TelemetryService_method_names[15], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest, ::mavsdk::rpc::telemetry::StatusTextResponse>( std::mem_fn(&TelemetryService::Service::SubscribeStatusText), this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + TelemetryService_method_names[16], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>( + std::mem_fn(&TelemetryService::Service::SubscribeActuatorControlTarget), this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + TelemetryService_method_names[17], + ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< TelemetryService::Service, ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>( + std::mem_fn(&TelemetryService::Service::SubscribeActuatorOutputStatus), this))); } TelemetryService::Service::~Service() { @@ -425,6 +494,13 @@ ::grpc::Status TelemetryService::Service::SubscribeAttitudeEuler(::grpc::ServerC return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status TelemetryService::Service::SubscribeAttitudeAngularVelocityBody(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status TelemetryService::Service::SubscribeCameraAttitudeQuaternion(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* writer) { (void) context; (void) request; @@ -488,6 +564,20 @@ ::grpc::Status TelemetryService::Service::SubscribeStatusText(::grpc::ServerCont return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status TelemetryService::Service::SubscribeActuatorControlTarget(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status TelemetryService::Service::SubscribeActuatorOutputStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + } // namespace mavsdk } // namespace rpc diff --git a/src/backend/src/generated/telemetry/telemetry.grpc.pb.h b/src/backend/src/generated/telemetry/telemetry.grpc.pb.h index c6dd89532a..b67e8a2c95 100644 --- a/src/backend/src/generated/telemetry/telemetry.grpc.pb.h +++ b/src/backend/src/generated/telemetry/telemetry.grpc.pb.h @@ -99,6 +99,15 @@ class TelemetryService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>> PrepareAsyncSubscribeAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>>(PrepareAsyncSubscribeAttitudeEulerRaw(context, request, cq)); } + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>> SubscribeAttitudeAngularVelocityBody(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>>(SubscribeAttitudeAngularVelocityBodyRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>> AsyncSubscribeAttitudeAngularVelocityBody(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>>(AsyncSubscribeAttitudeAngularVelocityBodyRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>> PrepareAsyncSubscribeAttitudeAngularVelocityBody(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>>(PrepareAsyncSubscribeAttitudeAngularVelocityBodyRaw(context, request, cq)); + } std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>> SubscribeCameraAttitudeQuaternion(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request) { return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>>(SubscribeCameraAttitudeQuaternionRaw(context, request)); } @@ -180,6 +189,24 @@ class TelemetryService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::StatusTextResponse>> PrepareAsyncSubscribeStatusText(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::StatusTextResponse>>(PrepareAsyncSubscribeStatusTextRaw(context, request, cq)); } + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>> SubscribeActuatorControlTarget(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>>(SubscribeActuatorControlTargetRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>> AsyncSubscribeActuatorControlTarget(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>>(AsyncSubscribeActuatorControlTargetRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>> PrepareAsyncSubscribeActuatorControlTarget(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>>(PrepareAsyncSubscribeActuatorControlTargetRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>> SubscribeActuatorOutputStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>>(SubscribeActuatorOutputStatusRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>> AsyncSubscribeActuatorOutputStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>>(AsyncSubscribeActuatorOutputStatusRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>> PrepareAsyncSubscribeActuatorOutputStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>>(PrepareAsyncSubscribeActuatorOutputStatusRaw(context, request, cq)); + } class experimental_async_interface { public: virtual ~experimental_async_interface() {} @@ -189,6 +216,7 @@ class TelemetryService final { virtual void SubscribeArmed(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeArmedRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::ArmedResponse>* reactor) = 0; virtual void SubscribeAttitudeQuaternion(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeAttitudeQuaternionRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::AttitudeQuaternionResponse>* reactor) = 0; virtual void SubscribeAttitudeEuler(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>* reactor) = 0; + virtual void SubscribeAttitudeAngularVelocityBody(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* reactor) = 0; virtual void SubscribeCameraAttitudeQuaternion(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* reactor) = 0; virtual void SubscribeCameraAttitudeEuler(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* reactor) = 0; virtual void SubscribeGroundSpeedNed(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeGroundSpeedNedRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::GroundSpeedNedResponse>* reactor) = 0; @@ -198,6 +226,8 @@ class TelemetryService final { virtual void SubscribeHealth(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeHealthRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::HealthResponse>* reactor) = 0; virtual void SubscribeRcStatus(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeRcStatusRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::RcStatusResponse>* reactor) = 0; virtual void SubscribeStatusText(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::StatusTextResponse>* reactor) = 0; + virtual void SubscribeActuatorControlTarget(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* reactor) = 0; + virtual void SubscribeActuatorOutputStatus(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* reactor) = 0; }; virtual class experimental_async_interface* experimental_async() { return nullptr; } private: @@ -219,6 +249,9 @@ class TelemetryService final { virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>* SubscribeAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>* AsyncSubscribeAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>* PrepareAsyncSubscribeAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* SubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* AsyncSubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* PrepareAsyncSubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* SubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* AsyncSubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* PrepareAsyncSubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq) = 0; @@ -246,6 +279,12 @@ class TelemetryService final { virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::StatusTextResponse>* SubscribeStatusTextRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::StatusTextResponse>* AsyncSubscribeStatusTextRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::StatusTextResponse>* PrepareAsyncSubscribeStatusTextRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* SubscribeActuatorControlTargetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* AsyncSubscribeActuatorControlTargetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* PrepareAsyncSubscribeActuatorControlTargetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* SubscribeActuatorOutputStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* AsyncSubscribeActuatorOutputStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* PrepareAsyncSubscribeActuatorOutputStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -304,6 +343,15 @@ class TelemetryService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>> PrepareAsyncSubscribeAttitudeEuler(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>>(PrepareAsyncSubscribeAttitudeEulerRaw(context, request, cq)); } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>> SubscribeAttitudeAngularVelocityBody(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>>(SubscribeAttitudeAngularVelocityBodyRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>> AsyncSubscribeAttitudeAngularVelocityBody(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>>(AsyncSubscribeAttitudeAngularVelocityBodyRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>> PrepareAsyncSubscribeAttitudeAngularVelocityBody(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>>(PrepareAsyncSubscribeAttitudeAngularVelocityBodyRaw(context, request, cq)); + } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>> SubscribeCameraAttitudeQuaternion(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>>(SubscribeCameraAttitudeQuaternionRaw(context, request)); } @@ -385,6 +433,24 @@ class TelemetryService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::StatusTextResponse>> PrepareAsyncSubscribeStatusText(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::StatusTextResponse>>(PrepareAsyncSubscribeStatusTextRaw(context, request, cq)); } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>> SubscribeActuatorControlTarget(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>>(SubscribeActuatorControlTargetRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>> AsyncSubscribeActuatorControlTarget(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>>(AsyncSubscribeActuatorControlTargetRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>> PrepareAsyncSubscribeActuatorControlTarget(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>>(PrepareAsyncSubscribeActuatorControlTargetRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>> SubscribeActuatorOutputStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>>(SubscribeActuatorOutputStatusRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>> AsyncSubscribeActuatorOutputStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>>(AsyncSubscribeActuatorOutputStatusRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>> PrepareAsyncSubscribeActuatorOutputStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>>(PrepareAsyncSubscribeActuatorOutputStatusRaw(context, request, cq)); + } class experimental_async final : public StubInterface::experimental_async_interface { public: @@ -394,6 +460,7 @@ class TelemetryService final { void SubscribeArmed(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeArmedRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::ArmedResponse>* reactor) override; void SubscribeAttitudeQuaternion(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeAttitudeQuaternionRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::AttitudeQuaternionResponse>* reactor) override; void SubscribeAttitudeEuler(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>* reactor) override; + void SubscribeAttitudeAngularVelocityBody(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* reactor) override; void SubscribeCameraAttitudeQuaternion(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* reactor) override; void SubscribeCameraAttitudeEuler(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* reactor) override; void SubscribeGroundSpeedNed(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeGroundSpeedNedRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::GroundSpeedNedResponse>* reactor) override; @@ -403,6 +470,8 @@ class TelemetryService final { void SubscribeHealth(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeHealthRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::HealthResponse>* reactor) override; void SubscribeRcStatus(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeRcStatusRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::RcStatusResponse>* reactor) override; void SubscribeStatusText(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::StatusTextResponse>* reactor) override; + void SubscribeActuatorControlTarget(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* reactor) override; + void SubscribeActuatorOutputStatus(::grpc::ClientContext* context, ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* request, ::grpc::experimental::ClientReadReactor< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* reactor) override; private: friend class Stub; explicit experimental_async(Stub* stub): stub_(stub) { } @@ -432,6 +501,9 @@ class TelemetryService final { ::grpc::ClientReader< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>* SubscribeAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>* AsyncSubscribeAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>* PrepareAsyncSubscribeAttitudeEulerRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* SubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* AsyncSubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* PrepareAsyncSubscribeAttitudeAngularVelocityBodyRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* SubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* AsyncSubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* PrepareAsyncSubscribeCameraAttitudeQuaternionRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest& request, ::grpc::CompletionQueue* cq) override; @@ -459,12 +531,19 @@ class TelemetryService final { ::grpc::ClientReader< ::mavsdk::rpc::telemetry::StatusTextResponse>* SubscribeStatusTextRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::StatusTextResponse>* AsyncSubscribeStatusTextRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::StatusTextResponse>* PrepareAsyncSubscribeStatusTextRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* SubscribeActuatorControlTargetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* AsyncSubscribeActuatorControlTargetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* PrepareAsyncSubscribeActuatorControlTargetRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* SubscribeActuatorOutputStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* AsyncSubscribeActuatorOutputStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* PrepareAsyncSubscribeActuatorOutputStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SubscribePosition_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeHome_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeInAir_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeArmed_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeAttitudeQuaternion_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeAttitudeEuler_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeAttitudeAngularVelocityBody_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeCameraAttitudeQuaternion_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeCameraAttitudeEuler_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeGroundSpeedNed_; @@ -474,6 +553,8 @@ class TelemetryService final { const ::grpc::internal::RpcMethod rpcmethod_SubscribeHealth_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeRcStatus_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeStatusText_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeActuatorControlTarget_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeActuatorOutputStatus_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -487,6 +568,7 @@ class TelemetryService final { virtual ::grpc::Status SubscribeArmed(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeArmedRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ArmedResponse>* writer); virtual ::grpc::Status SubscribeAttitudeQuaternion(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeQuaternionRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AttitudeQuaternionResponse>* writer); virtual ::grpc::Status SubscribeAttitudeEuler(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AttitudeEulerResponse>* writer); + virtual ::grpc::Status SubscribeAttitudeAngularVelocityBody(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* writer); virtual ::grpc::Status SubscribeCameraAttitudeQuaternion(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* writer); virtual ::grpc::Status SubscribeCameraAttitudeEuler(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* writer); virtual ::grpc::Status SubscribeGroundSpeedNed(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeGroundSpeedNedRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::GroundSpeedNedResponse>* writer); @@ -496,6 +578,8 @@ class TelemetryService final { virtual ::grpc::Status SubscribeHealth(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeHealthRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::HealthResponse>* writer); virtual ::grpc::Status SubscribeRcStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeRcStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::RcStatusResponse>* writer); virtual ::grpc::Status SubscribeStatusText(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::StatusTextResponse>* writer); + virtual ::grpc::Status SubscribeActuatorControlTarget(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* writer); + virtual ::grpc::Status SubscribeActuatorOutputStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* writer); }; template class WithAsyncMethod_SubscribePosition : public BaseClass { @@ -618,12 +702,32 @@ class TelemetryService final { } }; template + class WithAsyncMethod_SubscribeAttitudeAngularVelocityBody : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + WithAsyncMethod_SubscribeAttitudeAngularVelocityBody() { + ::grpc::Service::MarkMethodAsync(6); + } + ~WithAsyncMethod_SubscribeAttitudeAngularVelocityBody() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeAttitudeAngularVelocityBody(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeAttitudeAngularVelocityBody(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(6, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template class WithAsyncMethod_SubscribeCameraAttitudeQuaternion : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithAsyncMethod_SubscribeCameraAttitudeQuaternion() { - ::grpc::Service::MarkMethodAsync(6); + ::grpc::Service::MarkMethodAsync(7); } ~WithAsyncMethod_SubscribeCameraAttitudeQuaternion() override { BaseClassMustBeDerivedFromService(this); @@ -634,7 +738,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeCameraAttitudeQuaternion(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(6, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -643,7 +747,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithAsyncMethod_SubscribeCameraAttitudeEuler() { - ::grpc::Service::MarkMethodAsync(7); + ::grpc::Service::MarkMethodAsync(8); } ~WithAsyncMethod_SubscribeCameraAttitudeEuler() override { BaseClassMustBeDerivedFromService(this); @@ -654,7 +758,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeCameraAttitudeEuler(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -663,7 +767,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithAsyncMethod_SubscribeGroundSpeedNed() { - ::grpc::Service::MarkMethodAsync(8); + ::grpc::Service::MarkMethodAsync(9); } ~WithAsyncMethod_SubscribeGroundSpeedNed() override { BaseClassMustBeDerivedFromService(this); @@ -674,7 +778,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeGroundSpeedNed(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeGroundSpeedNedRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::GroundSpeedNedResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -683,7 +787,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithAsyncMethod_SubscribeGpsInfo() { - ::grpc::Service::MarkMethodAsync(9); + ::grpc::Service::MarkMethodAsync(10); } ~WithAsyncMethod_SubscribeGpsInfo() override { BaseClassMustBeDerivedFromService(this); @@ -694,7 +798,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeGpsInfo(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::GpsInfoResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(10, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -703,7 +807,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithAsyncMethod_SubscribeBattery() { - ::grpc::Service::MarkMethodAsync(10); + ::grpc::Service::MarkMethodAsync(11); } ~WithAsyncMethod_SubscribeBattery() override { BaseClassMustBeDerivedFromService(this); @@ -714,7 +818,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeBattery(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeBatteryRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::BatteryResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(10, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -723,7 +827,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithAsyncMethod_SubscribeFlightMode() { - ::grpc::Service::MarkMethodAsync(11); + ::grpc::Service::MarkMethodAsync(12); } ~WithAsyncMethod_SubscribeFlightMode() override { BaseClassMustBeDerivedFromService(this); @@ -734,7 +838,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeFlightMode(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeFlightModeRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::FlightModeResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(12, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -743,7 +847,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithAsyncMethod_SubscribeHealth() { - ::grpc::Service::MarkMethodAsync(12); + ::grpc::Service::MarkMethodAsync(13); } ~WithAsyncMethod_SubscribeHealth() override { BaseClassMustBeDerivedFromService(this); @@ -754,7 +858,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeHealth(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeHealthRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::HealthResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(12, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -763,7 +867,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithAsyncMethod_SubscribeRcStatus() { - ::grpc::Service::MarkMethodAsync(13); + ::grpc::Service::MarkMethodAsync(14); } ~WithAsyncMethod_SubscribeRcStatus() override { BaseClassMustBeDerivedFromService(this); @@ -774,7 +878,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeRcStatus(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeRcStatusRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::RcStatusResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -783,7 +887,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithAsyncMethod_SubscribeStatusText() { - ::grpc::Service::MarkMethodAsync(14); + ::grpc::Service::MarkMethodAsync(15); } ~WithAsyncMethod_SubscribeStatusText() override { BaseClassMustBeDerivedFromService(this); @@ -794,10 +898,50 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStatusText(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::StatusTextResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(15, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithAsyncMethod_SubscribeActuatorControlTarget : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + WithAsyncMethod_SubscribeActuatorControlTarget() { + ::grpc::Service::MarkMethodAsync(16); + } + ~WithAsyncMethod_SubscribeActuatorControlTarget() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeActuatorControlTarget(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeActuatorControlTarget(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(16, context, request, writer, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SubscribePosition > > > > > > > > > > > > > > AsyncService; + template + class WithAsyncMethod_SubscribeActuatorOutputStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + WithAsyncMethod_SubscribeActuatorOutputStatus() { + ::grpc::Service::MarkMethodAsync(17); + } + ~WithAsyncMethod_SubscribeActuatorOutputStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeActuatorOutputStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeActuatorOutputStatus(::grpc::ServerContext* context, ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(17, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_SubscribePosition > > > > > > > > > > > > > > > > > AsyncService; template class ExperimentalWithCallbackMethod_SubscribePosition : public BaseClass { private: @@ -931,12 +1075,34 @@ class TelemetryService final { ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest, ::mavsdk::rpc::telemetry::AttitudeEulerResponse>;} }; template + class ExperimentalWithCallbackMethod_SubscribeAttitudeAngularVelocityBody : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + ExperimentalWithCallbackMethod_SubscribeAttitudeAngularVelocityBody() { + ::grpc::Service::experimental().MarkMethodCallback(6, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest, ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>( + [this] { return this->SubscribeAttitudeAngularVelocityBody(); })); + } + ~ExperimentalWithCallbackMethod_SubscribeAttitudeAngularVelocityBody() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeAttitudeAngularVelocityBody(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::experimental::ServerWriteReactor< ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest, ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* SubscribeAttitudeAngularVelocityBody() { + return new ::grpc::internal::UnimplementedWriteReactor< + ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest, ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>;} + }; + template class ExperimentalWithCallbackMethod_SubscribeCameraAttitudeQuaternion : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithCallbackMethod_SubscribeCameraAttitudeQuaternion() { - ::grpc::Service::experimental().MarkMethodCallback(6, + ::grpc::Service::experimental().MarkMethodCallback(7, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest, ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>( [this] { return this->SubscribeCameraAttitudeQuaternion(); })); } @@ -958,7 +1124,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithCallbackMethod_SubscribeCameraAttitudeEuler() { - ::grpc::Service::experimental().MarkMethodCallback(7, + ::grpc::Service::experimental().MarkMethodCallback(8, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest, ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>( [this] { return this->SubscribeCameraAttitudeEuler(); })); } @@ -980,7 +1146,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithCallbackMethod_SubscribeGroundSpeedNed() { - ::grpc::Service::experimental().MarkMethodCallback(8, + ::grpc::Service::experimental().MarkMethodCallback(9, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeGroundSpeedNedRequest, ::mavsdk::rpc::telemetry::GroundSpeedNedResponse>( [this] { return this->SubscribeGroundSpeedNed(); })); } @@ -1002,7 +1168,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithCallbackMethod_SubscribeGpsInfo() { - ::grpc::Service::experimental().MarkMethodCallback(9, + ::grpc::Service::experimental().MarkMethodCallback(10, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest, ::mavsdk::rpc::telemetry::GpsInfoResponse>( [this] { return this->SubscribeGpsInfo(); })); } @@ -1024,7 +1190,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithCallbackMethod_SubscribeBattery() { - ::grpc::Service::experimental().MarkMethodCallback(10, + ::grpc::Service::experimental().MarkMethodCallback(11, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeBatteryRequest, ::mavsdk::rpc::telemetry::BatteryResponse>( [this] { return this->SubscribeBattery(); })); } @@ -1046,7 +1212,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithCallbackMethod_SubscribeFlightMode() { - ::grpc::Service::experimental().MarkMethodCallback(11, + ::grpc::Service::experimental().MarkMethodCallback(12, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeFlightModeRequest, ::mavsdk::rpc::telemetry::FlightModeResponse>( [this] { return this->SubscribeFlightMode(); })); } @@ -1068,7 +1234,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithCallbackMethod_SubscribeHealth() { - ::grpc::Service::experimental().MarkMethodCallback(12, + ::grpc::Service::experimental().MarkMethodCallback(13, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeHealthRequest, ::mavsdk::rpc::telemetry::HealthResponse>( [this] { return this->SubscribeHealth(); })); } @@ -1090,7 +1256,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithCallbackMethod_SubscribeRcStatus() { - ::grpc::Service::experimental().MarkMethodCallback(13, + ::grpc::Service::experimental().MarkMethodCallback(14, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeRcStatusRequest, ::mavsdk::rpc::telemetry::RcStatusResponse>( [this] { return this->SubscribeRcStatus(); })); } @@ -1112,7 +1278,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithCallbackMethod_SubscribeStatusText() { - ::grpc::Service::experimental().MarkMethodCallback(14, + ::grpc::Service::experimental().MarkMethodCallback(15, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest, ::mavsdk::rpc::telemetry::StatusTextResponse>( [this] { return this->SubscribeStatusText(); })); } @@ -1128,7 +1294,51 @@ class TelemetryService final { return new ::grpc::internal::UnimplementedWriteReactor< ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest, ::mavsdk::rpc::telemetry::StatusTextResponse>;} }; - typedef ExperimentalWithCallbackMethod_SubscribePosition > > > > > > > > > > > > > > ExperimentalCallbackService; + template + class ExperimentalWithCallbackMethod_SubscribeActuatorControlTarget : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + ExperimentalWithCallbackMethod_SubscribeActuatorControlTarget() { + ::grpc::Service::experimental().MarkMethodCallback(16, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>( + [this] { return this->SubscribeActuatorControlTarget(); })); + } + ~ExperimentalWithCallbackMethod_SubscribeActuatorControlTarget() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeActuatorControlTarget(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::experimental::ServerWriteReactor< ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* SubscribeActuatorControlTarget() { + return new ::grpc::internal::UnimplementedWriteReactor< + ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>;} + }; + template + class ExperimentalWithCallbackMethod_SubscribeActuatorOutputStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + ExperimentalWithCallbackMethod_SubscribeActuatorOutputStatus() { + ::grpc::Service::experimental().MarkMethodCallback(17, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>( + [this] { return this->SubscribeActuatorOutputStatus(); })); + } + ~ExperimentalWithCallbackMethod_SubscribeActuatorOutputStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeActuatorOutputStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::experimental::ServerWriteReactor< ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* SubscribeActuatorOutputStatus() { + return new ::grpc::internal::UnimplementedWriteReactor< + ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>;} + }; + typedef ExperimentalWithCallbackMethod_SubscribePosition > > > > > > > > > > > > > > > > > ExperimentalCallbackService; template class WithGenericMethod_SubscribePosition : public BaseClass { private: @@ -1232,12 +1442,29 @@ class TelemetryService final { } }; template + class WithGenericMethod_SubscribeAttitudeAngularVelocityBody : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + WithGenericMethod_SubscribeAttitudeAngularVelocityBody() { + ::grpc::Service::MarkMethodGeneric(6); + } + ~WithGenericMethod_SubscribeAttitudeAngularVelocityBody() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeAttitudeAngularVelocityBody(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithGenericMethod_SubscribeCameraAttitudeQuaternion : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithGenericMethod_SubscribeCameraAttitudeQuaternion() { - ::grpc::Service::MarkMethodGeneric(6); + ::grpc::Service::MarkMethodGeneric(7); } ~WithGenericMethod_SubscribeCameraAttitudeQuaternion() override { BaseClassMustBeDerivedFromService(this); @@ -1254,7 +1481,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithGenericMethod_SubscribeCameraAttitudeEuler() { - ::grpc::Service::MarkMethodGeneric(7); + ::grpc::Service::MarkMethodGeneric(8); } ~WithGenericMethod_SubscribeCameraAttitudeEuler() override { BaseClassMustBeDerivedFromService(this); @@ -1271,7 +1498,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithGenericMethod_SubscribeGroundSpeedNed() { - ::grpc::Service::MarkMethodGeneric(8); + ::grpc::Service::MarkMethodGeneric(9); } ~WithGenericMethod_SubscribeGroundSpeedNed() override { BaseClassMustBeDerivedFromService(this); @@ -1288,7 +1515,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithGenericMethod_SubscribeGpsInfo() { - ::grpc::Service::MarkMethodGeneric(9); + ::grpc::Service::MarkMethodGeneric(10); } ~WithGenericMethod_SubscribeGpsInfo() override { BaseClassMustBeDerivedFromService(this); @@ -1305,7 +1532,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithGenericMethod_SubscribeBattery() { - ::grpc::Service::MarkMethodGeneric(10); + ::grpc::Service::MarkMethodGeneric(11); } ~WithGenericMethod_SubscribeBattery() override { BaseClassMustBeDerivedFromService(this); @@ -1322,7 +1549,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithGenericMethod_SubscribeFlightMode() { - ::grpc::Service::MarkMethodGeneric(11); + ::grpc::Service::MarkMethodGeneric(12); } ~WithGenericMethod_SubscribeFlightMode() override { BaseClassMustBeDerivedFromService(this); @@ -1339,7 +1566,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithGenericMethod_SubscribeHealth() { - ::grpc::Service::MarkMethodGeneric(12); + ::grpc::Service::MarkMethodGeneric(13); } ~WithGenericMethod_SubscribeHealth() override { BaseClassMustBeDerivedFromService(this); @@ -1356,7 +1583,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithGenericMethod_SubscribeRcStatus() { - ::grpc::Service::MarkMethodGeneric(13); + ::grpc::Service::MarkMethodGeneric(14); } ~WithGenericMethod_SubscribeRcStatus() override { BaseClassMustBeDerivedFromService(this); @@ -1373,7 +1600,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithGenericMethod_SubscribeStatusText() { - ::grpc::Service::MarkMethodGeneric(14); + ::grpc::Service::MarkMethodGeneric(15); } ~WithGenericMethod_SubscribeStatusText() override { BaseClassMustBeDerivedFromService(this); @@ -1385,6 +1612,40 @@ class TelemetryService final { } }; template + class WithGenericMethod_SubscribeActuatorControlTarget : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + WithGenericMethod_SubscribeActuatorControlTarget() { + ::grpc::Service::MarkMethodGeneric(16); + } + ~WithGenericMethod_SubscribeActuatorControlTarget() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeActuatorControlTarget(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeActuatorOutputStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + WithGenericMethod_SubscribeActuatorOutputStatus() { + ::grpc::Service::MarkMethodGeneric(17); + } + ~WithGenericMethod_SubscribeActuatorOutputStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeActuatorOutputStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithRawMethod_SubscribePosition : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service *service) {} @@ -1505,12 +1766,32 @@ class TelemetryService final { } }; template + class WithRawMethod_SubscribeAttitudeAngularVelocityBody : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + WithRawMethod_SubscribeAttitudeAngularVelocityBody() { + ::grpc::Service::MarkMethodRaw(6); + } + ~WithRawMethod_SubscribeAttitudeAngularVelocityBody() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeAttitudeAngularVelocityBody(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeAttitudeAngularVelocityBody(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(6, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template class WithRawMethod_SubscribeCameraAttitudeQuaternion : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithRawMethod_SubscribeCameraAttitudeQuaternion() { - ::grpc::Service::MarkMethodRaw(6); + ::grpc::Service::MarkMethodRaw(7); } ~WithRawMethod_SubscribeCameraAttitudeQuaternion() override { BaseClassMustBeDerivedFromService(this); @@ -1521,7 +1802,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeCameraAttitudeQuaternion(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(6, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1530,7 +1811,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithRawMethod_SubscribeCameraAttitudeEuler() { - ::grpc::Service::MarkMethodRaw(7); + ::grpc::Service::MarkMethodRaw(8); } ~WithRawMethod_SubscribeCameraAttitudeEuler() override { BaseClassMustBeDerivedFromService(this); @@ -1541,7 +1822,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeCameraAttitudeEuler(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1550,7 +1831,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithRawMethod_SubscribeGroundSpeedNed() { - ::grpc::Service::MarkMethodRaw(8); + ::grpc::Service::MarkMethodRaw(9); } ~WithRawMethod_SubscribeGroundSpeedNed() override { BaseClassMustBeDerivedFromService(this); @@ -1561,7 +1842,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeGroundSpeedNed(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1570,7 +1851,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithRawMethod_SubscribeGpsInfo() { - ::grpc::Service::MarkMethodRaw(9); + ::grpc::Service::MarkMethodRaw(10); } ~WithRawMethod_SubscribeGpsInfo() override { BaseClassMustBeDerivedFromService(this); @@ -1581,7 +1862,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeGpsInfo(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(10, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1590,7 +1871,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithRawMethod_SubscribeBattery() { - ::grpc::Service::MarkMethodRaw(10); + ::grpc::Service::MarkMethodRaw(11); } ~WithRawMethod_SubscribeBattery() override { BaseClassMustBeDerivedFromService(this); @@ -1601,7 +1882,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeBattery(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(10, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1610,7 +1891,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithRawMethod_SubscribeFlightMode() { - ::grpc::Service::MarkMethodRaw(11); + ::grpc::Service::MarkMethodRaw(12); } ~WithRawMethod_SubscribeFlightMode() override { BaseClassMustBeDerivedFromService(this); @@ -1621,7 +1902,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeFlightMode(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(11, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(12, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1630,7 +1911,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithRawMethod_SubscribeHealth() { - ::grpc::Service::MarkMethodRaw(12); + ::grpc::Service::MarkMethodRaw(13); } ~WithRawMethod_SubscribeHealth() override { BaseClassMustBeDerivedFromService(this); @@ -1641,7 +1922,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeHealth(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(12, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1650,7 +1931,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithRawMethod_SubscribeRcStatus() { - ::grpc::Service::MarkMethodRaw(13); + ::grpc::Service::MarkMethodRaw(14); } ~WithRawMethod_SubscribeRcStatus() override { BaseClassMustBeDerivedFromService(this); @@ -1661,7 +1942,7 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeRcStatus(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(13, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1670,7 +1951,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithRawMethod_SubscribeStatusText() { - ::grpc::Service::MarkMethodRaw(14); + ::grpc::Service::MarkMethodRaw(15); } ~WithRawMethod_SubscribeStatusText() override { BaseClassMustBeDerivedFromService(this); @@ -1681,7 +1962,47 @@ class TelemetryService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeStatusText(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(14, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(15, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeActuatorControlTarget : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + WithRawMethod_SubscribeActuatorControlTarget() { + ::grpc::Service::MarkMethodRaw(16); + } + ~WithRawMethod_SubscribeActuatorControlTarget() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeActuatorControlTarget(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeActuatorControlTarget(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(16, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_SubscribeActuatorOutputStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + WithRawMethod_SubscribeActuatorOutputStatus() { + ::grpc::Service::MarkMethodRaw(17); + } + ~WithRawMethod_SubscribeActuatorOutputStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeActuatorOutputStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeActuatorOutputStatus(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncServerStreaming(17, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1817,12 +2138,34 @@ class TelemetryService final { ::grpc::ByteBuffer, ::grpc::ByteBuffer>;} }; template + class ExperimentalWithRawCallbackMethod_SubscribeAttitudeAngularVelocityBody : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + ExperimentalWithRawCallbackMethod_SubscribeAttitudeAngularVelocityBody() { + ::grpc::Service::experimental().MarkMethodRawCallback(6, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this] { return this->SubscribeAttitudeAngularVelocityBody(); })); + } + ~ExperimentalWithRawCallbackMethod_SubscribeAttitudeAngularVelocityBody() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeAttitudeAngularVelocityBody(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::experimental::ServerWriteReactor< ::grpc::ByteBuffer, ::grpc::ByteBuffer>* SubscribeAttitudeAngularVelocityBody() { + return new ::grpc::internal::UnimplementedWriteReactor< + ::grpc::ByteBuffer, ::grpc::ByteBuffer>;} + }; + template class ExperimentalWithRawCallbackMethod_SubscribeCameraAttitudeQuaternion : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithRawCallbackMethod_SubscribeCameraAttitudeQuaternion() { - ::grpc::Service::experimental().MarkMethodRawCallback(6, + ::grpc::Service::experimental().MarkMethodRawCallback(7, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this] { return this->SubscribeCameraAttitudeQuaternion(); })); } @@ -1844,7 +2187,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithRawCallbackMethod_SubscribeCameraAttitudeEuler() { - ::grpc::Service::experimental().MarkMethodRawCallback(7, + ::grpc::Service::experimental().MarkMethodRawCallback(8, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this] { return this->SubscribeCameraAttitudeEuler(); })); } @@ -1866,7 +2209,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithRawCallbackMethod_SubscribeGroundSpeedNed() { - ::grpc::Service::experimental().MarkMethodRawCallback(8, + ::grpc::Service::experimental().MarkMethodRawCallback(9, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this] { return this->SubscribeGroundSpeedNed(); })); } @@ -1888,7 +2231,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithRawCallbackMethod_SubscribeGpsInfo() { - ::grpc::Service::experimental().MarkMethodRawCallback(9, + ::grpc::Service::experimental().MarkMethodRawCallback(10, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this] { return this->SubscribeGpsInfo(); })); } @@ -1910,7 +2253,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithRawCallbackMethod_SubscribeBattery() { - ::grpc::Service::experimental().MarkMethodRawCallback(10, + ::grpc::Service::experimental().MarkMethodRawCallback(11, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this] { return this->SubscribeBattery(); })); } @@ -1932,7 +2275,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithRawCallbackMethod_SubscribeFlightMode() { - ::grpc::Service::experimental().MarkMethodRawCallback(11, + ::grpc::Service::experimental().MarkMethodRawCallback(12, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this] { return this->SubscribeFlightMode(); })); } @@ -1954,7 +2297,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithRawCallbackMethod_SubscribeHealth() { - ::grpc::Service::experimental().MarkMethodRawCallback(12, + ::grpc::Service::experimental().MarkMethodRawCallback(13, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this] { return this->SubscribeHealth(); })); } @@ -1976,7 +2319,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithRawCallbackMethod_SubscribeRcStatus() { - ::grpc::Service::experimental().MarkMethodRawCallback(13, + ::grpc::Service::experimental().MarkMethodRawCallback(14, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this] { return this->SubscribeRcStatus(); })); } @@ -1998,7 +2341,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: ExperimentalWithRawCallbackMethod_SubscribeStatusText() { - ::grpc::Service::experimental().MarkMethodRawCallback(14, + ::grpc::Service::experimental().MarkMethodRawCallback(15, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this] { return this->SubscribeStatusText(); })); } @@ -2014,6 +2357,50 @@ class TelemetryService final { return new ::grpc::internal::UnimplementedWriteReactor< ::grpc::ByteBuffer, ::grpc::ByteBuffer>;} }; + template + class ExperimentalWithRawCallbackMethod_SubscribeActuatorControlTarget : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + ExperimentalWithRawCallbackMethod_SubscribeActuatorControlTarget() { + ::grpc::Service::experimental().MarkMethodRawCallback(16, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this] { return this->SubscribeActuatorControlTarget(); })); + } + ~ExperimentalWithRawCallbackMethod_SubscribeActuatorControlTarget() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeActuatorControlTarget(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::experimental::ServerWriteReactor< ::grpc::ByteBuffer, ::grpc::ByteBuffer>* SubscribeActuatorControlTarget() { + return new ::grpc::internal::UnimplementedWriteReactor< + ::grpc::ByteBuffer, ::grpc::ByteBuffer>;} + }; + template + class ExperimentalWithRawCallbackMethod_SubscribeActuatorOutputStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + ExperimentalWithRawCallbackMethod_SubscribeActuatorOutputStatus() { + ::grpc::Service::experimental().MarkMethodRawCallback(17, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this] { return this->SubscribeActuatorOutputStatus(); })); + } + ~ExperimentalWithRawCallbackMethod_SubscribeActuatorOutputStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeActuatorOutputStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::experimental::ServerWriteReactor< ::grpc::ByteBuffer, ::grpc::ByteBuffer>* SubscribeActuatorOutputStatus() { + return new ::grpc::internal::UnimplementedWriteReactor< + ::grpc::ByteBuffer, ::grpc::ByteBuffer>;} + }; typedef Service StreamedUnaryService; template class WithSplitStreamingMethod_SubscribePosition : public BaseClass { @@ -2136,12 +2523,32 @@ class TelemetryService final { virtual ::grpc::Status StreamedSubscribeAttitudeEuler(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest,::mavsdk::rpc::telemetry::AttitudeEulerResponse>* server_split_streamer) = 0; }; template + class WithSplitStreamingMethod_SubscribeAttitudeAngularVelocityBody : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + WithSplitStreamingMethod_SubscribeAttitudeAngularVelocityBody() { + ::grpc::Service::MarkMethodStreamed(6, + new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest, ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>(std::bind(&WithSplitStreamingMethod_SubscribeAttitudeAngularVelocityBody::StreamedSubscribeAttitudeAngularVelocityBody, this, std::placeholders::_1, std::placeholders::_2))); + } + ~WithSplitStreamingMethod_SubscribeAttitudeAngularVelocityBody() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeAttitudeAngularVelocityBody(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeAttitudeAngularVelocityBody(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest,::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>* server_split_streamer) = 0; + }; + template class WithSplitStreamingMethod_SubscribeCameraAttitudeQuaternion : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithSplitStreamingMethod_SubscribeCameraAttitudeQuaternion() { - ::grpc::Service::MarkMethodStreamed(6, + ::grpc::Service::MarkMethodStreamed(7, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest, ::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse>(std::bind(&WithSplitStreamingMethod_SubscribeCameraAttitudeQuaternion::StreamedSubscribeCameraAttitudeQuaternion, this, std::placeholders::_1, std::placeholders::_2))); } ~WithSplitStreamingMethod_SubscribeCameraAttitudeQuaternion() override { @@ -2161,7 +2568,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithSplitStreamingMethod_SubscribeCameraAttitudeEuler() { - ::grpc::Service::MarkMethodStreamed(7, + ::grpc::Service::MarkMethodStreamed(8, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest, ::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse>(std::bind(&WithSplitStreamingMethod_SubscribeCameraAttitudeEuler::StreamedSubscribeCameraAttitudeEuler, this, std::placeholders::_1, std::placeholders::_2))); } ~WithSplitStreamingMethod_SubscribeCameraAttitudeEuler() override { @@ -2181,7 +2588,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithSplitStreamingMethod_SubscribeGroundSpeedNed() { - ::grpc::Service::MarkMethodStreamed(8, + ::grpc::Service::MarkMethodStreamed(9, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeGroundSpeedNedRequest, ::mavsdk::rpc::telemetry::GroundSpeedNedResponse>(std::bind(&WithSplitStreamingMethod_SubscribeGroundSpeedNed::StreamedSubscribeGroundSpeedNed, this, std::placeholders::_1, std::placeholders::_2))); } ~WithSplitStreamingMethod_SubscribeGroundSpeedNed() override { @@ -2201,7 +2608,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithSplitStreamingMethod_SubscribeGpsInfo() { - ::grpc::Service::MarkMethodStreamed(9, + ::grpc::Service::MarkMethodStreamed(10, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest, ::mavsdk::rpc::telemetry::GpsInfoResponse>(std::bind(&WithSplitStreamingMethod_SubscribeGpsInfo::StreamedSubscribeGpsInfo, this, std::placeholders::_1, std::placeholders::_2))); } ~WithSplitStreamingMethod_SubscribeGpsInfo() override { @@ -2221,7 +2628,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithSplitStreamingMethod_SubscribeBattery() { - ::grpc::Service::MarkMethodStreamed(10, + ::grpc::Service::MarkMethodStreamed(11, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeBatteryRequest, ::mavsdk::rpc::telemetry::BatteryResponse>(std::bind(&WithSplitStreamingMethod_SubscribeBattery::StreamedSubscribeBattery, this, std::placeholders::_1, std::placeholders::_2))); } ~WithSplitStreamingMethod_SubscribeBattery() override { @@ -2241,7 +2648,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithSplitStreamingMethod_SubscribeFlightMode() { - ::grpc::Service::MarkMethodStreamed(11, + ::grpc::Service::MarkMethodStreamed(12, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeFlightModeRequest, ::mavsdk::rpc::telemetry::FlightModeResponse>(std::bind(&WithSplitStreamingMethod_SubscribeFlightMode::StreamedSubscribeFlightMode, this, std::placeholders::_1, std::placeholders::_2))); } ~WithSplitStreamingMethod_SubscribeFlightMode() override { @@ -2261,7 +2668,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithSplitStreamingMethod_SubscribeHealth() { - ::grpc::Service::MarkMethodStreamed(12, + ::grpc::Service::MarkMethodStreamed(13, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeHealthRequest, ::mavsdk::rpc::telemetry::HealthResponse>(std::bind(&WithSplitStreamingMethod_SubscribeHealth::StreamedSubscribeHealth, this, std::placeholders::_1, std::placeholders::_2))); } ~WithSplitStreamingMethod_SubscribeHealth() override { @@ -2281,7 +2688,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithSplitStreamingMethod_SubscribeRcStatus() { - ::grpc::Service::MarkMethodStreamed(13, + ::grpc::Service::MarkMethodStreamed(14, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeRcStatusRequest, ::mavsdk::rpc::telemetry::RcStatusResponse>(std::bind(&WithSplitStreamingMethod_SubscribeRcStatus::StreamedSubscribeRcStatus, this, std::placeholders::_1, std::placeholders::_2))); } ~WithSplitStreamingMethod_SubscribeRcStatus() override { @@ -2301,7 +2708,7 @@ class TelemetryService final { void BaseClassMustBeDerivedFromService(const Service *service) {} public: WithSplitStreamingMethod_SubscribeStatusText() { - ::grpc::Service::MarkMethodStreamed(14, + ::grpc::Service::MarkMethodStreamed(15, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest, ::mavsdk::rpc::telemetry::StatusTextResponse>(std::bind(&WithSplitStreamingMethod_SubscribeStatusText::StreamedSubscribeStatusText, this, std::placeholders::_1, std::placeholders::_2))); } ~WithSplitStreamingMethod_SubscribeStatusText() override { @@ -2315,8 +2722,48 @@ class TelemetryService final { // replace default version of method with split streamed virtual ::grpc::Status StreamedSubscribeStatusText(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::telemetry::SubscribeStatusTextRequest,::mavsdk::rpc::telemetry::StatusTextResponse>* server_split_streamer) = 0; }; - typedef WithSplitStreamingMethod_SubscribePosition > > > > > > > > > > > > > > SplitStreamedService; - typedef WithSplitStreamingMethod_SubscribePosition > > > > > > > > > > > > > > StreamedService; + template + class WithSplitStreamingMethod_SubscribeActuatorControlTarget : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + WithSplitStreamingMethod_SubscribeActuatorControlTarget() { + ::grpc::Service::MarkMethodStreamed(16, + new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest, ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>(std::bind(&WithSplitStreamingMethod_SubscribeActuatorControlTarget::StreamedSubscribeActuatorControlTarget, this, std::placeholders::_1, std::placeholders::_2))); + } + ~WithSplitStreamingMethod_SubscribeActuatorControlTarget() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeActuatorControlTarget(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeActuatorControlTarget(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest,::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>* server_split_streamer) = 0; + }; + template + class WithSplitStreamingMethod_SubscribeActuatorOutputStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service *service) {} + public: + WithSplitStreamingMethod_SubscribeActuatorOutputStatus() { + ::grpc::Service::MarkMethodStreamed(17, + new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest, ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>(std::bind(&WithSplitStreamingMethod_SubscribeActuatorOutputStatus::StreamedSubscribeActuatorOutputStatus, this, std::placeholders::_1, std::placeholders::_2))); + } + ~WithSplitStreamingMethod_SubscribeActuatorOutputStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeActuatorOutputStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* writer) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeActuatorOutputStatus(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest,::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>* server_split_streamer) = 0; + }; + typedef WithSplitStreamingMethod_SubscribePosition > > > > > > > > > > > > > > > > > SplitStreamedService; + typedef WithSplitStreamingMethod_SubscribePosition > > > > > > > > > > > > > > > > > StreamedService; }; } // namespace telemetry diff --git a/src/backend/src/generated/telemetry/telemetry.pb.cc b/src/backend/src/generated/telemetry/telemetry.pb.cc index a006dfef96..00701266d7 100644 --- a/src/backend/src/generated/telemetry/telemetry.pb.cc +++ b/src/backend/src/generated/telemetry/telemetry.pb.cc @@ -16,6 +16,9 @@ // @@protoc_insertion_point(includes) #include +extern PROTOBUF_INTERNAL_EXPORT_telemetry_2ftelemetry_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_ActuatorControlTarget_telemetry_2ftelemetry_2eproto; +extern PROTOBUF_INTERNAL_EXPORT_telemetry_2ftelemetry_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_ActuatorOutputStatus_telemetry_2ftelemetry_2eproto; +extern PROTOBUF_INTERNAL_EXPORT_telemetry_2ftelemetry_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_AngularVelocityBody_telemetry_2ftelemetry_2eproto; extern PROTOBUF_INTERNAL_EXPORT_telemetry_2ftelemetry_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_Battery_telemetry_2ftelemetry_2eproto; extern PROTOBUF_INTERNAL_EXPORT_telemetry_2ftelemetry_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_EulerAngle_telemetry_2ftelemetry_2eproto; extern PROTOBUF_INTERNAL_EXPORT_telemetry_2ftelemetry_2eproto ::google::protobuf::internal::SCCInfo<0> scc_info_GpsInfo_telemetry_2ftelemetry_2eproto; @@ -76,6 +79,14 @@ class AttitudeEulerResponseDefaultTypeInternal { public: ::google::protobuf::internal::ExplicitlyConstructed _instance; } _AttitudeEulerResponse_default_instance_; +class SubscribeAttitudeAngularVelocityBodyRequestDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed _instance; +} _SubscribeAttitudeAngularVelocityBodyRequest_default_instance_; +class AttitudeAngularVelocityBodyResponseDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed _instance; +} _AttitudeAngularVelocityBodyResponse_default_instance_; class SubscribeCameraAttitudeQuaternionRequestDefaultTypeInternal { public: ::google::protobuf::internal::ExplicitlyConstructed _instance; @@ -148,6 +159,22 @@ class StatusTextResponseDefaultTypeInternal { public: ::google::protobuf::internal::ExplicitlyConstructed _instance; } _StatusTextResponse_default_instance_; +class SubscribeActuatorControlTargetRequestDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed _instance; +} _SubscribeActuatorControlTargetRequest_default_instance_; +class ActuatorControlTargetResponseDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed _instance; +} _ActuatorControlTargetResponse_default_instance_; +class SubscribeActuatorOutputStatusRequestDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed _instance; +} _SubscribeActuatorOutputStatusRequest_default_instance_; +class ActuatorOutputStatusResponseDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed _instance; +} _ActuatorOutputStatusResponse_default_instance_; class PositionDefaultTypeInternal { public: ::google::protobuf::internal::ExplicitlyConstructed _instance; @@ -160,6 +187,10 @@ class EulerAngleDefaultTypeInternal { public: ::google::protobuf::internal::ExplicitlyConstructed _instance; } _EulerAngle_default_instance_; +class AngularVelocityBodyDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed _instance; +} _AngularVelocityBody_default_instance_; class SpeedNedDefaultTypeInternal { public: ::google::protobuf::internal::ExplicitlyConstructed _instance; @@ -184,6 +215,14 @@ class StatusTextDefaultTypeInternal { public: ::google::protobuf::internal::ExplicitlyConstructed _instance; } _StatusText_default_instance_; +class ActuatorControlTargetDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed _instance; +} _ActuatorControlTarget_default_instance_; +class ActuatorOutputStatusDefaultTypeInternal { + public: + ::google::protobuf::internal::ExplicitlyConstructed _instance; +} _ActuatorOutputStatus_default_instance_; } // namespace telemetry } // namespace rpc } // namespace mavsdk @@ -359,6 +398,35 @@ ::google::protobuf::internal::SCCInfo<1> scc_info_AttitudeEulerResponse_telemetr {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsAttitudeEulerResponse_telemetry_2ftelemetry_2eproto}, { &scc_info_EulerAngle_telemetry_2ftelemetry_2eproto.base,}}; +static void InitDefaultsSubscribeAttitudeAngularVelocityBodyRequest_telemetry_2ftelemetry_2eproto() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::mavsdk::rpc::telemetry::_SubscribeAttitudeAngularVelocityBodyRequest_default_instance_; + new (ptr) ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_SubscribeAttitudeAngularVelocityBodyRequest_telemetry_2ftelemetry_2eproto = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsSubscribeAttitudeAngularVelocityBodyRequest_telemetry_2ftelemetry_2eproto}, {}}; + +static void InitDefaultsAttitudeAngularVelocityBodyResponse_telemetry_2ftelemetry_2eproto() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::mavsdk::rpc::telemetry::_AttitudeAngularVelocityBodyResponse_default_instance_; + new (ptr) ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_AttitudeAngularVelocityBodyResponse_telemetry_2ftelemetry_2eproto = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsAttitudeAngularVelocityBodyResponse_telemetry_2ftelemetry_2eproto}, { + &scc_info_AngularVelocityBody_telemetry_2ftelemetry_2eproto.base,}}; + static void InitDefaultsSubscribeCameraAttitudeQuaternionRequest_telemetry_2ftelemetry_2eproto() { GOOGLE_PROTOBUF_VERIFY_VERSION; @@ -619,6 +687,64 @@ ::google::protobuf::internal::SCCInfo<1> scc_info_StatusTextResponse_telemetry_2 {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsStatusTextResponse_telemetry_2ftelemetry_2eproto}, { &scc_info_StatusText_telemetry_2ftelemetry_2eproto.base,}}; +static void InitDefaultsSubscribeActuatorControlTargetRequest_telemetry_2ftelemetry_2eproto() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::mavsdk::rpc::telemetry::_SubscribeActuatorControlTargetRequest_default_instance_; + new (ptr) ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_SubscribeActuatorControlTargetRequest_telemetry_2ftelemetry_2eproto = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsSubscribeActuatorControlTargetRequest_telemetry_2ftelemetry_2eproto}, {}}; + +static void InitDefaultsActuatorControlTargetResponse_telemetry_2ftelemetry_2eproto() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::mavsdk::rpc::telemetry::_ActuatorControlTargetResponse_default_instance_; + new (ptr) ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_ActuatorControlTargetResponse_telemetry_2ftelemetry_2eproto = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsActuatorControlTargetResponse_telemetry_2ftelemetry_2eproto}, { + &scc_info_ActuatorControlTarget_telemetry_2ftelemetry_2eproto.base,}}; + +static void InitDefaultsSubscribeActuatorOutputStatusRequest_telemetry_2ftelemetry_2eproto() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::mavsdk::rpc::telemetry::_SubscribeActuatorOutputStatusRequest_default_instance_; + new (ptr) ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_SubscribeActuatorOutputStatusRequest_telemetry_2ftelemetry_2eproto = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsSubscribeActuatorOutputStatusRequest_telemetry_2ftelemetry_2eproto}, {}}; + +static void InitDefaultsActuatorOutputStatusResponse_telemetry_2ftelemetry_2eproto() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::mavsdk::rpc::telemetry::_ActuatorOutputStatusResponse_default_instance_; + new (ptr) ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<1> scc_info_ActuatorOutputStatusResponse_telemetry_2ftelemetry_2eproto = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 1, InitDefaultsActuatorOutputStatusResponse_telemetry_2ftelemetry_2eproto}, { + &scc_info_ActuatorOutputStatus_telemetry_2ftelemetry_2eproto.base,}}; + static void InitDefaultsPosition_telemetry_2ftelemetry_2eproto() { GOOGLE_PROTOBUF_VERIFY_VERSION; @@ -661,6 +787,20 @@ static void InitDefaultsEulerAngle_telemetry_2ftelemetry_2eproto() { ::google::protobuf::internal::SCCInfo<0> scc_info_EulerAngle_telemetry_2ftelemetry_2eproto = {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsEulerAngle_telemetry_2ftelemetry_2eproto}, {}}; +static void InitDefaultsAngularVelocityBody_telemetry_2ftelemetry_2eproto() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::mavsdk::rpc::telemetry::_AngularVelocityBody_default_instance_; + new (ptr) ::mavsdk::rpc::telemetry::AngularVelocityBody(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::mavsdk::rpc::telemetry::AngularVelocityBody::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_AngularVelocityBody_telemetry_2ftelemetry_2eproto = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsAngularVelocityBody_telemetry_2ftelemetry_2eproto}, {}}; + static void InitDefaultsSpeedNed_telemetry_2ftelemetry_2eproto() { GOOGLE_PROTOBUF_VERIFY_VERSION; @@ -745,6 +885,34 @@ static void InitDefaultsStatusText_telemetry_2ftelemetry_2eproto() { ::google::protobuf::internal::SCCInfo<0> scc_info_StatusText_telemetry_2ftelemetry_2eproto = {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsStatusText_telemetry_2ftelemetry_2eproto}, {}}; +static void InitDefaultsActuatorControlTarget_telemetry_2ftelemetry_2eproto() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::mavsdk::rpc::telemetry::_ActuatorControlTarget_default_instance_; + new (ptr) ::mavsdk::rpc::telemetry::ActuatorControlTarget(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::mavsdk::rpc::telemetry::ActuatorControlTarget::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_ActuatorControlTarget_telemetry_2ftelemetry_2eproto = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsActuatorControlTarget_telemetry_2ftelemetry_2eproto}, {}}; + +static void InitDefaultsActuatorOutputStatus_telemetry_2ftelemetry_2eproto() { + GOOGLE_PROTOBUF_VERIFY_VERSION; + + { + void* ptr = &::mavsdk::rpc::telemetry::_ActuatorOutputStatus_default_instance_; + new (ptr) ::mavsdk::rpc::telemetry::ActuatorOutputStatus(); + ::google::protobuf::internal::OnShutdownDestroyMessage(ptr); + } + ::mavsdk::rpc::telemetry::ActuatorOutputStatus::InitAsDefaultInstance(); +} + +::google::protobuf::internal::SCCInfo<0> scc_info_ActuatorOutputStatus_telemetry_2ftelemetry_2eproto = + {{ATOMIC_VAR_INIT(::google::protobuf::internal::SCCInfoBase::kUninitialized), 0, InitDefaultsActuatorOutputStatus_telemetry_2ftelemetry_2eproto}, {}}; + void InitDefaults_telemetry_2ftelemetry_2eproto() { ::google::protobuf::internal::InitSCC(&scc_info_SubscribePositionRequest_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_PositionResponse_telemetry_2ftelemetry_2eproto.base); @@ -758,6 +926,8 @@ void InitDefaults_telemetry_2ftelemetry_2eproto() { ::google::protobuf::internal::InitSCC(&scc_info_AttitudeQuaternionResponse_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_SubscribeAttitudeEulerRequest_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_AttitudeEulerResponse_telemetry_2ftelemetry_2eproto.base); + ::google::protobuf::internal::InitSCC(&scc_info_SubscribeAttitudeAngularVelocityBodyRequest_telemetry_2ftelemetry_2eproto.base); + ::google::protobuf::internal::InitSCC(&scc_info_AttitudeAngularVelocityBodyResponse_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_SubscribeCameraAttitudeQuaternionRequest_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_CameraAttitudeQuaternionResponse_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_SubscribeCameraAttitudeEulerRequest_telemetry_2ftelemetry_2eproto.base); @@ -776,18 +946,25 @@ void InitDefaults_telemetry_2ftelemetry_2eproto() { ::google::protobuf::internal::InitSCC(&scc_info_RcStatusResponse_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_SubscribeStatusTextRequest_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_StatusTextResponse_telemetry_2ftelemetry_2eproto.base); + ::google::protobuf::internal::InitSCC(&scc_info_SubscribeActuatorControlTargetRequest_telemetry_2ftelemetry_2eproto.base); + ::google::protobuf::internal::InitSCC(&scc_info_ActuatorControlTargetResponse_telemetry_2ftelemetry_2eproto.base); + ::google::protobuf::internal::InitSCC(&scc_info_SubscribeActuatorOutputStatusRequest_telemetry_2ftelemetry_2eproto.base); + ::google::protobuf::internal::InitSCC(&scc_info_ActuatorOutputStatusResponse_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_Position_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_Quaternion_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_EulerAngle_telemetry_2ftelemetry_2eproto.base); + ::google::protobuf::internal::InitSCC(&scc_info_AngularVelocityBody_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_SpeedNed_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_GpsInfo_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_Battery_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_Health_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_RcStatus_telemetry_2ftelemetry_2eproto.base); ::google::protobuf::internal::InitSCC(&scc_info_StatusText_telemetry_2ftelemetry_2eproto.base); + ::google::protobuf::internal::InitSCC(&scc_info_ActuatorControlTarget_telemetry_2ftelemetry_2eproto.base); + ::google::protobuf::internal::InitSCC(&scc_info_ActuatorOutputStatus_telemetry_2ftelemetry_2eproto.base); } -::google::protobuf::Metadata file_level_metadata_telemetry_2ftelemetry_2eproto[39]; +::google::protobuf::Metadata file_level_metadata_telemetry_2ftelemetry_2eproto[48]; const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors_telemetry_2ftelemetry_2eproto[3]; constexpr ::google::protobuf::ServiceDescriptor const** file_level_service_descriptors_telemetry_2ftelemetry_2eproto = nullptr; @@ -859,6 +1036,17 @@ const ::google::protobuf::uint32 TableStruct_telemetry_2ftelemetry_2eproto::offs ~0u, // no _weak_field_map_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::AttitudeEulerResponse, attitude_euler_), ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse, attitude_angular_velocity_body_), + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -958,6 +1146,28 @@ const ::google::protobuf::uint32 TableStruct_telemetry_2ftelemetry_2eproto::offs ~0u, // no _weak_field_map_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::StatusTextResponse, status_text_), ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::ActuatorControlTargetResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::ActuatorControlTargetResponse, actuator_control_target_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse, actuator_output_status_), + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::Position, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -984,6 +1194,14 @@ const ::google::protobuf::uint32 TableStruct_telemetry_2ftelemetry_2eproto::offs PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::EulerAngle, pitch_deg_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::EulerAngle, yaw_deg_), ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::AngularVelocityBody, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::AngularVelocityBody, roll_rad_s_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::AngularVelocityBody, pitch_rad_s_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::AngularVelocityBody, yaw_rad_s_), + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::SpeedNed, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -1032,6 +1250,20 @@ const ::google::protobuf::uint32 TableStruct_telemetry_2ftelemetry_2eproto::offs ~0u, // no _weak_field_map_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::StatusText, type_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::StatusText, text_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::ActuatorControlTarget, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::ActuatorControlTarget, group_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::ActuatorControlTarget, controls_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::ActuatorOutputStatus, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::ActuatorOutputStatus, active_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::telemetry::ActuatorOutputStatus, actuator_), }; static const ::google::protobuf::internal::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { { 0, -1, sizeof(::mavsdk::rpc::telemetry::SubscribePositionRequest)}, @@ -1046,33 +1278,42 @@ static const ::google::protobuf::internal::MigrationSchema schemas[] PROTOBUF_SE { 49, -1, sizeof(::mavsdk::rpc::telemetry::AttitudeQuaternionResponse)}, { 55, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest)}, { 60, -1, sizeof(::mavsdk::rpc::telemetry::AttitudeEulerResponse)}, - { 66, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest)}, - { 71, -1, sizeof(::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse)}, - { 77, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest)}, - { 82, -1, sizeof(::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse)}, - { 88, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeGroundSpeedNedRequest)}, - { 93, -1, sizeof(::mavsdk::rpc::telemetry::GroundSpeedNedResponse)}, - { 99, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest)}, - { 104, -1, sizeof(::mavsdk::rpc::telemetry::GpsInfoResponse)}, - { 110, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeBatteryRequest)}, - { 115, -1, sizeof(::mavsdk::rpc::telemetry::BatteryResponse)}, - { 121, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeFlightModeRequest)}, - { 126, -1, sizeof(::mavsdk::rpc::telemetry::FlightModeResponse)}, - { 132, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeHealthRequest)}, - { 137, -1, sizeof(::mavsdk::rpc::telemetry::HealthResponse)}, - { 143, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeRcStatusRequest)}, - { 148, -1, sizeof(::mavsdk::rpc::telemetry::RcStatusResponse)}, - { 154, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeStatusTextRequest)}, - { 159, -1, sizeof(::mavsdk::rpc::telemetry::StatusTextResponse)}, - { 165, -1, sizeof(::mavsdk::rpc::telemetry::Position)}, - { 174, -1, sizeof(::mavsdk::rpc::telemetry::Quaternion)}, - { 183, -1, sizeof(::mavsdk::rpc::telemetry::EulerAngle)}, - { 191, -1, sizeof(::mavsdk::rpc::telemetry::SpeedNed)}, - { 199, -1, sizeof(::mavsdk::rpc::telemetry::GpsInfo)}, - { 206, -1, sizeof(::mavsdk::rpc::telemetry::Battery)}, - { 213, -1, sizeof(::mavsdk::rpc::telemetry::Health)}, - { 225, -1, sizeof(::mavsdk::rpc::telemetry::RcStatus)}, - { 233, -1, sizeof(::mavsdk::rpc::telemetry::StatusText)}, + { 66, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest)}, + { 71, -1, sizeof(::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse)}, + { 77, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest)}, + { 82, -1, sizeof(::mavsdk::rpc::telemetry::CameraAttitudeQuaternionResponse)}, + { 88, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeCameraAttitudeEulerRequest)}, + { 93, -1, sizeof(::mavsdk::rpc::telemetry::CameraAttitudeEulerResponse)}, + { 99, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeGroundSpeedNedRequest)}, + { 104, -1, sizeof(::mavsdk::rpc::telemetry::GroundSpeedNedResponse)}, + { 110, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeGpsInfoRequest)}, + { 115, -1, sizeof(::mavsdk::rpc::telemetry::GpsInfoResponse)}, + { 121, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeBatteryRequest)}, + { 126, -1, sizeof(::mavsdk::rpc::telemetry::BatteryResponse)}, + { 132, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeFlightModeRequest)}, + { 137, -1, sizeof(::mavsdk::rpc::telemetry::FlightModeResponse)}, + { 143, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeHealthRequest)}, + { 148, -1, sizeof(::mavsdk::rpc::telemetry::HealthResponse)}, + { 154, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeRcStatusRequest)}, + { 159, -1, sizeof(::mavsdk::rpc::telemetry::RcStatusResponse)}, + { 165, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeStatusTextRequest)}, + { 170, -1, sizeof(::mavsdk::rpc::telemetry::StatusTextResponse)}, + { 176, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest)}, + { 181, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorControlTargetResponse)}, + { 187, -1, sizeof(::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest)}, + { 192, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse)}, + { 198, -1, sizeof(::mavsdk::rpc::telemetry::Position)}, + { 207, -1, sizeof(::mavsdk::rpc::telemetry::Quaternion)}, + { 216, -1, sizeof(::mavsdk::rpc::telemetry::EulerAngle)}, + { 224, -1, sizeof(::mavsdk::rpc::telemetry::AngularVelocityBody)}, + { 232, -1, sizeof(::mavsdk::rpc::telemetry::SpeedNed)}, + { 240, -1, sizeof(::mavsdk::rpc::telemetry::GpsInfo)}, + { 247, -1, sizeof(::mavsdk::rpc::telemetry::Battery)}, + { 254, -1, sizeof(::mavsdk::rpc::telemetry::Health)}, + { 266, -1, sizeof(::mavsdk::rpc::telemetry::RcStatus)}, + { 274, -1, sizeof(::mavsdk::rpc::telemetry::StatusText)}, + { 281, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorControlTarget)}, + { 288, -1, sizeof(::mavsdk::rpc::telemetry::ActuatorOutputStatus)}, }; static ::google::protobuf::Message const * const file_default_instances[] = { @@ -1088,6 +1329,8 @@ static ::google::protobuf::Message const * const file_default_instances[] = { reinterpret_cast(&::mavsdk::rpc::telemetry::_AttitudeQuaternionResponse_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_SubscribeAttitudeEulerRequest_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_AttitudeEulerResponse_default_instance_), + reinterpret_cast(&::mavsdk::rpc::telemetry::_SubscribeAttitudeAngularVelocityBodyRequest_default_instance_), + reinterpret_cast(&::mavsdk::rpc::telemetry::_AttitudeAngularVelocityBodyResponse_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_SubscribeCameraAttitudeQuaternionRequest_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_CameraAttitudeQuaternionResponse_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_SubscribeCameraAttitudeEulerRequest_default_instance_), @@ -1106,21 +1349,28 @@ static ::google::protobuf::Message const * const file_default_instances[] = { reinterpret_cast(&::mavsdk::rpc::telemetry::_RcStatusResponse_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_SubscribeStatusTextRequest_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_StatusTextResponse_default_instance_), + reinterpret_cast(&::mavsdk::rpc::telemetry::_SubscribeActuatorControlTargetRequest_default_instance_), + reinterpret_cast(&::mavsdk::rpc::telemetry::_ActuatorControlTargetResponse_default_instance_), + reinterpret_cast(&::mavsdk::rpc::telemetry::_SubscribeActuatorOutputStatusRequest_default_instance_), + reinterpret_cast(&::mavsdk::rpc::telemetry::_ActuatorOutputStatusResponse_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_Position_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_Quaternion_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_EulerAngle_default_instance_), + reinterpret_cast(&::mavsdk::rpc::telemetry::_AngularVelocityBody_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_SpeedNed_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_GpsInfo_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_Battery_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_Health_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_RcStatus_default_instance_), reinterpret_cast(&::mavsdk::rpc::telemetry::_StatusText_default_instance_), + reinterpret_cast(&::mavsdk::rpc::telemetry::_ActuatorControlTarget_default_instance_), + reinterpret_cast(&::mavsdk::rpc::telemetry::_ActuatorOutputStatus_default_instance_), }; ::google::protobuf::internal::AssignDescriptorsTable assign_descriptors_table_telemetry_2ftelemetry_2eproto = { {}, AddDescriptors_telemetry_2ftelemetry_2eproto, "telemetry/telemetry.proto", schemas, file_default_instances, TableStruct_telemetry_2ftelemetry_2eproto::offsets, - file_level_metadata_telemetry_2ftelemetry_2eproto, 39, file_level_enum_descriptors_telemetry_2ftelemetry_2eproto, file_level_service_descriptors_telemetry_2ftelemetry_2eproto, + file_level_metadata_telemetry_2ftelemetry_2eproto, 48, file_level_enum_descriptors_telemetry_2ftelemetry_2eproto, file_level_service_descriptors_telemetry_2ftelemetry_2eproto, }; const char descriptor_table_protodef_telemetry_2ftelemetry_2eproto[] = @@ -1139,113 +1389,142 @@ const char descriptor_table_protodef_telemetry_2ftelemetry_2eproto[] = "rnion\"\037\n\035SubscribeAttitudeEulerRequest\"Q" "\n\025AttitudeEulerResponse\0228\n\016attitude_eule" "r\030\001 \001(\0132 .mavsdk.rpc.telemetry.EulerAngl" - "e\"*\n(SubscribeCameraAttitudeQuaternionRe" - "quest\"a\n CameraAttitudeQuaternionRespons" - "e\022=\n\023attitude_quaternion\030\001 \001(\0132 .mavsdk." - "rpc.telemetry.Quaternion\"%\n#SubscribeCam" - "eraAttitudeEulerRequest\"W\n\033CameraAttitud" - "eEulerResponse\0228\n\016attitude_euler\030\001 \001(\0132 " - ".mavsdk.rpc.telemetry.EulerAngle\" \n\036Subs" - "cribeGroundSpeedNedRequest\"R\n\026GroundSpee" - "dNedResponse\0228\n\020ground_speed_ned\030\001 \001(\0132\036" - ".mavsdk.rpc.telemetry.SpeedNed\"\031\n\027Subscr" - "ibeGpsInfoRequest\"B\n\017GpsInfoResponse\022/\n\010" - "gps_info\030\001 \001(\0132\035.mavsdk.rpc.telemetry.Gp" - "sInfo\"\031\n\027SubscribeBatteryRequest\"A\n\017Batt" - "eryResponse\022.\n\007battery\030\001 \001(\0132\035.mavsdk.rp" - "c.telemetry.Battery\"\034\n\032SubscribeFlightMo" - "deRequest\"K\n\022FlightModeResponse\0225\n\013fligh" - "t_mode\030\001 \001(\0162 .mavsdk.rpc.telemetry.Flig" - "htMode\"\030\n\026SubscribeHealthRequest\">\n\016Heal" - "thResponse\022,\n\006health\030\001 \001(\0132\034.mavsdk.rpc." - "telemetry.Health\"\032\n\030SubscribeRcStatusReq" - "uest\"E\n\020RcStatusResponse\0221\n\trc_status\030\001 " - "\001(\0132\036.mavsdk.rpc.telemetry.RcStatus\"\034\n\032S" - "ubscribeStatusTextRequest\"K\n\022StatusTextR" - "esponse\0225\n\013status_text\030\001 \001(\0132 .mavsdk.rp" - "c.telemetry.StatusText\"q\n\010Position\022\024\n\014la" - "titude_deg\030\001 \001(\001\022\025\n\rlongitude_deg\030\002 \001(\001\022" - "\033\n\023absolute_altitude_m\030\003 \001(\002\022\033\n\023relative" - "_altitude_m\030\004 \001(\002\"8\n\nQuaternion\022\t\n\001w\030\001 \001" - "(\002\022\t\n\001x\030\002 \001(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"B\n\nE" - "ulerAngle\022\020\n\010roll_deg\030\001 \001(\002\022\021\n\tpitch_deg" - "\030\002 \001(\002\022\017\n\007yaw_deg\030\003 \001(\002\"\\\n\010SpeedNed\022\032\n\022v" - "elocity_north_m_s\030\001 \001(\002\022\031\n\021velocity_east" - "_m_s\030\002 \001(\002\022\031\n\021velocity_down_m_s\030\003 \001(\002\"R\n" - "\007GpsInfo\022\026\n\016num_satellites\030\001 \001(\005\022/\n\010fix_" - "type\030\002 \001(\0162\035.mavsdk.rpc.telemetry.FixTyp" - "e\"7\n\007Battery\022\021\n\tvoltage_v\030\001 \001(\002\022\031\n\021remai" - "ning_percent\030\002 \001(\002\"\371\001\n\006Health\022#\n\033is_gyro" - "meter_calibration_ok\030\001 \001(\010\022\'\n\037is_acceler" - "ometer_calibration_ok\030\002 \001(\010\022&\n\036is_magnet" - "ometer_calibration_ok\030\003 \001(\010\022\037\n\027is_level_" - "calibration_ok\030\004 \001(\010\022\034\n\024is_local_positio" - "n_ok\030\005 \001(\010\022\035\n\025is_global_position_ok\030\006 \001(" - "\010\022\033\n\023is_home_position_ok\030\007 \001(\010\"]\n\010RcStat" - "us\022\032\n\022was_available_once\030\001 \001(\010\022\024\n\014is_ava" - "ilable\030\002 \001(\010\022\037\n\027signal_strength_percent\030" - "\003 \001(\002\"\210\001\n\nStatusText\0229\n\004type\030\001 \001(\0162+.mav" - "sdk.rpc.telemetry.StatusText.StatusType\022" - "\014\n\004text\030\002 \001(\t\"1\n\nStatusType\022\010\n\004INFO\020\000\022\013\n" - "\007WARNING\020\001\022\014\n\010CRITICAL\020\002*e\n\007FixType\022\n\n\006N" - "O_GPS\020\000\022\n\n\006NO_FIX\020\001\022\n\n\006FIX_2D\020\002\022\n\n\006FIX_3" - "D\020\003\022\014\n\010FIX_DGPS\020\004\022\r\n\tRTK_FLOAT\020\005\022\r\n\tRTK_" - "FIXED\020\006*\205\001\n\nFlightMode\022\013\n\007UNKNOWN\020\000\022\t\n\005R" - "EADY\020\001\022\013\n\007TAKEOFF\020\002\022\010\n\004HOLD\020\003\022\013\n\007MISSION" - "\020\004\022\024\n\020RETURN_TO_LAUNCH\020\005\022\010\n\004LAND\020\006\022\014\n\010OF" - "FBOARD\020\007\022\r\n\tFOLLOW_ME\020\0102\247\016\n\020TelemetrySer" - "vice\022o\n\021SubscribePosition\022..mavsdk.rpc.t" - "elemetry.SubscribePositionRequest\032&.mavs" - "dk.rpc.telemetry.PositionResponse\"\0000\001\022c\n" - "\rSubscribeHome\022*.mavsdk.rpc.telemetry.Su" - "bscribeHomeRequest\032\".mavsdk.rpc.telemetr" - "y.HomeResponse\"\0000\001\022f\n\016SubscribeInAir\022+.m" - "avsdk.rpc.telemetry.SubscribeInAirReques" - "t\032#.mavsdk.rpc.telemetry.InAirResponse\"\000" - "0\001\022f\n\016SubscribeArmed\022+.mavsdk.rpc.teleme" - "try.SubscribeArmedRequest\032#.mavsdk.rpc.t" - "elemetry.ArmedResponse\"\0000\001\022\215\001\n\033Subscribe" - "AttitudeQuaternion\0228.mavsdk.rpc.telemetr" - "y.SubscribeAttitudeQuaternionRequest\0320.m" - "avsdk.rpc.telemetry.AttitudeQuaternionRe" - "sponse\"\0000\001\022~\n\026SubscribeAttitudeEuler\0223.m" - "avsdk.rpc.telemetry.SubscribeAttitudeEul" - "erRequest\032+.mavsdk.rpc.telemetry.Attitud" - "eEulerResponse\"\0000\001\022\237\001\n!SubscribeCameraAt" - "titudeQuaternion\022>.mavsdk.rpc.telemetry." - "SubscribeCameraAttitudeQuaternionRequest" - "\0326.mavsdk.rpc.telemetry.CameraAttitudeQu" - "aternionResponse\"\0000\001\022\220\001\n\034SubscribeCamera" - "AttitudeEuler\0229.mavsdk.rpc.telemetry.Sub" - "scribeCameraAttitudeEulerRequest\0321.mavsd" - "k.rpc.telemetry.CameraAttitudeEulerRespo" - "nse\"\0000\001\022\201\001\n\027SubscribeGroundSpeedNed\0224.ma" - "vsdk.rpc.telemetry.SubscribeGroundSpeedN" - "edRequest\032,.mavsdk.rpc.telemetry.GroundS" - "peedNedResponse\"\0000\001\022l\n\020SubscribeGpsInfo\022" - "-.mavsdk.rpc.telemetry.SubscribeGpsInfoR" - "equest\032%.mavsdk.rpc.telemetry.GpsInfoRes" - "ponse\"\0000\001\022l\n\020SubscribeBattery\022-.mavsdk.r" - "pc.telemetry.SubscribeBatteryRequest\032%.m" - "avsdk.rpc.telemetry.BatteryResponse\"\0000\001\022" - "u\n\023SubscribeFlightMode\0220.mavsdk.rpc.tele" - "metry.SubscribeFlightModeRequest\032(.mavsd" - "k.rpc.telemetry.FlightModeResponse\"\0000\001\022i" - "\n\017SubscribeHealth\022,.mavsdk.rpc.telemetry" - ".SubscribeHealthRequest\032$.mavsdk.rpc.tel" - "emetry.HealthResponse\"\0000\001\022o\n\021SubscribeRc" - "Status\022..mavsdk.rpc.telemetry.SubscribeR" - "cStatusRequest\032&.mavsdk.rpc.telemetry.Rc" - "StatusResponse\"\0000\001\022u\n\023SubscribeStatusTex" - "t\0220.mavsdk.rpc.telemetry.SubscribeStatus" - "TextRequest\032(.mavsdk.rpc.telemetry.Statu" - "sTextResponse\"\0000\001B%\n\023io.mavsdk.telemetry" - "B\016TelemetryProtob\006proto3" + "e\"-\n+SubscribeAttitudeAngularVelocityBod" + "yRequest\"x\n#AttitudeAngularVelocityBodyR" + "esponse\022Q\n\036attitude_angular_velocity_bod" + "y\030\001 \001(\0132).mavsdk.rpc.telemetry.AngularVe" + "locityBody\"*\n(SubscribeCameraAttitudeQua" + "ternionRequest\"a\n CameraAttitudeQuaterni" + "onResponse\022=\n\023attitude_quaternion\030\001 \001(\0132" + " .mavsdk.rpc.telemetry.Quaternion\"%\n#Sub" + "scribeCameraAttitudeEulerRequest\"W\n\033Came" + "raAttitudeEulerResponse\0228\n\016attitude_eule" + "r\030\001 \001(\0132 .mavsdk.rpc.telemetry.EulerAngl" + "e\" \n\036SubscribeGroundSpeedNedRequest\"R\n\026G" + "roundSpeedNedResponse\0228\n\020ground_speed_ne" + "d\030\001 \001(\0132\036.mavsdk.rpc.telemetry.SpeedNed\"" + "\031\n\027SubscribeGpsInfoRequest\"B\n\017GpsInfoRes" + "ponse\022/\n\010gps_info\030\001 \001(\0132\035.mavsdk.rpc.tel" + "emetry.GpsInfo\"\031\n\027SubscribeBatteryReques" + "t\"A\n\017BatteryResponse\022.\n\007battery\030\001 \001(\0132\035." + "mavsdk.rpc.telemetry.Battery\"\034\n\032Subscrib" + "eFlightModeRequest\"K\n\022FlightModeResponse" + "\0225\n\013flight_mode\030\001 \001(\0162 .mavsdk.rpc.telem" + "etry.FlightMode\"\030\n\026SubscribeHealthReques" + "t\">\n\016HealthResponse\022,\n\006health\030\001 \001(\0132\034.ma" + "vsdk.rpc.telemetry.Health\"\032\n\030SubscribeRc" + "StatusRequest\"E\n\020RcStatusResponse\0221\n\trc_" + "status\030\001 \001(\0132\036.mavsdk.rpc.telemetry.RcSt" + "atus\"\034\n\032SubscribeStatusTextRequest\"K\n\022St" + "atusTextResponse\0225\n\013status_text\030\001 \001(\0132 ." + "mavsdk.rpc.telemetry.StatusText\"\'\n%Subsc" + "ribeActuatorControlTargetRequest\"m\n\035Actu" + "atorControlTargetResponse\022L\n\027actuator_co" + "ntrol_target\030\001 \001(\0132+.mavsdk.rpc.telemetr" + "y.ActuatorControlTarget\"&\n$SubscribeActu" + "atorOutputStatusRequest\"j\n\034ActuatorOutpu" + "tStatusResponse\022J\n\026actuator_output_statu" + "s\030\001 \001(\0132*.mavsdk.rpc.telemetry.ActuatorO" + "utputStatus\"q\n\010Position\022\024\n\014latitude_deg\030" + "\001 \001(\001\022\025\n\rlongitude_deg\030\002 \001(\001\022\033\n\023absolute" + "_altitude_m\030\003 \001(\002\022\033\n\023relative_altitude_m" + "\030\004 \001(\002\"8\n\nQuaternion\022\t\n\001w\030\001 \001(\002\022\t\n\001x\030\002 \001" + "(\002\022\t\n\001y\030\003 \001(\002\022\t\n\001z\030\004 \001(\002\"B\n\nEulerAngle\022\020" + "\n\010roll_deg\030\001 \001(\002\022\021\n\tpitch_deg\030\002 \001(\002\022\017\n\007y" + "aw_deg\030\003 \001(\002\"Q\n\023AngularVelocityBody\022\022\n\nr" + "oll_rad_s\030\001 \001(\002\022\023\n\013pitch_rad_s\030\002 \001(\002\022\021\n\t" + "yaw_rad_s\030\003 \001(\002\"\\\n\010SpeedNed\022\032\n\022velocity_" + "north_m_s\030\001 \001(\002\022\031\n\021velocity_east_m_s\030\002 \001" + "(\002\022\031\n\021velocity_down_m_s\030\003 \001(\002\"R\n\007GpsInfo" + "\022\026\n\016num_satellites\030\001 \001(\005\022/\n\010fix_type\030\002 \001" + "(\0162\035.mavsdk.rpc.telemetry.FixType\"7\n\007Bat" + "tery\022\021\n\tvoltage_v\030\001 \001(\002\022\031\n\021remaining_per" + "cent\030\002 \001(\002\"\371\001\n\006Health\022#\n\033is_gyrometer_ca" + "libration_ok\030\001 \001(\010\022\'\n\037is_accelerometer_c" + "alibration_ok\030\002 \001(\010\022&\n\036is_magnetometer_c" + "alibration_ok\030\003 \001(\010\022\037\n\027is_level_calibrat" + "ion_ok\030\004 \001(\010\022\034\n\024is_local_position_ok\030\005 \001" + "(\010\022\035\n\025is_global_position_ok\030\006 \001(\010\022\033\n\023is_" + "home_position_ok\030\007 \001(\010\"]\n\010RcStatus\022\032\n\022wa" + "s_available_once\030\001 \001(\010\022\024\n\014is_available\030\002" + " \001(\010\022\037\n\027signal_strength_percent\030\003 \001(\002\"\210\001" + "\n\nStatusText\0229\n\004type\030\001 \001(\0162+.mavsdk.rpc." + "telemetry.StatusText.StatusType\022\014\n\004text\030" + "\002 \001(\t\"1\n\nStatusType\022\010\n\004INFO\020\000\022\013\n\007WARNING" + "\020\001\022\014\n\010CRITICAL\020\002\"8\n\025ActuatorControlTarge" + "t\022\r\n\005group\030\001 \001(\005\022\020\n\010controls\030\002 \003(\002\"8\n\024Ac" + "tuatorOutputStatus\022\016\n\006active\030\001 \001(\r\022\020\n\010ac" + "tuator\030\002 \003(\002*e\n\007FixType\022\n\n\006NO_GPS\020\000\022\n\n\006N" + "O_FIX\020\001\022\n\n\006FIX_2D\020\002\022\n\n\006FIX_3D\020\003\022\014\n\010FIX_D" + "GPS\020\004\022\r\n\tRTK_FLOAT\020\005\022\r\n\tRTK_FIXED\020\006*\205\001\n\n" + "FlightMode\022\013\n\007UNKNOWN\020\000\022\t\n\005READY\020\001\022\013\n\007TA" + "KEOFF\020\002\022\010\n\004HOLD\020\003\022\013\n\007MISSION\020\004\022\024\n\020RETURN" + "_TO_LAUNCH\020\005\022\010\n\004LAND\020\006\022\014\n\010OFFBOARD\020\007\022\r\n\t" + "FOLLOW_ME\020\0102\201\022\n\020TelemetryService\022o\n\021Subs" + "cribePosition\022..mavsdk.rpc.telemetry.Sub" + "scribePositionRequest\032&.mavsdk.rpc.telem" + "etry.PositionResponse\"\0000\001\022c\n\rSubscribeHo" + "me\022*.mavsdk.rpc.telemetry.SubscribeHomeR" + "equest\032\".mavsdk.rpc.telemetry.HomeRespon" + "se\"\0000\001\022f\n\016SubscribeInAir\022+.mavsdk.rpc.te" + "lemetry.SubscribeInAirRequest\032#.mavsdk.r" + "pc.telemetry.InAirResponse\"\0000\001\022f\n\016Subscr" + "ibeArmed\022+.mavsdk.rpc.telemetry.Subscrib" + "eArmedRequest\032#.mavsdk.rpc.telemetry.Arm" + "edResponse\"\0000\001\022\215\001\n\033SubscribeAttitudeQuat" + "ernion\0228.mavsdk.rpc.telemetry.SubscribeA" + "ttitudeQuaternionRequest\0320.mavsdk.rpc.te" + "lemetry.AttitudeQuaternionResponse\"\0000\001\022~" + "\n\026SubscribeAttitudeEuler\0223.mavsdk.rpc.te" + "lemetry.SubscribeAttitudeEulerRequest\032+." + "mavsdk.rpc.telemetry.AttitudeEulerRespon" + "se\"\0000\001\022\250\001\n$SubscribeAttitudeAngularVeloc" + "ityBody\022A.mavsdk.rpc.telemetry.Subscribe" + "AttitudeAngularVelocityBodyRequest\0329.mav" + "sdk.rpc.telemetry.AttitudeAngularVelocit" + "yBodyResponse\"\0000\001\022\237\001\n!SubscribeCameraAtt" + "itudeQuaternion\022>.mavsdk.rpc.telemetry.S" + "ubscribeCameraAttitudeQuaternionRequest\032" + "6.mavsdk.rpc.telemetry.CameraAttitudeQua" + "ternionResponse\"\0000\001\022\220\001\n\034SubscribeCameraA" + "ttitudeEuler\0229.mavsdk.rpc.telemetry.Subs" + "cribeCameraAttitudeEulerRequest\0321.mavsdk" + ".rpc.telemetry.CameraAttitudeEulerRespon" + "se\"\0000\001\022\201\001\n\027SubscribeGroundSpeedNed\0224.mav" + "sdk.rpc.telemetry.SubscribeGroundSpeedNe" + "dRequest\032,.mavsdk.rpc.telemetry.GroundSp" + "eedNedResponse\"\0000\001\022l\n\020SubscribeGpsInfo\022-" + ".mavsdk.rpc.telemetry.SubscribeGpsInfoRe" + "quest\032%.mavsdk.rpc.telemetry.GpsInfoResp" + "onse\"\0000\001\022l\n\020SubscribeBattery\022-.mavsdk.rp" + "c.telemetry.SubscribeBatteryRequest\032%.ma" + "vsdk.rpc.telemetry.BatteryResponse\"\0000\001\022u" + "\n\023SubscribeFlightMode\0220.mavsdk.rpc.telem" + "etry.SubscribeFlightModeRequest\032(.mavsdk" + ".rpc.telemetry.FlightModeResponse\"\0000\001\022i\n" + "\017SubscribeHealth\022,.mavsdk.rpc.telemetry." + "SubscribeHealthRequest\032$.mavsdk.rpc.tele" + "metry.HealthResponse\"\0000\001\022o\n\021SubscribeRcS" + "tatus\022..mavsdk.rpc.telemetry.SubscribeRc" + "StatusRequest\032&.mavsdk.rpc.telemetry.RcS" + "tatusResponse\"\0000\001\022u\n\023SubscribeStatusText" + "\0220.mavsdk.rpc.telemetry.SubscribeStatusT" + "extRequest\032(.mavsdk.rpc.telemetry.Status" + "TextResponse\"\0000\001\022\226\001\n\036SubscribeActuatorCo" + "ntrolTarget\022;.mavsdk.rpc.telemetry.Subsc" + "ribeActuatorControlTargetRequest\0323.mavsd" + "k.rpc.telemetry.ActuatorControlTargetRes" + "ponse\"\0000\001\022\223\001\n\035SubscribeActuatorOutputSta" + "tus\022:.mavsdk.rpc.telemetry.SubscribeActu" + "atorOutputStatusRequest\0322.mavsdk.rpc.tel" + "emetry.ActuatorOutputStatusResponse\"\0000\001B" + "%\n\023io.mavsdk.telemetryB\016TelemetryProtob\006" + "proto3" ; ::google::protobuf::internal::DescriptorTable descriptor_table_telemetry_2ftelemetry_2eproto = { false, InitDefaults_telemetry_2ftelemetry_2eproto, descriptor_table_protodef_telemetry_2ftelemetry_2eproto, - "telemetry/telemetry.proto", &assign_descriptors_table_telemetry_2ftelemetry_2eproto, 4664, + "telemetry/telemetry.proto", &assign_descriptors_table_telemetry_2ftelemetry_2eproto, 5806, }; void AddDescriptors_telemetry_2ftelemetry_2eproto() { @@ -4244,49 +4523,49 @@ ::google::protobuf::Metadata AttitudeEulerResponse::GetMetadata() const { // =================================================================== -void SubscribeCameraAttitudeQuaternionRequest::InitAsDefaultInstance() { +void SubscribeAttitudeAngularVelocityBodyRequest::InitAsDefaultInstance() { } -class SubscribeCameraAttitudeQuaternionRequest::HasBitSetters { +class SubscribeAttitudeAngularVelocityBodyRequest::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -SubscribeCameraAttitudeQuaternionRequest::SubscribeCameraAttitudeQuaternionRequest() +SubscribeAttitudeAngularVelocityBodyRequest::SubscribeAttitudeAngularVelocityBodyRequest() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) } -SubscribeCameraAttitudeQuaternionRequest::SubscribeCameraAttitudeQuaternionRequest(const SubscribeCameraAttitudeQuaternionRequest& from) +SubscribeAttitudeAngularVelocityBodyRequest::SubscribeAttitudeAngularVelocityBodyRequest(const SubscribeAttitudeAngularVelocityBodyRequest& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) } -void SubscribeCameraAttitudeQuaternionRequest::SharedCtor() { +void SubscribeAttitudeAngularVelocityBodyRequest::SharedCtor() { } -SubscribeCameraAttitudeQuaternionRequest::~SubscribeCameraAttitudeQuaternionRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) +SubscribeAttitudeAngularVelocityBodyRequest::~SubscribeAttitudeAngularVelocityBodyRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) SharedDtor(); } -void SubscribeCameraAttitudeQuaternionRequest::SharedDtor() { +void SubscribeAttitudeAngularVelocityBodyRequest::SharedDtor() { } -void SubscribeCameraAttitudeQuaternionRequest::SetCachedSize(int size) const { +void SubscribeAttitudeAngularVelocityBodyRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -const SubscribeCameraAttitudeQuaternionRequest& SubscribeCameraAttitudeQuaternionRequest::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeCameraAttitudeQuaternionRequest_telemetry_2ftelemetry_2eproto.base); +const SubscribeAttitudeAngularVelocityBodyRequest& SubscribeAttitudeAngularVelocityBodyRequest::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeAttitudeAngularVelocityBodyRequest_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void SubscribeCameraAttitudeQuaternionRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) +void SubscribeAttitudeAngularVelocityBodyRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -4295,9 +4574,9 @@ void SubscribeCameraAttitudeQuaternionRequest::Clear() { } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* SubscribeCameraAttitudeQuaternionRequest::_InternalParse(const char* begin, const char* end, void* object, +const char* SubscribeAttitudeAngularVelocityBodyRequest::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -4323,11 +4602,11 @@ const char* SubscribeCameraAttitudeQuaternionRequest::_InternalParse(const char* return ptr; } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool SubscribeCameraAttitudeQuaternionRequest::MergePartialFromCodedStream( +bool SubscribeAttitudeAngularVelocityBodyRequest::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; @@ -4340,18 +4619,18 @@ bool SubscribeCameraAttitudeQuaternionRequest::MergePartialFromCodedStream( input, tag, _internal_metadata_.mutable_unknown_fields())); } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void SubscribeCameraAttitudeQuaternionRequest::SerializeWithCachedSizes( +void SubscribeAttitudeAngularVelocityBodyRequest::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -4359,12 +4638,12 @@ void SubscribeCameraAttitudeQuaternionRequest::SerializeWithCachedSizes( ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) } -::google::protobuf::uint8* SubscribeCameraAttitudeQuaternionRequest::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* SubscribeAttitudeAngularVelocityBodyRequest::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -4372,12 +4651,12 @@ ::google::protobuf::uint8* SubscribeCameraAttitudeQuaternionRequest::InternalSer target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) return target; } -size_t SubscribeCameraAttitudeQuaternionRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) +size_t SubscribeAttitudeAngularVelocityBodyRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -4394,23 +4673,23 @@ size_t SubscribeCameraAttitudeQuaternionRequest::ByteSizeLong() const { return total_size; } -void SubscribeCameraAttitudeQuaternionRequest::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) +void SubscribeAttitudeAngularVelocityBodyRequest::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) GOOGLE_DCHECK_NE(&from, this); - const SubscribeCameraAttitudeQuaternionRequest* source = - ::google::protobuf::DynamicCastToGenerated( + const SubscribeAttitudeAngularVelocityBodyRequest* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) MergeFrom(*source); } } -void SubscribeCameraAttitudeQuaternionRequest::MergeFrom(const SubscribeCameraAttitudeQuaternionRequest& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) +void SubscribeAttitudeAngularVelocityBodyRequest::MergeFrom(const SubscribeAttitudeAngularVelocityBodyRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; @@ -4418,34 +4697,34 @@ void SubscribeCameraAttitudeQuaternionRequest::MergeFrom(const SubscribeCameraAt } -void SubscribeCameraAttitudeQuaternionRequest::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) +void SubscribeAttitudeAngularVelocityBodyRequest::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) if (&from == this) return; Clear(); MergeFrom(from); } -void SubscribeCameraAttitudeQuaternionRequest::CopyFrom(const SubscribeCameraAttitudeQuaternionRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) +void SubscribeAttitudeAngularVelocityBodyRequest::CopyFrom(const SubscribeAttitudeAngularVelocityBodyRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool SubscribeCameraAttitudeQuaternionRequest::IsInitialized() const { +bool SubscribeAttitudeAngularVelocityBodyRequest::IsInitialized() const { return true; } -void SubscribeCameraAttitudeQuaternionRequest::Swap(SubscribeCameraAttitudeQuaternionRequest* other) { +void SubscribeAttitudeAngularVelocityBodyRequest::Swap(SubscribeAttitudeAngularVelocityBodyRequest* other) { if (other == this) return; InternalSwap(other); } -void SubscribeCameraAttitudeQuaternionRequest::InternalSwap(SubscribeCameraAttitudeQuaternionRequest* other) { +void SubscribeAttitudeAngularVelocityBodyRequest::InternalSwap(SubscribeAttitudeAngularVelocityBodyRequest* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); } -::google::protobuf::Metadata SubscribeCameraAttitudeQuaternionRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeAttitudeAngularVelocityBodyRequest::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -4453,81 +4732,81 @@ ::google::protobuf::Metadata SubscribeCameraAttitudeQuaternionRequest::GetMetada // =================================================================== -void CameraAttitudeQuaternionResponse::InitAsDefaultInstance() { - ::mavsdk::rpc::telemetry::_CameraAttitudeQuaternionResponse_default_instance_._instance.get_mutable()->attitude_quaternion_ = const_cast< ::mavsdk::rpc::telemetry::Quaternion*>( - ::mavsdk::rpc::telemetry::Quaternion::internal_default_instance()); +void AttitudeAngularVelocityBodyResponse::InitAsDefaultInstance() { + ::mavsdk::rpc::telemetry::_AttitudeAngularVelocityBodyResponse_default_instance_._instance.get_mutable()->attitude_angular_velocity_body_ = const_cast< ::mavsdk::rpc::telemetry::AngularVelocityBody*>( + ::mavsdk::rpc::telemetry::AngularVelocityBody::internal_default_instance()); } -class CameraAttitudeQuaternionResponse::HasBitSetters { +class AttitudeAngularVelocityBodyResponse::HasBitSetters { public: - static const ::mavsdk::rpc::telemetry::Quaternion& attitude_quaternion(const CameraAttitudeQuaternionResponse* msg); + static const ::mavsdk::rpc::telemetry::AngularVelocityBody& attitude_angular_velocity_body(const AttitudeAngularVelocityBodyResponse* msg); }; -const ::mavsdk::rpc::telemetry::Quaternion& -CameraAttitudeQuaternionResponse::HasBitSetters::attitude_quaternion(const CameraAttitudeQuaternionResponse* msg) { - return *msg->attitude_quaternion_; +const ::mavsdk::rpc::telemetry::AngularVelocityBody& +AttitudeAngularVelocityBodyResponse::HasBitSetters::attitude_angular_velocity_body(const AttitudeAngularVelocityBodyResponse* msg) { + return *msg->attitude_angular_velocity_body_; } #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int CameraAttitudeQuaternionResponse::kAttitudeQuaternionFieldNumber; +const int AttitudeAngularVelocityBodyResponse::kAttitudeAngularVelocityBodyFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -CameraAttitudeQuaternionResponse::CameraAttitudeQuaternionResponse() +AttitudeAngularVelocityBodyResponse::AttitudeAngularVelocityBodyResponse() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) } -CameraAttitudeQuaternionResponse::CameraAttitudeQuaternionResponse(const CameraAttitudeQuaternionResponse& from) +AttitudeAngularVelocityBodyResponse::AttitudeAngularVelocityBodyResponse(const AttitudeAngularVelocityBodyResponse& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - if (from.has_attitude_quaternion()) { - attitude_quaternion_ = new ::mavsdk::rpc::telemetry::Quaternion(*from.attitude_quaternion_); + if (from.has_attitude_angular_velocity_body()) { + attitude_angular_velocity_body_ = new ::mavsdk::rpc::telemetry::AngularVelocityBody(*from.attitude_angular_velocity_body_); } else { - attitude_quaternion_ = nullptr; + attitude_angular_velocity_body_ = nullptr; } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) } -void CameraAttitudeQuaternionResponse::SharedCtor() { +void AttitudeAngularVelocityBodyResponse::SharedCtor() { ::google::protobuf::internal::InitSCC( - &scc_info_CameraAttitudeQuaternionResponse_telemetry_2ftelemetry_2eproto.base); - attitude_quaternion_ = nullptr; + &scc_info_AttitudeAngularVelocityBodyResponse_telemetry_2ftelemetry_2eproto.base); + attitude_angular_velocity_body_ = nullptr; } -CameraAttitudeQuaternionResponse::~CameraAttitudeQuaternionResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) +AttitudeAngularVelocityBodyResponse::~AttitudeAngularVelocityBodyResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) SharedDtor(); } -void CameraAttitudeQuaternionResponse::SharedDtor() { - if (this != internal_default_instance()) delete attitude_quaternion_; +void AttitudeAngularVelocityBodyResponse::SharedDtor() { + if (this != internal_default_instance()) delete attitude_angular_velocity_body_; } -void CameraAttitudeQuaternionResponse::SetCachedSize(int size) const { +void AttitudeAngularVelocityBodyResponse::SetCachedSize(int size) const { _cached_size_.Set(size); } -const CameraAttitudeQuaternionResponse& CameraAttitudeQuaternionResponse::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_CameraAttitudeQuaternionResponse_telemetry_2ftelemetry_2eproto.base); +const AttitudeAngularVelocityBodyResponse& AttitudeAngularVelocityBodyResponse::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_AttitudeAngularVelocityBodyResponse_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void CameraAttitudeQuaternionResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) +void AttitudeAngularVelocityBodyResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - if (GetArenaNoVirtual() == nullptr && attitude_quaternion_ != nullptr) { - delete attitude_quaternion_; + if (GetArenaNoVirtual() == nullptr && attitude_angular_velocity_body_ != nullptr) { + delete attitude_angular_velocity_body_; } - attitude_quaternion_ = nullptr; + attitude_angular_velocity_body_ = nullptr; _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* CameraAttitudeQuaternionResponse::_InternalParse(const char* begin, const char* end, void* object, +const char* AttitudeAngularVelocityBodyResponse::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -4537,13 +4816,13 @@ const char* CameraAttitudeQuaternionResponse::_InternalParse(const char* begin, ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; + // .mavsdk.rpc.telemetry.AngularVelocityBody attitude_angular_velocity_body = 1; case 1: { if (static_cast<::google::protobuf::uint8>(tag) != 10) goto handle_unusual; ptr = ::google::protobuf::io::ReadSize(ptr, &size); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - parser_till_end = ::mavsdk::rpc::telemetry::Quaternion::_InternalParse; - object = msg->mutable_attitude_quaternion(); + parser_till_end = ::mavsdk::rpc::telemetry::AngularVelocityBody::_InternalParse; + object = msg->mutable_attitude_angular_velocity_body(); if (size > end - ptr) goto len_delim_till_end; ptr += size; GOOGLE_PROTOBUF_PARSER_ASSERT(ctx->ParseExactRange( @@ -4570,21 +4849,21 @@ const char* CameraAttitudeQuaternionResponse::_InternalParse(const char* begin, {parser_till_end, object}, size); } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool CameraAttitudeQuaternionResponse::MergePartialFromCodedStream( +bool AttitudeAngularVelocityBodyResponse::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; + // .mavsdk.rpc.telemetry.AngularVelocityBody attitude_angular_velocity_body = 1; case 1: { if (static_cast< ::google::protobuf::uint8>(tag) == (10 & 0xFF)) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( - input, mutable_attitude_quaternion())); + input, mutable_attitude_angular_velocity_body())); } else { goto handle_unusual; } @@ -4603,57 +4882,57 @@ bool CameraAttitudeQuaternionResponse::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void CameraAttitudeQuaternionResponse::SerializeWithCachedSizes( +void AttitudeAngularVelocityBodyResponse::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; - if (this->has_attitude_quaternion()) { + // .mavsdk.rpc.telemetry.AngularVelocityBody attitude_angular_velocity_body = 1; + if (this->has_attitude_angular_velocity_body()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, HasBitSetters::attitude_quaternion(this), output); + 1, HasBitSetters::attitude_angular_velocity_body(this), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) } -::google::protobuf::uint8* CameraAttitudeQuaternionResponse::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* AttitudeAngularVelocityBodyResponse::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; - if (this->has_attitude_quaternion()) { + // .mavsdk.rpc.telemetry.AngularVelocityBody attitude_angular_velocity_body = 1; + if (this->has_attitude_angular_velocity_body()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageToArray( - 1, HasBitSetters::attitude_quaternion(this), target); + 1, HasBitSetters::attitude_angular_velocity_body(this), target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) return target; } -size_t CameraAttitudeQuaternionResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) +size_t AttitudeAngularVelocityBodyResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -4665,11 +4944,11 @@ size_t CameraAttitudeQuaternionResponse::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; - if (this->has_attitude_quaternion()) { + // .mavsdk.rpc.telemetry.AngularVelocityBody attitude_angular_velocity_body = 1; + if (this->has_attitude_angular_velocity_body()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSize( - *attitude_quaternion_); + *attitude_angular_velocity_body_); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -4677,62 +4956,62 @@ size_t CameraAttitudeQuaternionResponse::ByteSizeLong() const { return total_size; } -void CameraAttitudeQuaternionResponse::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) +void AttitudeAngularVelocityBodyResponse::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) GOOGLE_DCHECK_NE(&from, this); - const CameraAttitudeQuaternionResponse* source = - ::google::protobuf::DynamicCastToGenerated( + const AttitudeAngularVelocityBodyResponse* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) MergeFrom(*source); } } -void CameraAttitudeQuaternionResponse::MergeFrom(const CameraAttitudeQuaternionResponse& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) +void AttitudeAngularVelocityBodyResponse::MergeFrom(const AttitudeAngularVelocityBodyResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.has_attitude_quaternion()) { - mutable_attitude_quaternion()->::mavsdk::rpc::telemetry::Quaternion::MergeFrom(from.attitude_quaternion()); + if (from.has_attitude_angular_velocity_body()) { + mutable_attitude_angular_velocity_body()->::mavsdk::rpc::telemetry::AngularVelocityBody::MergeFrom(from.attitude_angular_velocity_body()); } } -void CameraAttitudeQuaternionResponse::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) +void AttitudeAngularVelocityBodyResponse::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void CameraAttitudeQuaternionResponse::CopyFrom(const CameraAttitudeQuaternionResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) +void AttitudeAngularVelocityBodyResponse::CopyFrom(const AttitudeAngularVelocityBodyResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool CameraAttitudeQuaternionResponse::IsInitialized() const { +bool AttitudeAngularVelocityBodyResponse::IsInitialized() const { return true; } -void CameraAttitudeQuaternionResponse::Swap(CameraAttitudeQuaternionResponse* other) { +void AttitudeAngularVelocityBodyResponse::Swap(AttitudeAngularVelocityBodyResponse* other) { if (other == this) return; InternalSwap(other); } -void CameraAttitudeQuaternionResponse::InternalSwap(CameraAttitudeQuaternionResponse* other) { +void AttitudeAngularVelocityBodyResponse::InternalSwap(AttitudeAngularVelocityBodyResponse* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(attitude_quaternion_, other->attitude_quaternion_); + swap(attitude_angular_velocity_body_, other->attitude_angular_velocity_body_); } -::google::protobuf::Metadata CameraAttitudeQuaternionResponse::GetMetadata() const { +::google::protobuf::Metadata AttitudeAngularVelocityBodyResponse::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -4740,49 +5019,49 @@ ::google::protobuf::Metadata CameraAttitudeQuaternionResponse::GetMetadata() con // =================================================================== -void SubscribeCameraAttitudeEulerRequest::InitAsDefaultInstance() { +void SubscribeCameraAttitudeQuaternionRequest::InitAsDefaultInstance() { } -class SubscribeCameraAttitudeEulerRequest::HasBitSetters { +class SubscribeCameraAttitudeQuaternionRequest::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -SubscribeCameraAttitudeEulerRequest::SubscribeCameraAttitudeEulerRequest() +SubscribeCameraAttitudeQuaternionRequest::SubscribeCameraAttitudeQuaternionRequest() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) } -SubscribeCameraAttitudeEulerRequest::SubscribeCameraAttitudeEulerRequest(const SubscribeCameraAttitudeEulerRequest& from) +SubscribeCameraAttitudeQuaternionRequest::SubscribeCameraAttitudeQuaternionRequest(const SubscribeCameraAttitudeQuaternionRequest& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) } -void SubscribeCameraAttitudeEulerRequest::SharedCtor() { +void SubscribeCameraAttitudeQuaternionRequest::SharedCtor() { } -SubscribeCameraAttitudeEulerRequest::~SubscribeCameraAttitudeEulerRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) +SubscribeCameraAttitudeQuaternionRequest::~SubscribeCameraAttitudeQuaternionRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) SharedDtor(); } -void SubscribeCameraAttitudeEulerRequest::SharedDtor() { +void SubscribeCameraAttitudeQuaternionRequest::SharedDtor() { } -void SubscribeCameraAttitudeEulerRequest::SetCachedSize(int size) const { +void SubscribeCameraAttitudeQuaternionRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -const SubscribeCameraAttitudeEulerRequest& SubscribeCameraAttitudeEulerRequest::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeCameraAttitudeEulerRequest_telemetry_2ftelemetry_2eproto.base); +const SubscribeCameraAttitudeQuaternionRequest& SubscribeCameraAttitudeQuaternionRequest::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeCameraAttitudeQuaternionRequest_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void SubscribeCameraAttitudeEulerRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) +void SubscribeCameraAttitudeQuaternionRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -4791,9 +5070,9 @@ void SubscribeCameraAttitudeEulerRequest::Clear() { } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* SubscribeCameraAttitudeEulerRequest::_InternalParse(const char* begin, const char* end, void* object, +const char* SubscribeCameraAttitudeQuaternionRequest::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -4819,11 +5098,11 @@ const char* SubscribeCameraAttitudeEulerRequest::_InternalParse(const char* begi return ptr; } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool SubscribeCameraAttitudeEulerRequest::MergePartialFromCodedStream( +bool SubscribeCameraAttitudeQuaternionRequest::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; @@ -4836,18 +5115,18 @@ bool SubscribeCameraAttitudeEulerRequest::MergePartialFromCodedStream( input, tag, _internal_metadata_.mutable_unknown_fields())); } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void SubscribeCameraAttitudeEulerRequest::SerializeWithCachedSizes( +void SubscribeCameraAttitudeQuaternionRequest::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -4855,12 +5134,12 @@ void SubscribeCameraAttitudeEulerRequest::SerializeWithCachedSizes( ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) } -::google::protobuf::uint8* SubscribeCameraAttitudeEulerRequest::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* SubscribeCameraAttitudeQuaternionRequest::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -4868,12 +5147,12 @@ ::google::protobuf::uint8* SubscribeCameraAttitudeEulerRequest::InternalSerializ target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) return target; } -size_t SubscribeCameraAttitudeEulerRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) +size_t SubscribeCameraAttitudeQuaternionRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -4890,23 +5169,23 @@ size_t SubscribeCameraAttitudeEulerRequest::ByteSizeLong() const { return total_size; } -void SubscribeCameraAttitudeEulerRequest::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) +void SubscribeCameraAttitudeQuaternionRequest::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) GOOGLE_DCHECK_NE(&from, this); - const SubscribeCameraAttitudeEulerRequest* source = - ::google::protobuf::DynamicCastToGenerated( + const SubscribeCameraAttitudeQuaternionRequest* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) MergeFrom(*source); } } -void SubscribeCameraAttitudeEulerRequest::MergeFrom(const SubscribeCameraAttitudeEulerRequest& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) +void SubscribeCameraAttitudeQuaternionRequest::MergeFrom(const SubscribeCameraAttitudeQuaternionRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; @@ -4914,34 +5193,34 @@ void SubscribeCameraAttitudeEulerRequest::MergeFrom(const SubscribeCameraAttitud } -void SubscribeCameraAttitudeEulerRequest::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) +void SubscribeCameraAttitudeQuaternionRequest::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) if (&from == this) return; Clear(); MergeFrom(from); } -void SubscribeCameraAttitudeEulerRequest::CopyFrom(const SubscribeCameraAttitudeEulerRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) +void SubscribeCameraAttitudeQuaternionRequest::CopyFrom(const SubscribeCameraAttitudeQuaternionRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool SubscribeCameraAttitudeEulerRequest::IsInitialized() const { +bool SubscribeCameraAttitudeQuaternionRequest::IsInitialized() const { return true; } -void SubscribeCameraAttitudeEulerRequest::Swap(SubscribeCameraAttitudeEulerRequest* other) { +void SubscribeCameraAttitudeQuaternionRequest::Swap(SubscribeCameraAttitudeQuaternionRequest* other) { if (other == this) return; InternalSwap(other); } -void SubscribeCameraAttitudeEulerRequest::InternalSwap(SubscribeCameraAttitudeEulerRequest* other) { +void SubscribeCameraAttitudeQuaternionRequest::InternalSwap(SubscribeCameraAttitudeQuaternionRequest* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); } -::google::protobuf::Metadata SubscribeCameraAttitudeEulerRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeCameraAttitudeQuaternionRequest::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -4949,81 +5228,81 @@ ::google::protobuf::Metadata SubscribeCameraAttitudeEulerRequest::GetMetadata() // =================================================================== -void CameraAttitudeEulerResponse::InitAsDefaultInstance() { - ::mavsdk::rpc::telemetry::_CameraAttitudeEulerResponse_default_instance_._instance.get_mutable()->attitude_euler_ = const_cast< ::mavsdk::rpc::telemetry::EulerAngle*>( - ::mavsdk::rpc::telemetry::EulerAngle::internal_default_instance()); +void CameraAttitudeQuaternionResponse::InitAsDefaultInstance() { + ::mavsdk::rpc::telemetry::_CameraAttitudeQuaternionResponse_default_instance_._instance.get_mutable()->attitude_quaternion_ = const_cast< ::mavsdk::rpc::telemetry::Quaternion*>( + ::mavsdk::rpc::telemetry::Quaternion::internal_default_instance()); } -class CameraAttitudeEulerResponse::HasBitSetters { +class CameraAttitudeQuaternionResponse::HasBitSetters { public: - static const ::mavsdk::rpc::telemetry::EulerAngle& attitude_euler(const CameraAttitudeEulerResponse* msg); + static const ::mavsdk::rpc::telemetry::Quaternion& attitude_quaternion(const CameraAttitudeQuaternionResponse* msg); }; -const ::mavsdk::rpc::telemetry::EulerAngle& -CameraAttitudeEulerResponse::HasBitSetters::attitude_euler(const CameraAttitudeEulerResponse* msg) { - return *msg->attitude_euler_; +const ::mavsdk::rpc::telemetry::Quaternion& +CameraAttitudeQuaternionResponse::HasBitSetters::attitude_quaternion(const CameraAttitudeQuaternionResponse* msg) { + return *msg->attitude_quaternion_; } #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int CameraAttitudeEulerResponse::kAttitudeEulerFieldNumber; +const int CameraAttitudeQuaternionResponse::kAttitudeQuaternionFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -CameraAttitudeEulerResponse::CameraAttitudeEulerResponse() +CameraAttitudeQuaternionResponse::CameraAttitudeQuaternionResponse() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) } -CameraAttitudeEulerResponse::CameraAttitudeEulerResponse(const CameraAttitudeEulerResponse& from) +CameraAttitudeQuaternionResponse::CameraAttitudeQuaternionResponse(const CameraAttitudeQuaternionResponse& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - if (from.has_attitude_euler()) { - attitude_euler_ = new ::mavsdk::rpc::telemetry::EulerAngle(*from.attitude_euler_); + if (from.has_attitude_quaternion()) { + attitude_quaternion_ = new ::mavsdk::rpc::telemetry::Quaternion(*from.attitude_quaternion_); } else { - attitude_euler_ = nullptr; + attitude_quaternion_ = nullptr; } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) } -void CameraAttitudeEulerResponse::SharedCtor() { +void CameraAttitudeQuaternionResponse::SharedCtor() { ::google::protobuf::internal::InitSCC( - &scc_info_CameraAttitudeEulerResponse_telemetry_2ftelemetry_2eproto.base); - attitude_euler_ = nullptr; + &scc_info_CameraAttitudeQuaternionResponse_telemetry_2ftelemetry_2eproto.base); + attitude_quaternion_ = nullptr; } -CameraAttitudeEulerResponse::~CameraAttitudeEulerResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) +CameraAttitudeQuaternionResponse::~CameraAttitudeQuaternionResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) SharedDtor(); } -void CameraAttitudeEulerResponse::SharedDtor() { - if (this != internal_default_instance()) delete attitude_euler_; +void CameraAttitudeQuaternionResponse::SharedDtor() { + if (this != internal_default_instance()) delete attitude_quaternion_; } -void CameraAttitudeEulerResponse::SetCachedSize(int size) const { +void CameraAttitudeQuaternionResponse::SetCachedSize(int size) const { _cached_size_.Set(size); } -const CameraAttitudeEulerResponse& CameraAttitudeEulerResponse::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_CameraAttitudeEulerResponse_telemetry_2ftelemetry_2eproto.base); +const CameraAttitudeQuaternionResponse& CameraAttitudeQuaternionResponse::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_CameraAttitudeQuaternionResponse_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void CameraAttitudeEulerResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) +void CameraAttitudeQuaternionResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - if (GetArenaNoVirtual() == nullptr && attitude_euler_ != nullptr) { - delete attitude_euler_; + if (GetArenaNoVirtual() == nullptr && attitude_quaternion_ != nullptr) { + delete attitude_quaternion_; } - attitude_euler_ = nullptr; + attitude_quaternion_ = nullptr; _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* CameraAttitudeEulerResponse::_InternalParse(const char* begin, const char* end, void* object, +const char* CameraAttitudeQuaternionResponse::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -5033,13 +5312,13 @@ const char* CameraAttitudeEulerResponse::_InternalParse(const char* begin, const ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; + // .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; case 1: { if (static_cast<::google::protobuf::uint8>(tag) != 10) goto handle_unusual; ptr = ::google::protobuf::io::ReadSize(ptr, &size); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - parser_till_end = ::mavsdk::rpc::telemetry::EulerAngle::_InternalParse; - object = msg->mutable_attitude_euler(); + parser_till_end = ::mavsdk::rpc::telemetry::Quaternion::_InternalParse; + object = msg->mutable_attitude_quaternion(); if (size > end - ptr) goto len_delim_till_end; ptr += size; GOOGLE_PROTOBUF_PARSER_ASSERT(ctx->ParseExactRange( @@ -5066,21 +5345,21 @@ const char* CameraAttitudeEulerResponse::_InternalParse(const char* begin, const {parser_till_end, object}, size); } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool CameraAttitudeEulerResponse::MergePartialFromCodedStream( +bool CameraAttitudeQuaternionResponse::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; + // .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; case 1: { if (static_cast< ::google::protobuf::uint8>(tag) == (10 & 0xFF)) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( - input, mutable_attitude_euler())); + input, mutable_attitude_quaternion())); } else { goto handle_unusual; } @@ -5099,57 +5378,57 @@ bool CameraAttitudeEulerResponse::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void CameraAttitudeEulerResponse::SerializeWithCachedSizes( +void CameraAttitudeQuaternionResponse::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; - if (this->has_attitude_euler()) { + // .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; + if (this->has_attitude_quaternion()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, HasBitSetters::attitude_euler(this), output); + 1, HasBitSetters::attitude_quaternion(this), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) } -::google::protobuf::uint8* CameraAttitudeEulerResponse::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* CameraAttitudeQuaternionResponse::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; - if (this->has_attitude_euler()) { + // .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; + if (this->has_attitude_quaternion()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageToArray( - 1, HasBitSetters::attitude_euler(this), target); + 1, HasBitSetters::attitude_quaternion(this), target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) return target; } -size_t CameraAttitudeEulerResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) +size_t CameraAttitudeQuaternionResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -5161,11 +5440,11 @@ size_t CameraAttitudeEulerResponse::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; - if (this->has_attitude_euler()) { + // .mavsdk.rpc.telemetry.Quaternion attitude_quaternion = 1; + if (this->has_attitude_quaternion()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSize( - *attitude_euler_); + *attitude_quaternion_); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -5173,62 +5452,62 @@ size_t CameraAttitudeEulerResponse::ByteSizeLong() const { return total_size; } -void CameraAttitudeEulerResponse::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) +void CameraAttitudeQuaternionResponse::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) GOOGLE_DCHECK_NE(&from, this); - const CameraAttitudeEulerResponse* source = - ::google::protobuf::DynamicCastToGenerated( + const CameraAttitudeQuaternionResponse* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) MergeFrom(*source); } } -void CameraAttitudeEulerResponse::MergeFrom(const CameraAttitudeEulerResponse& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) +void CameraAttitudeQuaternionResponse::MergeFrom(const CameraAttitudeQuaternionResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.has_attitude_euler()) { - mutable_attitude_euler()->::mavsdk::rpc::telemetry::EulerAngle::MergeFrom(from.attitude_euler()); + if (from.has_attitude_quaternion()) { + mutable_attitude_quaternion()->::mavsdk::rpc::telemetry::Quaternion::MergeFrom(from.attitude_quaternion()); } } -void CameraAttitudeEulerResponse::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) +void CameraAttitudeQuaternionResponse::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void CameraAttitudeEulerResponse::CopyFrom(const CameraAttitudeEulerResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) +void CameraAttitudeQuaternionResponse::CopyFrom(const CameraAttitudeQuaternionResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.CameraAttitudeQuaternionResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool CameraAttitudeEulerResponse::IsInitialized() const { +bool CameraAttitudeQuaternionResponse::IsInitialized() const { return true; } -void CameraAttitudeEulerResponse::Swap(CameraAttitudeEulerResponse* other) { +void CameraAttitudeQuaternionResponse::Swap(CameraAttitudeQuaternionResponse* other) { if (other == this) return; InternalSwap(other); } -void CameraAttitudeEulerResponse::InternalSwap(CameraAttitudeEulerResponse* other) { +void CameraAttitudeQuaternionResponse::InternalSwap(CameraAttitudeQuaternionResponse* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(attitude_euler_, other->attitude_euler_); + swap(attitude_quaternion_, other->attitude_quaternion_); } -::google::protobuf::Metadata CameraAttitudeEulerResponse::GetMetadata() const { +::google::protobuf::Metadata CameraAttitudeQuaternionResponse::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -5236,49 +5515,49 @@ ::google::protobuf::Metadata CameraAttitudeEulerResponse::GetMetadata() const { // =================================================================== -void SubscribeGroundSpeedNedRequest::InitAsDefaultInstance() { +void SubscribeCameraAttitudeEulerRequest::InitAsDefaultInstance() { } -class SubscribeGroundSpeedNedRequest::HasBitSetters { +class SubscribeCameraAttitudeEulerRequest::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -SubscribeGroundSpeedNedRequest::SubscribeGroundSpeedNedRequest() +SubscribeCameraAttitudeEulerRequest::SubscribeCameraAttitudeEulerRequest() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) } -SubscribeGroundSpeedNedRequest::SubscribeGroundSpeedNedRequest(const SubscribeGroundSpeedNedRequest& from) +SubscribeCameraAttitudeEulerRequest::SubscribeCameraAttitudeEulerRequest(const SubscribeCameraAttitudeEulerRequest& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) } -void SubscribeGroundSpeedNedRequest::SharedCtor() { +void SubscribeCameraAttitudeEulerRequest::SharedCtor() { } -SubscribeGroundSpeedNedRequest::~SubscribeGroundSpeedNedRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) +SubscribeCameraAttitudeEulerRequest::~SubscribeCameraAttitudeEulerRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) SharedDtor(); } -void SubscribeGroundSpeedNedRequest::SharedDtor() { +void SubscribeCameraAttitudeEulerRequest::SharedDtor() { } -void SubscribeGroundSpeedNedRequest::SetCachedSize(int size) const { +void SubscribeCameraAttitudeEulerRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -const SubscribeGroundSpeedNedRequest& SubscribeGroundSpeedNedRequest::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeGroundSpeedNedRequest_telemetry_2ftelemetry_2eproto.base); - return *internal_default_instance(); +const SubscribeCameraAttitudeEulerRequest& SubscribeCameraAttitudeEulerRequest::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeCameraAttitudeEulerRequest_telemetry_2ftelemetry_2eproto.base); + return *internal_default_instance(); } -void SubscribeGroundSpeedNedRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) +void SubscribeCameraAttitudeEulerRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -5287,9 +5566,9 @@ void SubscribeGroundSpeedNedRequest::Clear() { } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* SubscribeGroundSpeedNedRequest::_InternalParse(const char* begin, const char* end, void* object, +const char* SubscribeCameraAttitudeEulerRequest::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -5315,11 +5594,11 @@ const char* SubscribeGroundSpeedNedRequest::_InternalParse(const char* begin, co return ptr; } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool SubscribeGroundSpeedNedRequest::MergePartialFromCodedStream( +bool SubscribeCameraAttitudeEulerRequest::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; @@ -5332,18 +5611,18 @@ bool SubscribeGroundSpeedNedRequest::MergePartialFromCodedStream( input, tag, _internal_metadata_.mutable_unknown_fields())); } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void SubscribeGroundSpeedNedRequest::SerializeWithCachedSizes( +void SubscribeCameraAttitudeEulerRequest::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -5351,12 +5630,12 @@ void SubscribeGroundSpeedNedRequest::SerializeWithCachedSizes( ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) } -::google::protobuf::uint8* SubscribeGroundSpeedNedRequest::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* SubscribeCameraAttitudeEulerRequest::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -5364,12 +5643,12 @@ ::google::protobuf::uint8* SubscribeGroundSpeedNedRequest::InternalSerializeWith target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) return target; } -size_t SubscribeGroundSpeedNedRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) +size_t SubscribeCameraAttitudeEulerRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -5386,23 +5665,23 @@ size_t SubscribeGroundSpeedNedRequest::ByteSizeLong() const { return total_size; } -void SubscribeGroundSpeedNedRequest::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) +void SubscribeCameraAttitudeEulerRequest::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) GOOGLE_DCHECK_NE(&from, this); - const SubscribeGroundSpeedNedRequest* source = - ::google::protobuf::DynamicCastToGenerated( + const SubscribeCameraAttitudeEulerRequest* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) MergeFrom(*source); } } -void SubscribeGroundSpeedNedRequest::MergeFrom(const SubscribeGroundSpeedNedRequest& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) +void SubscribeCameraAttitudeEulerRequest::MergeFrom(const SubscribeCameraAttitudeEulerRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; @@ -5410,34 +5689,34 @@ void SubscribeGroundSpeedNedRequest::MergeFrom(const SubscribeGroundSpeedNedRequ } -void SubscribeGroundSpeedNedRequest::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) +void SubscribeCameraAttitudeEulerRequest::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) if (&from == this) return; Clear(); MergeFrom(from); } -void SubscribeGroundSpeedNedRequest::CopyFrom(const SubscribeGroundSpeedNedRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) +void SubscribeCameraAttitudeEulerRequest::CopyFrom(const SubscribeCameraAttitudeEulerRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeCameraAttitudeEulerRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool SubscribeGroundSpeedNedRequest::IsInitialized() const { +bool SubscribeCameraAttitudeEulerRequest::IsInitialized() const { return true; } -void SubscribeGroundSpeedNedRequest::Swap(SubscribeGroundSpeedNedRequest* other) { +void SubscribeCameraAttitudeEulerRequest::Swap(SubscribeCameraAttitudeEulerRequest* other) { if (other == this) return; InternalSwap(other); } -void SubscribeGroundSpeedNedRequest::InternalSwap(SubscribeGroundSpeedNedRequest* other) { +void SubscribeCameraAttitudeEulerRequest::InternalSwap(SubscribeCameraAttitudeEulerRequest* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); } -::google::protobuf::Metadata SubscribeGroundSpeedNedRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeCameraAttitudeEulerRequest::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -5445,81 +5724,81 @@ ::google::protobuf::Metadata SubscribeGroundSpeedNedRequest::GetMetadata() const // =================================================================== -void GroundSpeedNedResponse::InitAsDefaultInstance() { - ::mavsdk::rpc::telemetry::_GroundSpeedNedResponse_default_instance_._instance.get_mutable()->ground_speed_ned_ = const_cast< ::mavsdk::rpc::telemetry::SpeedNed*>( - ::mavsdk::rpc::telemetry::SpeedNed::internal_default_instance()); +void CameraAttitudeEulerResponse::InitAsDefaultInstance() { + ::mavsdk::rpc::telemetry::_CameraAttitudeEulerResponse_default_instance_._instance.get_mutable()->attitude_euler_ = const_cast< ::mavsdk::rpc::telemetry::EulerAngle*>( + ::mavsdk::rpc::telemetry::EulerAngle::internal_default_instance()); } -class GroundSpeedNedResponse::HasBitSetters { +class CameraAttitudeEulerResponse::HasBitSetters { public: - static const ::mavsdk::rpc::telemetry::SpeedNed& ground_speed_ned(const GroundSpeedNedResponse* msg); + static const ::mavsdk::rpc::telemetry::EulerAngle& attitude_euler(const CameraAttitudeEulerResponse* msg); }; -const ::mavsdk::rpc::telemetry::SpeedNed& -GroundSpeedNedResponse::HasBitSetters::ground_speed_ned(const GroundSpeedNedResponse* msg) { - return *msg->ground_speed_ned_; +const ::mavsdk::rpc::telemetry::EulerAngle& +CameraAttitudeEulerResponse::HasBitSetters::attitude_euler(const CameraAttitudeEulerResponse* msg) { + return *msg->attitude_euler_; } #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int GroundSpeedNedResponse::kGroundSpeedNedFieldNumber; +const int CameraAttitudeEulerResponse::kAttitudeEulerFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -GroundSpeedNedResponse::GroundSpeedNedResponse() +CameraAttitudeEulerResponse::CameraAttitudeEulerResponse() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.GroundSpeedNedResponse) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) } -GroundSpeedNedResponse::GroundSpeedNedResponse(const GroundSpeedNedResponse& from) +CameraAttitudeEulerResponse::CameraAttitudeEulerResponse(const CameraAttitudeEulerResponse& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - if (from.has_ground_speed_ned()) { - ground_speed_ned_ = new ::mavsdk::rpc::telemetry::SpeedNed(*from.ground_speed_ned_); + if (from.has_attitude_euler()) { + attitude_euler_ = new ::mavsdk::rpc::telemetry::EulerAngle(*from.attitude_euler_); } else { - ground_speed_ned_ = nullptr; + attitude_euler_ = nullptr; } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.GroundSpeedNedResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) } -void GroundSpeedNedResponse::SharedCtor() { +void CameraAttitudeEulerResponse::SharedCtor() { ::google::protobuf::internal::InitSCC( - &scc_info_GroundSpeedNedResponse_telemetry_2ftelemetry_2eproto.base); - ground_speed_ned_ = nullptr; + &scc_info_CameraAttitudeEulerResponse_telemetry_2ftelemetry_2eproto.base); + attitude_euler_ = nullptr; } -GroundSpeedNedResponse::~GroundSpeedNedResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.GroundSpeedNedResponse) +CameraAttitudeEulerResponse::~CameraAttitudeEulerResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) SharedDtor(); } -void GroundSpeedNedResponse::SharedDtor() { - if (this != internal_default_instance()) delete ground_speed_ned_; +void CameraAttitudeEulerResponse::SharedDtor() { + if (this != internal_default_instance()) delete attitude_euler_; } -void GroundSpeedNedResponse::SetCachedSize(int size) const { +void CameraAttitudeEulerResponse::SetCachedSize(int size) const { _cached_size_.Set(size); } -const GroundSpeedNedResponse& GroundSpeedNedResponse::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_GroundSpeedNedResponse_telemetry_2ftelemetry_2eproto.base); +const CameraAttitudeEulerResponse& CameraAttitudeEulerResponse::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_CameraAttitudeEulerResponse_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void GroundSpeedNedResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) +void CameraAttitudeEulerResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - if (GetArenaNoVirtual() == nullptr && ground_speed_ned_ != nullptr) { - delete ground_speed_ned_; + if (GetArenaNoVirtual() == nullptr && attitude_euler_ != nullptr) { + delete attitude_euler_; } - ground_speed_ned_ = nullptr; + attitude_euler_ = nullptr; _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* GroundSpeedNedResponse::_InternalParse(const char* begin, const char* end, void* object, +const char* CameraAttitudeEulerResponse::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -5529,13 +5808,13 @@ const char* GroundSpeedNedResponse::_InternalParse(const char* begin, const char ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // .mavsdk.rpc.telemetry.SpeedNed ground_speed_ned = 1; + // .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; case 1: { if (static_cast<::google::protobuf::uint8>(tag) != 10) goto handle_unusual; ptr = ::google::protobuf::io::ReadSize(ptr, &size); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - parser_till_end = ::mavsdk::rpc::telemetry::SpeedNed::_InternalParse; - object = msg->mutable_ground_speed_ned(); + parser_till_end = ::mavsdk::rpc::telemetry::EulerAngle::_InternalParse; + object = msg->mutable_attitude_euler(); if (size > end - ptr) goto len_delim_till_end; ptr += size; GOOGLE_PROTOBUF_PARSER_ASSERT(ctx->ParseExactRange( @@ -5562,21 +5841,21 @@ const char* GroundSpeedNedResponse::_InternalParse(const char* begin, const char {parser_till_end, object}, size); } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool GroundSpeedNedResponse::MergePartialFromCodedStream( +bool CameraAttitudeEulerResponse::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // .mavsdk.rpc.telemetry.SpeedNed ground_speed_ned = 1; + // .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; case 1: { if (static_cast< ::google::protobuf::uint8>(tag) == (10 & 0xFF)) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( - input, mutable_ground_speed_ned())); + input, mutable_attitude_euler())); } else { goto handle_unusual; } @@ -5595,57 +5874,57 @@ bool GroundSpeedNedResponse::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.GroundSpeedNedResponse) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.GroundSpeedNedResponse) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void GroundSpeedNedResponse::SerializeWithCachedSizes( +void CameraAttitudeEulerResponse::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.SpeedNed ground_speed_ned = 1; - if (this->has_ground_speed_ned()) { + // .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; + if (this->has_attitude_euler()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, HasBitSetters::ground_speed_ned(this), output); + 1, HasBitSetters::attitude_euler(this), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.GroundSpeedNedResponse) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) } -::google::protobuf::uint8* GroundSpeedNedResponse::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* CameraAttitudeEulerResponse::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.SpeedNed ground_speed_ned = 1; - if (this->has_ground_speed_ned()) { + // .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; + if (this->has_attitude_euler()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageToArray( - 1, HasBitSetters::ground_speed_ned(this), target); + 1, HasBitSetters::attitude_euler(this), target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.GroundSpeedNedResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) return target; } -size_t GroundSpeedNedResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) +size_t CameraAttitudeEulerResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -5657,11 +5936,11 @@ size_t GroundSpeedNedResponse::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.telemetry.SpeedNed ground_speed_ned = 1; - if (this->has_ground_speed_ned()) { + // .mavsdk.rpc.telemetry.EulerAngle attitude_euler = 1; + if (this->has_attitude_euler()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSize( - *ground_speed_ned_); + *attitude_euler_); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -5669,62 +5948,62 @@ size_t GroundSpeedNedResponse::ByteSizeLong() const { return total_size; } -void GroundSpeedNedResponse::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) +void CameraAttitudeEulerResponse::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) GOOGLE_DCHECK_NE(&from, this); - const GroundSpeedNedResponse* source = - ::google::protobuf::DynamicCastToGenerated( + const CameraAttitudeEulerResponse* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.GroundSpeedNedResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.GroundSpeedNedResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) MergeFrom(*source); } } -void GroundSpeedNedResponse::MergeFrom(const GroundSpeedNedResponse& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) +void CameraAttitudeEulerResponse::MergeFrom(const CameraAttitudeEulerResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.has_ground_speed_ned()) { - mutable_ground_speed_ned()->::mavsdk::rpc::telemetry::SpeedNed::MergeFrom(from.ground_speed_ned()); + if (from.has_attitude_euler()) { + mutable_attitude_euler()->::mavsdk::rpc::telemetry::EulerAngle::MergeFrom(from.attitude_euler()); } } -void GroundSpeedNedResponse::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) +void CameraAttitudeEulerResponse::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void GroundSpeedNedResponse::CopyFrom(const GroundSpeedNedResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) +void CameraAttitudeEulerResponse::CopyFrom(const CameraAttitudeEulerResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.CameraAttitudeEulerResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool GroundSpeedNedResponse::IsInitialized() const { +bool CameraAttitudeEulerResponse::IsInitialized() const { return true; } -void GroundSpeedNedResponse::Swap(GroundSpeedNedResponse* other) { +void CameraAttitudeEulerResponse::Swap(CameraAttitudeEulerResponse* other) { if (other == this) return; InternalSwap(other); } -void GroundSpeedNedResponse::InternalSwap(GroundSpeedNedResponse* other) { +void CameraAttitudeEulerResponse::InternalSwap(CameraAttitudeEulerResponse* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(ground_speed_ned_, other->ground_speed_ned_); + swap(attitude_euler_, other->attitude_euler_); } -::google::protobuf::Metadata GroundSpeedNedResponse::GetMetadata() const { +::google::protobuf::Metadata CameraAttitudeEulerResponse::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -5732,49 +6011,49 @@ ::google::protobuf::Metadata GroundSpeedNedResponse::GetMetadata() const { // =================================================================== -void SubscribeGpsInfoRequest::InitAsDefaultInstance() { +void SubscribeGroundSpeedNedRequest::InitAsDefaultInstance() { } -class SubscribeGpsInfoRequest::HasBitSetters { +class SubscribeGroundSpeedNedRequest::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -SubscribeGpsInfoRequest::SubscribeGpsInfoRequest() +SubscribeGroundSpeedNedRequest::SubscribeGroundSpeedNedRequest() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) } -SubscribeGpsInfoRequest::SubscribeGpsInfoRequest(const SubscribeGpsInfoRequest& from) +SubscribeGroundSpeedNedRequest::SubscribeGroundSpeedNedRequest(const SubscribeGroundSpeedNedRequest& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) } -void SubscribeGpsInfoRequest::SharedCtor() { +void SubscribeGroundSpeedNedRequest::SharedCtor() { } -SubscribeGpsInfoRequest::~SubscribeGpsInfoRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) +SubscribeGroundSpeedNedRequest::~SubscribeGroundSpeedNedRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) SharedDtor(); } -void SubscribeGpsInfoRequest::SharedDtor() { +void SubscribeGroundSpeedNedRequest::SharedDtor() { } -void SubscribeGpsInfoRequest::SetCachedSize(int size) const { +void SubscribeGroundSpeedNedRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -const SubscribeGpsInfoRequest& SubscribeGpsInfoRequest::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeGpsInfoRequest_telemetry_2ftelemetry_2eproto.base); +const SubscribeGroundSpeedNedRequest& SubscribeGroundSpeedNedRequest::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeGroundSpeedNedRequest_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void SubscribeGpsInfoRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) +void SubscribeGroundSpeedNedRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -5783,9 +6062,9 @@ void SubscribeGpsInfoRequest::Clear() { } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* SubscribeGpsInfoRequest::_InternalParse(const char* begin, const char* end, void* object, +const char* SubscribeGroundSpeedNedRequest::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -5811,11 +6090,11 @@ const char* SubscribeGpsInfoRequest::_InternalParse(const char* begin, const cha return ptr; } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool SubscribeGpsInfoRequest::MergePartialFromCodedStream( +bool SubscribeGroundSpeedNedRequest::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; @@ -5828,18 +6107,18 @@ bool SubscribeGpsInfoRequest::MergePartialFromCodedStream( input, tag, _internal_metadata_.mutable_unknown_fields())); } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void SubscribeGpsInfoRequest::SerializeWithCachedSizes( +void SubscribeGroundSpeedNedRequest::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -5847,12 +6126,12 @@ void SubscribeGpsInfoRequest::SerializeWithCachedSizes( ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) } -::google::protobuf::uint8* SubscribeGpsInfoRequest::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* SubscribeGroundSpeedNedRequest::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -5860,12 +6139,12 @@ ::google::protobuf::uint8* SubscribeGpsInfoRequest::InternalSerializeWithCachedS target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) return target; } -size_t SubscribeGpsInfoRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) +size_t SubscribeGroundSpeedNedRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -5882,23 +6161,23 @@ size_t SubscribeGpsInfoRequest::ByteSizeLong() const { return total_size; } -void SubscribeGpsInfoRequest::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) +void SubscribeGroundSpeedNedRequest::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) GOOGLE_DCHECK_NE(&from, this); - const SubscribeGpsInfoRequest* source = - ::google::protobuf::DynamicCastToGenerated( + const SubscribeGroundSpeedNedRequest* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) MergeFrom(*source); } } -void SubscribeGpsInfoRequest::MergeFrom(const SubscribeGpsInfoRequest& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) +void SubscribeGroundSpeedNedRequest::MergeFrom(const SubscribeGroundSpeedNedRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; @@ -5906,34 +6185,34 @@ void SubscribeGpsInfoRequest::MergeFrom(const SubscribeGpsInfoRequest& from) { } -void SubscribeGpsInfoRequest::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) +void SubscribeGroundSpeedNedRequest::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) if (&from == this) return; Clear(); MergeFrom(from); } -void SubscribeGpsInfoRequest::CopyFrom(const SubscribeGpsInfoRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) +void SubscribeGroundSpeedNedRequest::CopyFrom(const SubscribeGroundSpeedNedRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeGroundSpeedNedRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool SubscribeGpsInfoRequest::IsInitialized() const { +bool SubscribeGroundSpeedNedRequest::IsInitialized() const { return true; } -void SubscribeGpsInfoRequest::Swap(SubscribeGpsInfoRequest* other) { +void SubscribeGroundSpeedNedRequest::Swap(SubscribeGroundSpeedNedRequest* other) { if (other == this) return; InternalSwap(other); } -void SubscribeGpsInfoRequest::InternalSwap(SubscribeGpsInfoRequest* other) { +void SubscribeGroundSpeedNedRequest::InternalSwap(SubscribeGroundSpeedNedRequest* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); } -::google::protobuf::Metadata SubscribeGpsInfoRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeGroundSpeedNedRequest::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -5941,81 +6220,81 @@ ::google::protobuf::Metadata SubscribeGpsInfoRequest::GetMetadata() const { // =================================================================== -void GpsInfoResponse::InitAsDefaultInstance() { - ::mavsdk::rpc::telemetry::_GpsInfoResponse_default_instance_._instance.get_mutable()->gps_info_ = const_cast< ::mavsdk::rpc::telemetry::GpsInfo*>( - ::mavsdk::rpc::telemetry::GpsInfo::internal_default_instance()); +void GroundSpeedNedResponse::InitAsDefaultInstance() { + ::mavsdk::rpc::telemetry::_GroundSpeedNedResponse_default_instance_._instance.get_mutable()->ground_speed_ned_ = const_cast< ::mavsdk::rpc::telemetry::SpeedNed*>( + ::mavsdk::rpc::telemetry::SpeedNed::internal_default_instance()); } -class GpsInfoResponse::HasBitSetters { +class GroundSpeedNedResponse::HasBitSetters { public: - static const ::mavsdk::rpc::telemetry::GpsInfo& gps_info(const GpsInfoResponse* msg); + static const ::mavsdk::rpc::telemetry::SpeedNed& ground_speed_ned(const GroundSpeedNedResponse* msg); }; -const ::mavsdk::rpc::telemetry::GpsInfo& -GpsInfoResponse::HasBitSetters::gps_info(const GpsInfoResponse* msg) { - return *msg->gps_info_; +const ::mavsdk::rpc::telemetry::SpeedNed& +GroundSpeedNedResponse::HasBitSetters::ground_speed_ned(const GroundSpeedNedResponse* msg) { + return *msg->ground_speed_ned_; } #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int GpsInfoResponse::kGpsInfoFieldNumber; +const int GroundSpeedNedResponse::kGroundSpeedNedFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -GpsInfoResponse::GpsInfoResponse() +GroundSpeedNedResponse::GroundSpeedNedResponse() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.GroundSpeedNedResponse) } -GpsInfoResponse::GpsInfoResponse(const GpsInfoResponse& from) +GroundSpeedNedResponse::GroundSpeedNedResponse(const GroundSpeedNedResponse& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - if (from.has_gps_info()) { - gps_info_ = new ::mavsdk::rpc::telemetry::GpsInfo(*from.gps_info_); + if (from.has_ground_speed_ned()) { + ground_speed_ned_ = new ::mavsdk::rpc::telemetry::SpeedNed(*from.ground_speed_ned_); } else { - gps_info_ = nullptr; + ground_speed_ned_ = nullptr; } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.GroundSpeedNedResponse) } -void GpsInfoResponse::SharedCtor() { +void GroundSpeedNedResponse::SharedCtor() { ::google::protobuf::internal::InitSCC( - &scc_info_GpsInfoResponse_telemetry_2ftelemetry_2eproto.base); - gps_info_ = nullptr; + &scc_info_GroundSpeedNedResponse_telemetry_2ftelemetry_2eproto.base); + ground_speed_ned_ = nullptr; } -GpsInfoResponse::~GpsInfoResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.GpsInfoResponse) +GroundSpeedNedResponse::~GroundSpeedNedResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.GroundSpeedNedResponse) SharedDtor(); } -void GpsInfoResponse::SharedDtor() { - if (this != internal_default_instance()) delete gps_info_; +void GroundSpeedNedResponse::SharedDtor() { + if (this != internal_default_instance()) delete ground_speed_ned_; } -void GpsInfoResponse::SetCachedSize(int size) const { +void GroundSpeedNedResponse::SetCachedSize(int size) const { _cached_size_.Set(size); } -const GpsInfoResponse& GpsInfoResponse::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_GpsInfoResponse_telemetry_2ftelemetry_2eproto.base); +const GroundSpeedNedResponse& GroundSpeedNedResponse::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_GroundSpeedNedResponse_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void GpsInfoResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.GpsInfoResponse) +void GroundSpeedNedResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - if (GetArenaNoVirtual() == nullptr && gps_info_ != nullptr) { - delete gps_info_; + if (GetArenaNoVirtual() == nullptr && ground_speed_ned_ != nullptr) { + delete ground_speed_ned_; } - gps_info_ = nullptr; + ground_speed_ned_ = nullptr; _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* GpsInfoResponse::_InternalParse(const char* begin, const char* end, void* object, +const char* GroundSpeedNedResponse::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -6025,13 +6304,13 @@ const char* GpsInfoResponse::_InternalParse(const char* begin, const char* end, ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; + // .mavsdk.rpc.telemetry.SpeedNed ground_speed_ned = 1; case 1: { if (static_cast<::google::protobuf::uint8>(tag) != 10) goto handle_unusual; ptr = ::google::protobuf::io::ReadSize(ptr, &size); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - parser_till_end = ::mavsdk::rpc::telemetry::GpsInfo::_InternalParse; - object = msg->mutable_gps_info(); + parser_till_end = ::mavsdk::rpc::telemetry::SpeedNed::_InternalParse; + object = msg->mutable_ground_speed_ned(); if (size > end - ptr) goto len_delim_till_end; ptr += size; GOOGLE_PROTOBUF_PARSER_ASSERT(ctx->ParseExactRange( @@ -6058,21 +6337,21 @@ const char* GpsInfoResponse::_InternalParse(const char* begin, const char* end, {parser_till_end, object}, size); } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool GpsInfoResponse::MergePartialFromCodedStream( +bool GroundSpeedNedResponse::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; + // .mavsdk.rpc.telemetry.SpeedNed ground_speed_ned = 1; case 1: { if (static_cast< ::google::protobuf::uint8>(tag) == (10 & 0xFF)) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( - input, mutable_gps_info())); + input, mutable_ground_speed_ned())); } else { goto handle_unusual; } @@ -6091,57 +6370,57 @@ bool GpsInfoResponse::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.GroundSpeedNedResponse) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.GroundSpeedNedResponse) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void GpsInfoResponse::SerializeWithCachedSizes( +void GroundSpeedNedResponse::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; - if (this->has_gps_info()) { + // .mavsdk.rpc.telemetry.SpeedNed ground_speed_ned = 1; + if (this->has_ground_speed_ned()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, HasBitSetters::gps_info(this), output); + 1, HasBitSetters::ground_speed_ned(this), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.GroundSpeedNedResponse) } -::google::protobuf::uint8* GpsInfoResponse::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* GroundSpeedNedResponse::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; - if (this->has_gps_info()) { + // .mavsdk.rpc.telemetry.SpeedNed ground_speed_ned = 1; + if (this->has_ground_speed_ned()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageToArray( - 1, HasBitSetters::gps_info(this), target); + 1, HasBitSetters::ground_speed_ned(this), target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.GroundSpeedNedResponse) return target; } -size_t GpsInfoResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.GpsInfoResponse) +size_t GroundSpeedNedResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -6153,11 +6432,11 @@ size_t GpsInfoResponse::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; - if (this->has_gps_info()) { + // .mavsdk.rpc.telemetry.SpeedNed ground_speed_ned = 1; + if (this->has_ground_speed_ned()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSize( - *gps_info_); + *ground_speed_ned_); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -6165,62 +6444,62 @@ size_t GpsInfoResponse::ByteSizeLong() const { return total_size; } -void GpsInfoResponse::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.GpsInfoResponse) +void GroundSpeedNedResponse::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) GOOGLE_DCHECK_NE(&from, this); - const GpsInfoResponse* source = - ::google::protobuf::DynamicCastToGenerated( + const GroundSpeedNedResponse* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.GroundSpeedNedResponse) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.GpsInfoResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.GroundSpeedNedResponse) MergeFrom(*source); } } -void GpsInfoResponse::MergeFrom(const GpsInfoResponse& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.GpsInfoResponse) +void GroundSpeedNedResponse::MergeFrom(const GroundSpeedNedResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.has_gps_info()) { - mutable_gps_info()->::mavsdk::rpc::telemetry::GpsInfo::MergeFrom(from.gps_info()); + if (from.has_ground_speed_ned()) { + mutable_ground_speed_ned()->::mavsdk::rpc::telemetry::SpeedNed::MergeFrom(from.ground_speed_ned()); } } -void GpsInfoResponse::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.GpsInfoResponse) +void GroundSpeedNedResponse::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void GpsInfoResponse::CopyFrom(const GpsInfoResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.GpsInfoResponse) +void GroundSpeedNedResponse::CopyFrom(const GroundSpeedNedResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.GroundSpeedNedResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool GpsInfoResponse::IsInitialized() const { +bool GroundSpeedNedResponse::IsInitialized() const { return true; } -void GpsInfoResponse::Swap(GpsInfoResponse* other) { +void GroundSpeedNedResponse::Swap(GroundSpeedNedResponse* other) { if (other == this) return; InternalSwap(other); } -void GpsInfoResponse::InternalSwap(GpsInfoResponse* other) { +void GroundSpeedNedResponse::InternalSwap(GroundSpeedNedResponse* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(gps_info_, other->gps_info_); + swap(ground_speed_ned_, other->ground_speed_ned_); } -::google::protobuf::Metadata GpsInfoResponse::GetMetadata() const { +::google::protobuf::Metadata GroundSpeedNedResponse::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -6228,49 +6507,49 @@ ::google::protobuf::Metadata GpsInfoResponse::GetMetadata() const { // =================================================================== -void SubscribeBatteryRequest::InitAsDefaultInstance() { +void SubscribeGpsInfoRequest::InitAsDefaultInstance() { } -class SubscribeBatteryRequest::HasBitSetters { +class SubscribeGpsInfoRequest::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -SubscribeBatteryRequest::SubscribeBatteryRequest() +SubscribeGpsInfoRequest::SubscribeGpsInfoRequest() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeBatteryRequest) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) } -SubscribeBatteryRequest::SubscribeBatteryRequest(const SubscribeBatteryRequest& from) +SubscribeGpsInfoRequest::SubscribeGpsInfoRequest(const SubscribeGpsInfoRequest& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeBatteryRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) } -void SubscribeBatteryRequest::SharedCtor() { +void SubscribeGpsInfoRequest::SharedCtor() { } -SubscribeBatteryRequest::~SubscribeBatteryRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeBatteryRequest) +SubscribeGpsInfoRequest::~SubscribeGpsInfoRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) SharedDtor(); } -void SubscribeBatteryRequest::SharedDtor() { +void SubscribeGpsInfoRequest::SharedDtor() { } -void SubscribeBatteryRequest::SetCachedSize(int size) const { +void SubscribeGpsInfoRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -const SubscribeBatteryRequest& SubscribeBatteryRequest::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeBatteryRequest_telemetry_2ftelemetry_2eproto.base); +const SubscribeGpsInfoRequest& SubscribeGpsInfoRequest::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeGpsInfoRequest_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void SubscribeBatteryRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) +void SubscribeGpsInfoRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -6279,9 +6558,9 @@ void SubscribeBatteryRequest::Clear() { } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* SubscribeBatteryRequest::_InternalParse(const char* begin, const char* end, void* object, +const char* SubscribeGpsInfoRequest::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -6307,11 +6586,11 @@ const char* SubscribeBatteryRequest::_InternalParse(const char* begin, const cha return ptr; } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool SubscribeBatteryRequest::MergePartialFromCodedStream( +bool SubscribeGpsInfoRequest::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; @@ -6324,18 +6603,18 @@ bool SubscribeBatteryRequest::MergePartialFromCodedStream( input, tag, _internal_metadata_.mutable_unknown_fields())); } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeBatteryRequest) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeBatteryRequest) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void SubscribeBatteryRequest::SerializeWithCachedSizes( +void SubscribeGpsInfoRequest::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -6343,12 +6622,12 @@ void SubscribeBatteryRequest::SerializeWithCachedSizes( ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeBatteryRequest) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) } -::google::protobuf::uint8* SubscribeBatteryRequest::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* SubscribeGpsInfoRequest::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -6356,12 +6635,12 @@ ::google::protobuf::uint8* SubscribeBatteryRequest::InternalSerializeWithCachedS target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeBatteryRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) return target; } -size_t SubscribeBatteryRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) +size_t SubscribeGpsInfoRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -6378,23 +6657,23 @@ size_t SubscribeBatteryRequest::ByteSizeLong() const { return total_size; } -void SubscribeBatteryRequest::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) +void SubscribeGpsInfoRequest::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) GOOGLE_DCHECK_NE(&from, this); - const SubscribeBatteryRequest* source = - ::google::protobuf::DynamicCastToGenerated( + const SubscribeGpsInfoRequest* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeBatteryRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeBatteryRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) MergeFrom(*source); } } -void SubscribeBatteryRequest::MergeFrom(const SubscribeBatteryRequest& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) +void SubscribeGpsInfoRequest::MergeFrom(const SubscribeGpsInfoRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; @@ -6402,34 +6681,34 @@ void SubscribeBatteryRequest::MergeFrom(const SubscribeBatteryRequest& from) { } -void SubscribeBatteryRequest::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) +void SubscribeGpsInfoRequest::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) if (&from == this) return; Clear(); MergeFrom(from); } -void SubscribeBatteryRequest::CopyFrom(const SubscribeBatteryRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) +void SubscribeGpsInfoRequest::CopyFrom(const SubscribeGpsInfoRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeGpsInfoRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool SubscribeBatteryRequest::IsInitialized() const { +bool SubscribeGpsInfoRequest::IsInitialized() const { return true; } -void SubscribeBatteryRequest::Swap(SubscribeBatteryRequest* other) { +void SubscribeGpsInfoRequest::Swap(SubscribeGpsInfoRequest* other) { if (other == this) return; InternalSwap(other); } -void SubscribeBatteryRequest::InternalSwap(SubscribeBatteryRequest* other) { +void SubscribeGpsInfoRequest::InternalSwap(SubscribeGpsInfoRequest* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); } -::google::protobuf::Metadata SubscribeBatteryRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeGpsInfoRequest::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -6437,81 +6716,81 @@ ::google::protobuf::Metadata SubscribeBatteryRequest::GetMetadata() const { // =================================================================== -void BatteryResponse::InitAsDefaultInstance() { - ::mavsdk::rpc::telemetry::_BatteryResponse_default_instance_._instance.get_mutable()->battery_ = const_cast< ::mavsdk::rpc::telemetry::Battery*>( - ::mavsdk::rpc::telemetry::Battery::internal_default_instance()); +void GpsInfoResponse::InitAsDefaultInstance() { + ::mavsdk::rpc::telemetry::_GpsInfoResponse_default_instance_._instance.get_mutable()->gps_info_ = const_cast< ::mavsdk::rpc::telemetry::GpsInfo*>( + ::mavsdk::rpc::telemetry::GpsInfo::internal_default_instance()); } -class BatteryResponse::HasBitSetters { +class GpsInfoResponse::HasBitSetters { public: - static const ::mavsdk::rpc::telemetry::Battery& battery(const BatteryResponse* msg); + static const ::mavsdk::rpc::telemetry::GpsInfo& gps_info(const GpsInfoResponse* msg); }; -const ::mavsdk::rpc::telemetry::Battery& -BatteryResponse::HasBitSetters::battery(const BatteryResponse* msg) { - return *msg->battery_; +const ::mavsdk::rpc::telemetry::GpsInfo& +GpsInfoResponse::HasBitSetters::gps_info(const GpsInfoResponse* msg) { + return *msg->gps_info_; } #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int BatteryResponse::kBatteryFieldNumber; +const int GpsInfoResponse::kGpsInfoFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -BatteryResponse::BatteryResponse() +GpsInfoResponse::GpsInfoResponse() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.BatteryResponse) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.GpsInfoResponse) } -BatteryResponse::BatteryResponse(const BatteryResponse& from) +GpsInfoResponse::GpsInfoResponse(const GpsInfoResponse& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - if (from.has_battery()) { - battery_ = new ::mavsdk::rpc::telemetry::Battery(*from.battery_); + if (from.has_gps_info()) { + gps_info_ = new ::mavsdk::rpc::telemetry::GpsInfo(*from.gps_info_); } else { - battery_ = nullptr; + gps_info_ = nullptr; } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.BatteryResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.GpsInfoResponse) } -void BatteryResponse::SharedCtor() { +void GpsInfoResponse::SharedCtor() { ::google::protobuf::internal::InitSCC( - &scc_info_BatteryResponse_telemetry_2ftelemetry_2eproto.base); - battery_ = nullptr; + &scc_info_GpsInfoResponse_telemetry_2ftelemetry_2eproto.base); + gps_info_ = nullptr; } -BatteryResponse::~BatteryResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.BatteryResponse) +GpsInfoResponse::~GpsInfoResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.GpsInfoResponse) SharedDtor(); } -void BatteryResponse::SharedDtor() { - if (this != internal_default_instance()) delete battery_; +void GpsInfoResponse::SharedDtor() { + if (this != internal_default_instance()) delete gps_info_; } -void BatteryResponse::SetCachedSize(int size) const { +void GpsInfoResponse::SetCachedSize(int size) const { _cached_size_.Set(size); } -const BatteryResponse& BatteryResponse::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_BatteryResponse_telemetry_2ftelemetry_2eproto.base); +const GpsInfoResponse& GpsInfoResponse::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_GpsInfoResponse_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void BatteryResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.BatteryResponse) +void GpsInfoResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.GpsInfoResponse) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - if (GetArenaNoVirtual() == nullptr && battery_ != nullptr) { - delete battery_; + if (GetArenaNoVirtual() == nullptr && gps_info_ != nullptr) { + delete gps_info_; } - battery_ = nullptr; + gps_info_ = nullptr; _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* BatteryResponse::_InternalParse(const char* begin, const char* end, void* object, +const char* GpsInfoResponse::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -6521,13 +6800,13 @@ const char* BatteryResponse::_InternalParse(const char* begin, const char* end, ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // .mavsdk.rpc.telemetry.Battery battery = 1; + // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; case 1: { if (static_cast<::google::protobuf::uint8>(tag) != 10) goto handle_unusual; ptr = ::google::protobuf::io::ReadSize(ptr, &size); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - parser_till_end = ::mavsdk::rpc::telemetry::Battery::_InternalParse; - object = msg->mutable_battery(); + parser_till_end = ::mavsdk::rpc::telemetry::GpsInfo::_InternalParse; + object = msg->mutable_gps_info(); if (size > end - ptr) goto len_delim_till_end; ptr += size; GOOGLE_PROTOBUF_PARSER_ASSERT(ctx->ParseExactRange( @@ -6554,21 +6833,21 @@ const char* BatteryResponse::_InternalParse(const char* begin, const char* end, {parser_till_end, object}, size); } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool BatteryResponse::MergePartialFromCodedStream( +bool GpsInfoResponse::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.BatteryResponse) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.GpsInfoResponse) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // .mavsdk.rpc.telemetry.Battery battery = 1; + // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; case 1: { if (static_cast< ::google::protobuf::uint8>(tag) == (10 & 0xFF)) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( - input, mutable_battery())); + input, mutable_gps_info())); } else { goto handle_unusual; } @@ -6587,57 +6866,57 @@ bool BatteryResponse::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.BatteryResponse) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.GpsInfoResponse) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.BatteryResponse) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.GpsInfoResponse) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void BatteryResponse::SerializeWithCachedSizes( +void GpsInfoResponse::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.BatteryResponse) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.GpsInfoResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.Battery battery = 1; - if (this->has_battery()) { + // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; + if (this->has_gps_info()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, HasBitSetters::battery(this), output); + 1, HasBitSetters::gps_info(this), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.BatteryResponse) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.GpsInfoResponse) } -::google::protobuf::uint8* BatteryResponse::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* GpsInfoResponse::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.BatteryResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.GpsInfoResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.Battery battery = 1; - if (this->has_battery()) { + // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; + if (this->has_gps_info()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageToArray( - 1, HasBitSetters::battery(this), target); + 1, HasBitSetters::gps_info(this), target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.BatteryResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.GpsInfoResponse) return target; } -size_t BatteryResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.BatteryResponse) +size_t GpsInfoResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.GpsInfoResponse) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -6649,11 +6928,11 @@ size_t BatteryResponse::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.telemetry.Battery battery = 1; - if (this->has_battery()) { + // .mavsdk.rpc.telemetry.GpsInfo gps_info = 1; + if (this->has_gps_info()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSize( - *battery_); + *gps_info_); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -6661,62 +6940,62 @@ size_t BatteryResponse::ByteSizeLong() const { return total_size; } -void BatteryResponse::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.BatteryResponse) +void GpsInfoResponse::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.GpsInfoResponse) GOOGLE_DCHECK_NE(&from, this); - const BatteryResponse* source = - ::google::protobuf::DynamicCastToGenerated( + const GpsInfoResponse* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.BatteryResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.GpsInfoResponse) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.BatteryResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.GpsInfoResponse) MergeFrom(*source); } } -void BatteryResponse::MergeFrom(const BatteryResponse& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.BatteryResponse) +void GpsInfoResponse::MergeFrom(const GpsInfoResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.GpsInfoResponse) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.has_battery()) { - mutable_battery()->::mavsdk::rpc::telemetry::Battery::MergeFrom(from.battery()); + if (from.has_gps_info()) { + mutable_gps_info()->::mavsdk::rpc::telemetry::GpsInfo::MergeFrom(from.gps_info()); } } -void BatteryResponse::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.BatteryResponse) +void GpsInfoResponse::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.GpsInfoResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void BatteryResponse::CopyFrom(const BatteryResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.BatteryResponse) +void GpsInfoResponse::CopyFrom(const GpsInfoResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.GpsInfoResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool BatteryResponse::IsInitialized() const { +bool GpsInfoResponse::IsInitialized() const { return true; } -void BatteryResponse::Swap(BatteryResponse* other) { +void GpsInfoResponse::Swap(GpsInfoResponse* other) { if (other == this) return; InternalSwap(other); } -void BatteryResponse::InternalSwap(BatteryResponse* other) { +void GpsInfoResponse::InternalSwap(GpsInfoResponse* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(battery_, other->battery_); + swap(gps_info_, other->gps_info_); } -::google::protobuf::Metadata BatteryResponse::GetMetadata() const { +::google::protobuf::Metadata GpsInfoResponse::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -6724,49 +7003,49 @@ ::google::protobuf::Metadata BatteryResponse::GetMetadata() const { // =================================================================== -void SubscribeFlightModeRequest::InitAsDefaultInstance() { +void SubscribeBatteryRequest::InitAsDefaultInstance() { } -class SubscribeFlightModeRequest::HasBitSetters { +class SubscribeBatteryRequest::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -SubscribeFlightModeRequest::SubscribeFlightModeRequest() +SubscribeBatteryRequest::SubscribeBatteryRequest() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeBatteryRequest) } -SubscribeFlightModeRequest::SubscribeFlightModeRequest(const SubscribeFlightModeRequest& from) +SubscribeBatteryRequest::SubscribeBatteryRequest(const SubscribeBatteryRequest& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeBatteryRequest) } -void SubscribeFlightModeRequest::SharedCtor() { +void SubscribeBatteryRequest::SharedCtor() { } -SubscribeFlightModeRequest::~SubscribeFlightModeRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) +SubscribeBatteryRequest::~SubscribeBatteryRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeBatteryRequest) SharedDtor(); } -void SubscribeFlightModeRequest::SharedDtor() { +void SubscribeBatteryRequest::SharedDtor() { } -void SubscribeFlightModeRequest::SetCachedSize(int size) const { +void SubscribeBatteryRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -const SubscribeFlightModeRequest& SubscribeFlightModeRequest::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeFlightModeRequest_telemetry_2ftelemetry_2eproto.base); +const SubscribeBatteryRequest& SubscribeBatteryRequest::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeBatteryRequest_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void SubscribeFlightModeRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) +void SubscribeBatteryRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -6775,9 +7054,9 @@ void SubscribeFlightModeRequest::Clear() { } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* SubscribeFlightModeRequest::_InternalParse(const char* begin, const char* end, void* object, +const char* SubscribeBatteryRequest::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -6803,11 +7082,11 @@ const char* SubscribeFlightModeRequest::_InternalParse(const char* begin, const return ptr; } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool SubscribeFlightModeRequest::MergePartialFromCodedStream( +bool SubscribeBatteryRequest::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; @@ -6820,18 +7099,18 @@ bool SubscribeFlightModeRequest::MergePartialFromCodedStream( input, tag, _internal_metadata_.mutable_unknown_fields())); } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeBatteryRequest) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeBatteryRequest) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void SubscribeFlightModeRequest::SerializeWithCachedSizes( +void SubscribeBatteryRequest::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -6839,12 +7118,12 @@ void SubscribeFlightModeRequest::SerializeWithCachedSizes( ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeBatteryRequest) } -::google::protobuf::uint8* SubscribeFlightModeRequest::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* SubscribeBatteryRequest::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -6852,12 +7131,12 @@ ::google::protobuf::uint8* SubscribeFlightModeRequest::InternalSerializeWithCach target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeBatteryRequest) return target; } -size_t SubscribeFlightModeRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) +size_t SubscribeBatteryRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -6874,23 +7153,23 @@ size_t SubscribeFlightModeRequest::ByteSizeLong() const { return total_size; } -void SubscribeFlightModeRequest::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) +void SubscribeBatteryRequest::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) GOOGLE_DCHECK_NE(&from, this); - const SubscribeFlightModeRequest* source = - ::google::protobuf::DynamicCastToGenerated( + const SubscribeBatteryRequest* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeBatteryRequest) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeBatteryRequest) MergeFrom(*source); } } -void SubscribeFlightModeRequest::MergeFrom(const SubscribeFlightModeRequest& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) +void SubscribeBatteryRequest::MergeFrom(const SubscribeBatteryRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; @@ -6898,34 +7177,34 @@ void SubscribeFlightModeRequest::MergeFrom(const SubscribeFlightModeRequest& fro } -void SubscribeFlightModeRequest::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) +void SubscribeBatteryRequest::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) if (&from == this) return; Clear(); MergeFrom(from); } -void SubscribeFlightModeRequest::CopyFrom(const SubscribeFlightModeRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) +void SubscribeBatteryRequest::CopyFrom(const SubscribeBatteryRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeBatteryRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool SubscribeFlightModeRequest::IsInitialized() const { +bool SubscribeBatteryRequest::IsInitialized() const { return true; } -void SubscribeFlightModeRequest::Swap(SubscribeFlightModeRequest* other) { +void SubscribeBatteryRequest::Swap(SubscribeBatteryRequest* other) { if (other == this) return; InternalSwap(other); } -void SubscribeFlightModeRequest::InternalSwap(SubscribeFlightModeRequest* other) { +void SubscribeBatteryRequest::InternalSwap(SubscribeBatteryRequest* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); } -::google::protobuf::Metadata SubscribeFlightModeRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeBatteryRequest::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -6933,64 +7212,81 @@ ::google::protobuf::Metadata SubscribeFlightModeRequest::GetMetadata() const { // =================================================================== -void FlightModeResponse::InitAsDefaultInstance() { +void BatteryResponse::InitAsDefaultInstance() { + ::mavsdk::rpc::telemetry::_BatteryResponse_default_instance_._instance.get_mutable()->battery_ = const_cast< ::mavsdk::rpc::telemetry::Battery*>( + ::mavsdk::rpc::telemetry::Battery::internal_default_instance()); } -class FlightModeResponse::HasBitSetters { +class BatteryResponse::HasBitSetters { public: + static const ::mavsdk::rpc::telemetry::Battery& battery(const BatteryResponse* msg); }; +const ::mavsdk::rpc::telemetry::Battery& +BatteryResponse::HasBitSetters::battery(const BatteryResponse* msg) { + return *msg->battery_; +} #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int FlightModeResponse::kFlightModeFieldNumber; +const int BatteryResponse::kBatteryFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -FlightModeResponse::FlightModeResponse() +BatteryResponse::BatteryResponse() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.FlightModeResponse) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.BatteryResponse) } -FlightModeResponse::FlightModeResponse(const FlightModeResponse& from) +BatteryResponse::BatteryResponse(const BatteryResponse& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - flight_mode_ = from.flight_mode_; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.FlightModeResponse) + if (from.has_battery()) { + battery_ = new ::mavsdk::rpc::telemetry::Battery(*from.battery_); + } else { + battery_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.BatteryResponse) } -void FlightModeResponse::SharedCtor() { - flight_mode_ = 0; +void BatteryResponse::SharedCtor() { + ::google::protobuf::internal::InitSCC( + &scc_info_BatteryResponse_telemetry_2ftelemetry_2eproto.base); + battery_ = nullptr; } -FlightModeResponse::~FlightModeResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.FlightModeResponse) +BatteryResponse::~BatteryResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.BatteryResponse) SharedDtor(); } -void FlightModeResponse::SharedDtor() { +void BatteryResponse::SharedDtor() { + if (this != internal_default_instance()) delete battery_; } -void FlightModeResponse::SetCachedSize(int size) const { +void BatteryResponse::SetCachedSize(int size) const { _cached_size_.Set(size); } -const FlightModeResponse& FlightModeResponse::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_FlightModeResponse_telemetry_2ftelemetry_2eproto.base); +const BatteryResponse& BatteryResponse::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_BatteryResponse_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void FlightModeResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.FlightModeResponse) +void BatteryResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.BatteryResponse) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - flight_mode_ = 0; + if (GetArenaNoVirtual() == nullptr && battery_ != nullptr) { + delete battery_; + } + battery_ = nullptr; _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* FlightModeResponse::_InternalParse(const char* begin, const char* end, void* object, +const char* BatteryResponse::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -7000,12 +7296,17 @@ const char* FlightModeResponse::_InternalParse(const char* begin, const char* en ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; + // .mavsdk.rpc.telemetry.Battery battery = 1; case 1: { - if (static_cast<::google::protobuf::uint8>(tag) != 8) goto handle_unusual; - ::google::protobuf::uint64 val = ::google::protobuf::internal::ReadVarint(&ptr); - msg->set_flight_mode(static_cast<::mavsdk::rpc::telemetry::FlightMode>(val)); + if (static_cast<::google::protobuf::uint8>(tag) != 10) goto handle_unusual; + ptr = ::google::protobuf::io::ReadSize(ptr, &size); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + parser_till_end = ::mavsdk::rpc::telemetry::Battery::_InternalParse; + object = msg->mutable_battery(); + if (size > end - ptr) goto len_delim_till_end; + ptr += size; + GOOGLE_PROTOBUF_PARSER_ASSERT(ctx->ParseExactRange( + {parser_till_end, object}, ptr - size, ptr)); break; } default: { @@ -7023,26 +7324,26 @@ const char* FlightModeResponse::_InternalParse(const char* begin, const char* en } // switch } // while return ptr; +len_delim_till_end: + return ctx->StoreAndTailCall(ptr, end, {_InternalParse, msg}, + {parser_till_end, object}, size); } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool FlightModeResponse::MergePartialFromCodedStream( +bool BatteryResponse::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.FlightModeResponse) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.BatteryResponse) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; + // .mavsdk.rpc.telemetry.Battery battery = 1; case 1: { - if (static_cast< ::google::protobuf::uint8>(tag) == (8 & 0xFF)) { - int value = 0; - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( - input, &value))); - set_flight_mode(static_cast< ::mavsdk::rpc::telemetry::FlightMode >(value)); + if (static_cast< ::google::protobuf::uint8>(tag) == (10 & 0xFF)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_battery())); } else { goto handle_unusual; } @@ -7061,56 +7362,57 @@ bool FlightModeResponse::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.FlightModeResponse) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.BatteryResponse) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.FlightModeResponse) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.BatteryResponse) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void FlightModeResponse::SerializeWithCachedSizes( +void BatteryResponse::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.FlightModeResponse) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.BatteryResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; - if (this->flight_mode() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteEnum( - 1, this->flight_mode(), output); + // .mavsdk.rpc.telemetry.Battery battery = 1; + if (this->has_battery()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, HasBitSetters::battery(this), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.FlightModeResponse) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.BatteryResponse) } -::google::protobuf::uint8* FlightModeResponse::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* BatteryResponse::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.FlightModeResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.BatteryResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; - if (this->flight_mode() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( - 1, this->flight_mode(), target); + // .mavsdk.rpc.telemetry.Battery battery = 1; + if (this->has_battery()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, HasBitSetters::battery(this), target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.FlightModeResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.BatteryResponse) return target; } -size_t FlightModeResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.FlightModeResponse) +size_t BatteryResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.BatteryResponse) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -7122,10 +7424,11 @@ size_t FlightModeResponse::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; - if (this->flight_mode() != 0) { + // .mavsdk.rpc.telemetry.Battery battery = 1; + if (this->has_battery()) { total_size += 1 + - ::google::protobuf::internal::WireFormatLite::EnumSize(this->flight_mode()); + ::google::protobuf::internal::WireFormatLite::MessageSize( + *battery_); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -7133,62 +7436,62 @@ size_t FlightModeResponse::ByteSizeLong() const { return total_size; } -void FlightModeResponse::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.FlightModeResponse) +void BatteryResponse::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.BatteryResponse) GOOGLE_DCHECK_NE(&from, this); - const FlightModeResponse* source = - ::google::protobuf::DynamicCastToGenerated( + const BatteryResponse* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.FlightModeResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.BatteryResponse) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.FlightModeResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.BatteryResponse) MergeFrom(*source); } } -void FlightModeResponse::MergeFrom(const FlightModeResponse& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.FlightModeResponse) +void BatteryResponse::MergeFrom(const BatteryResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.BatteryResponse) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.flight_mode() != 0) { - set_flight_mode(from.flight_mode()); + if (from.has_battery()) { + mutable_battery()->::mavsdk::rpc::telemetry::Battery::MergeFrom(from.battery()); } } -void FlightModeResponse::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.FlightModeResponse) +void BatteryResponse::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.BatteryResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void FlightModeResponse::CopyFrom(const FlightModeResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.FlightModeResponse) +void BatteryResponse::CopyFrom(const BatteryResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.BatteryResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool FlightModeResponse::IsInitialized() const { +bool BatteryResponse::IsInitialized() const { return true; } -void FlightModeResponse::Swap(FlightModeResponse* other) { +void BatteryResponse::Swap(BatteryResponse* other) { if (other == this) return; InternalSwap(other); } -void FlightModeResponse::InternalSwap(FlightModeResponse* other) { +void BatteryResponse::InternalSwap(BatteryResponse* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(flight_mode_, other->flight_mode_); + swap(battery_, other->battery_); } -::google::protobuf::Metadata FlightModeResponse::GetMetadata() const { +::google::protobuf::Metadata BatteryResponse::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -7196,49 +7499,49 @@ ::google::protobuf::Metadata FlightModeResponse::GetMetadata() const { // =================================================================== -void SubscribeHealthRequest::InitAsDefaultInstance() { +void SubscribeFlightModeRequest::InitAsDefaultInstance() { } -class SubscribeHealthRequest::HasBitSetters { +class SubscribeFlightModeRequest::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -SubscribeHealthRequest::SubscribeHealthRequest() +SubscribeFlightModeRequest::SubscribeFlightModeRequest() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeHealthRequest) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) } -SubscribeHealthRequest::SubscribeHealthRequest(const SubscribeHealthRequest& from) +SubscribeFlightModeRequest::SubscribeFlightModeRequest(const SubscribeFlightModeRequest& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeHealthRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) } -void SubscribeHealthRequest::SharedCtor() { +void SubscribeFlightModeRequest::SharedCtor() { } -SubscribeHealthRequest::~SubscribeHealthRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeHealthRequest) +SubscribeFlightModeRequest::~SubscribeFlightModeRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) SharedDtor(); } -void SubscribeHealthRequest::SharedDtor() { +void SubscribeFlightModeRequest::SharedDtor() { } -void SubscribeHealthRequest::SetCachedSize(int size) const { +void SubscribeFlightModeRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -const SubscribeHealthRequest& SubscribeHealthRequest::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeHealthRequest_telemetry_2ftelemetry_2eproto.base); +const SubscribeFlightModeRequest& SubscribeFlightModeRequest::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeFlightModeRequest_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void SubscribeHealthRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) +void SubscribeFlightModeRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -7247,9 +7550,9 @@ void SubscribeHealthRequest::Clear() { } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* SubscribeHealthRequest::_InternalParse(const char* begin, const char* end, void* object, +const char* SubscribeFlightModeRequest::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -7275,11 +7578,11 @@ const char* SubscribeHealthRequest::_InternalParse(const char* begin, const char return ptr; } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool SubscribeHealthRequest::MergePartialFromCodedStream( +bool SubscribeFlightModeRequest::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; @@ -7292,18 +7595,18 @@ bool SubscribeHealthRequest::MergePartialFromCodedStream( input, tag, _internal_metadata_.mutable_unknown_fields())); } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeHealthRequest) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeHealthRequest) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void SubscribeHealthRequest::SerializeWithCachedSizes( +void SubscribeFlightModeRequest::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -7311,12 +7614,12 @@ void SubscribeHealthRequest::SerializeWithCachedSizes( ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeHealthRequest) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) } -::google::protobuf::uint8* SubscribeHealthRequest::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* SubscribeFlightModeRequest::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -7324,12 +7627,12 @@ ::google::protobuf::uint8* SubscribeHealthRequest::InternalSerializeWithCachedSi target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeHealthRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) return target; } -size_t SubscribeHealthRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) +size_t SubscribeFlightModeRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -7346,23 +7649,23 @@ size_t SubscribeHealthRequest::ByteSizeLong() const { return total_size; } -void SubscribeHealthRequest::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) +void SubscribeFlightModeRequest::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) GOOGLE_DCHECK_NE(&from, this); - const SubscribeHealthRequest* source = - ::google::protobuf::DynamicCastToGenerated( + const SubscribeFlightModeRequest* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeHealthRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeHealthRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) MergeFrom(*source); } } -void SubscribeHealthRequest::MergeFrom(const SubscribeHealthRequest& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) +void SubscribeFlightModeRequest::MergeFrom(const SubscribeFlightModeRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; @@ -7370,34 +7673,34 @@ void SubscribeHealthRequest::MergeFrom(const SubscribeHealthRequest& from) { } -void SubscribeHealthRequest::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) +void SubscribeFlightModeRequest::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) if (&from == this) return; Clear(); MergeFrom(from); } -void SubscribeHealthRequest::CopyFrom(const SubscribeHealthRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) +void SubscribeFlightModeRequest::CopyFrom(const SubscribeFlightModeRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeFlightModeRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool SubscribeHealthRequest::IsInitialized() const { +bool SubscribeFlightModeRequest::IsInitialized() const { return true; } -void SubscribeHealthRequest::Swap(SubscribeHealthRequest* other) { +void SubscribeFlightModeRequest::Swap(SubscribeFlightModeRequest* other) { if (other == this) return; InternalSwap(other); } -void SubscribeHealthRequest::InternalSwap(SubscribeHealthRequest* other) { +void SubscribeFlightModeRequest::InternalSwap(SubscribeFlightModeRequest* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); } -::google::protobuf::Metadata SubscribeHealthRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeFlightModeRequest::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -7405,81 +7708,64 @@ ::google::protobuf::Metadata SubscribeHealthRequest::GetMetadata() const { // =================================================================== -void HealthResponse::InitAsDefaultInstance() { - ::mavsdk::rpc::telemetry::_HealthResponse_default_instance_._instance.get_mutable()->health_ = const_cast< ::mavsdk::rpc::telemetry::Health*>( - ::mavsdk::rpc::telemetry::Health::internal_default_instance()); +void FlightModeResponse::InitAsDefaultInstance() { } -class HealthResponse::HasBitSetters { +class FlightModeResponse::HasBitSetters { public: - static const ::mavsdk::rpc::telemetry::Health& health(const HealthResponse* msg); }; -const ::mavsdk::rpc::telemetry::Health& -HealthResponse::HasBitSetters::health(const HealthResponse* msg) { - return *msg->health_; -} #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int HealthResponse::kHealthFieldNumber; +const int FlightModeResponse::kFlightModeFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -HealthResponse::HealthResponse() +FlightModeResponse::FlightModeResponse() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.HealthResponse) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.FlightModeResponse) } -HealthResponse::HealthResponse(const HealthResponse& from) +FlightModeResponse::FlightModeResponse(const FlightModeResponse& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - if (from.has_health()) { - health_ = new ::mavsdk::rpc::telemetry::Health(*from.health_); - } else { - health_ = nullptr; - } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.HealthResponse) + flight_mode_ = from.flight_mode_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.FlightModeResponse) } -void HealthResponse::SharedCtor() { - ::google::protobuf::internal::InitSCC( - &scc_info_HealthResponse_telemetry_2ftelemetry_2eproto.base); - health_ = nullptr; +void FlightModeResponse::SharedCtor() { + flight_mode_ = 0; } -HealthResponse::~HealthResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.HealthResponse) +FlightModeResponse::~FlightModeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.FlightModeResponse) SharedDtor(); } -void HealthResponse::SharedDtor() { - if (this != internal_default_instance()) delete health_; +void FlightModeResponse::SharedDtor() { } -void HealthResponse::SetCachedSize(int size) const { +void FlightModeResponse::SetCachedSize(int size) const { _cached_size_.Set(size); } -const HealthResponse& HealthResponse::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_HealthResponse_telemetry_2ftelemetry_2eproto.base); +const FlightModeResponse& FlightModeResponse::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_FlightModeResponse_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void HealthResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.HealthResponse) +void FlightModeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.FlightModeResponse) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - if (GetArenaNoVirtual() == nullptr && health_ != nullptr) { - delete health_; - } - health_ = nullptr; + flight_mode_ = 0; _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* HealthResponse::_InternalParse(const char* begin, const char* end, void* object, +const char* FlightModeResponse::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -7489,17 +7775,12 @@ const char* HealthResponse::_InternalParse(const char* begin, const char* end, v ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // .mavsdk.rpc.telemetry.Health health = 1; + // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; case 1: { - if (static_cast<::google::protobuf::uint8>(tag) != 10) goto handle_unusual; - ptr = ::google::protobuf::io::ReadSize(ptr, &size); + if (static_cast<::google::protobuf::uint8>(tag) != 8) goto handle_unusual; + ::google::protobuf::uint64 val = ::google::protobuf::internal::ReadVarint(&ptr); + msg->set_flight_mode(static_cast<::mavsdk::rpc::telemetry::FlightMode>(val)); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - parser_till_end = ::mavsdk::rpc::telemetry::Health::_InternalParse; - object = msg->mutable_health(); - if (size > end - ptr) goto len_delim_till_end; - ptr += size; - GOOGLE_PROTOBUF_PARSER_ASSERT(ctx->ParseExactRange( - {parser_till_end, object}, ptr - size, ptr)); break; } default: { @@ -7517,26 +7798,26 @@ const char* HealthResponse::_InternalParse(const char* begin, const char* end, v } // switch } // while return ptr; -len_delim_till_end: - return ctx->StoreAndTailCall(ptr, end, {_InternalParse, msg}, - {parser_till_end, object}, size); } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool HealthResponse::MergePartialFromCodedStream( +bool FlightModeResponse::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.HealthResponse) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.FlightModeResponse) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // .mavsdk.rpc.telemetry.Health health = 1; + // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; case 1: { - if (static_cast< ::google::protobuf::uint8>(tag) == (10 & 0xFF)) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( - input, mutable_health())); + if (static_cast< ::google::protobuf::uint8>(tag) == (8 & 0xFF)) { + int value = 0; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_flight_mode(static_cast< ::mavsdk::rpc::telemetry::FlightMode >(value)); } else { goto handle_unusual; } @@ -7555,57 +7836,56 @@ bool HealthResponse::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.HealthResponse) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.FlightModeResponse) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.HealthResponse) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.FlightModeResponse) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void HealthResponse::SerializeWithCachedSizes( +void FlightModeResponse::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.HealthResponse) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.FlightModeResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.Health health = 1; - if (this->has_health()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, HasBitSetters::health(this), output); + // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; + if (this->flight_mode() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 1, this->flight_mode(), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.HealthResponse) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.FlightModeResponse) } -::google::protobuf::uint8* HealthResponse::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* FlightModeResponse::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.HealthResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.FlightModeResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.Health health = 1; - if (this->has_health()) { - target = ::google::protobuf::internal::WireFormatLite:: - InternalWriteMessageToArray( - 1, HasBitSetters::health(this), target); + // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; + if (this->flight_mode() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 1, this->flight_mode(), target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.HealthResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.FlightModeResponse) return target; } -size_t HealthResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.HealthResponse) +size_t FlightModeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.FlightModeResponse) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -7617,11 +7897,10 @@ size_t HealthResponse::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.telemetry.Health health = 1; - if (this->has_health()) { + // .mavsdk.rpc.telemetry.FlightMode flight_mode = 1; + if (this->flight_mode() != 0) { total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSize( - *health_); + ::google::protobuf::internal::WireFormatLite::EnumSize(this->flight_mode()); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -7629,62 +7908,62 @@ size_t HealthResponse::ByteSizeLong() const { return total_size; } -void HealthResponse::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.HealthResponse) +void FlightModeResponse::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.FlightModeResponse) GOOGLE_DCHECK_NE(&from, this); - const HealthResponse* source = - ::google::protobuf::DynamicCastToGenerated( + const FlightModeResponse* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.HealthResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.FlightModeResponse) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.HealthResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.FlightModeResponse) MergeFrom(*source); } } -void HealthResponse::MergeFrom(const HealthResponse& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.HealthResponse) +void FlightModeResponse::MergeFrom(const FlightModeResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.FlightModeResponse) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.has_health()) { - mutable_health()->::mavsdk::rpc::telemetry::Health::MergeFrom(from.health()); + if (from.flight_mode() != 0) { + set_flight_mode(from.flight_mode()); } } -void HealthResponse::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.HealthResponse) +void FlightModeResponse::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.FlightModeResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void HealthResponse::CopyFrom(const HealthResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.HealthResponse) +void FlightModeResponse::CopyFrom(const FlightModeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.FlightModeResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool HealthResponse::IsInitialized() const { +bool FlightModeResponse::IsInitialized() const { return true; } -void HealthResponse::Swap(HealthResponse* other) { +void FlightModeResponse::Swap(FlightModeResponse* other) { if (other == this) return; InternalSwap(other); } -void HealthResponse::InternalSwap(HealthResponse* other) { +void FlightModeResponse::InternalSwap(FlightModeResponse* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(health_, other->health_); + swap(flight_mode_, other->flight_mode_); } -::google::protobuf::Metadata HealthResponse::GetMetadata() const { +::google::protobuf::Metadata FlightModeResponse::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -7692,49 +7971,49 @@ ::google::protobuf::Metadata HealthResponse::GetMetadata() const { // =================================================================== -void SubscribeRcStatusRequest::InitAsDefaultInstance() { +void SubscribeHealthRequest::InitAsDefaultInstance() { } -class SubscribeRcStatusRequest::HasBitSetters { +class SubscribeHealthRequest::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -SubscribeRcStatusRequest::SubscribeRcStatusRequest() +SubscribeHealthRequest::SubscribeHealthRequest() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeHealthRequest) } -SubscribeRcStatusRequest::SubscribeRcStatusRequest(const SubscribeRcStatusRequest& from) +SubscribeHealthRequest::SubscribeHealthRequest(const SubscribeHealthRequest& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeHealthRequest) } -void SubscribeRcStatusRequest::SharedCtor() { +void SubscribeHealthRequest::SharedCtor() { } -SubscribeRcStatusRequest::~SubscribeRcStatusRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) +SubscribeHealthRequest::~SubscribeHealthRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeHealthRequest) SharedDtor(); } -void SubscribeRcStatusRequest::SharedDtor() { +void SubscribeHealthRequest::SharedDtor() { } -void SubscribeRcStatusRequest::SetCachedSize(int size) const { +void SubscribeHealthRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -const SubscribeRcStatusRequest& SubscribeRcStatusRequest::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeRcStatusRequest_telemetry_2ftelemetry_2eproto.base); +const SubscribeHealthRequest& SubscribeHealthRequest::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeHealthRequest_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void SubscribeRcStatusRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) +void SubscribeHealthRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -7743,9 +8022,9 @@ void SubscribeRcStatusRequest::Clear() { } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* SubscribeRcStatusRequest::_InternalParse(const char* begin, const char* end, void* object, +const char* SubscribeHealthRequest::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -7771,11 +8050,11 @@ const char* SubscribeRcStatusRequest::_InternalParse(const char* begin, const ch return ptr; } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool SubscribeRcStatusRequest::MergePartialFromCodedStream( +bool SubscribeHealthRequest::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; @@ -7788,18 +8067,18 @@ bool SubscribeRcStatusRequest::MergePartialFromCodedStream( input, tag, _internal_metadata_.mutable_unknown_fields())); } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeHealthRequest) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeHealthRequest) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void SubscribeRcStatusRequest::SerializeWithCachedSizes( +void SubscribeHealthRequest::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -7807,12 +8086,12 @@ void SubscribeRcStatusRequest::SerializeWithCachedSizes( ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeHealthRequest) } -::google::protobuf::uint8* SubscribeRcStatusRequest::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* SubscribeHealthRequest::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -7820,12 +8099,12 @@ ::google::protobuf::uint8* SubscribeRcStatusRequest::InternalSerializeWithCached target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeHealthRequest) return target; } -size_t SubscribeRcStatusRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) +size_t SubscribeHealthRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -7842,23 +8121,23 @@ size_t SubscribeRcStatusRequest::ByteSizeLong() const { return total_size; } -void SubscribeRcStatusRequest::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) +void SubscribeHealthRequest::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) GOOGLE_DCHECK_NE(&from, this); - const SubscribeRcStatusRequest* source = - ::google::protobuf::DynamicCastToGenerated( + const SubscribeHealthRequest* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeHealthRequest) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeHealthRequest) MergeFrom(*source); } } -void SubscribeRcStatusRequest::MergeFrom(const SubscribeRcStatusRequest& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) +void SubscribeHealthRequest::MergeFrom(const SubscribeHealthRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; @@ -7866,34 +8145,34 @@ void SubscribeRcStatusRequest::MergeFrom(const SubscribeRcStatusRequest& from) { } -void SubscribeRcStatusRequest::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) +void SubscribeHealthRequest::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) if (&from == this) return; Clear(); MergeFrom(from); } -void SubscribeRcStatusRequest::CopyFrom(const SubscribeRcStatusRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) +void SubscribeHealthRequest::CopyFrom(const SubscribeHealthRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeHealthRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool SubscribeRcStatusRequest::IsInitialized() const { +bool SubscribeHealthRequest::IsInitialized() const { return true; } -void SubscribeRcStatusRequest::Swap(SubscribeRcStatusRequest* other) { +void SubscribeHealthRequest::Swap(SubscribeHealthRequest* other) { if (other == this) return; InternalSwap(other); } -void SubscribeRcStatusRequest::InternalSwap(SubscribeRcStatusRequest* other) { +void SubscribeHealthRequest::InternalSwap(SubscribeHealthRequest* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); } -::google::protobuf::Metadata SubscribeRcStatusRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeHealthRequest::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -7901,81 +8180,81 @@ ::google::protobuf::Metadata SubscribeRcStatusRequest::GetMetadata() const { // =================================================================== -void RcStatusResponse::InitAsDefaultInstance() { - ::mavsdk::rpc::telemetry::_RcStatusResponse_default_instance_._instance.get_mutable()->rc_status_ = const_cast< ::mavsdk::rpc::telemetry::RcStatus*>( - ::mavsdk::rpc::telemetry::RcStatus::internal_default_instance()); +void HealthResponse::InitAsDefaultInstance() { + ::mavsdk::rpc::telemetry::_HealthResponse_default_instance_._instance.get_mutable()->health_ = const_cast< ::mavsdk::rpc::telemetry::Health*>( + ::mavsdk::rpc::telemetry::Health::internal_default_instance()); } -class RcStatusResponse::HasBitSetters { +class HealthResponse::HasBitSetters { public: - static const ::mavsdk::rpc::telemetry::RcStatus& rc_status(const RcStatusResponse* msg); + static const ::mavsdk::rpc::telemetry::Health& health(const HealthResponse* msg); }; -const ::mavsdk::rpc::telemetry::RcStatus& -RcStatusResponse::HasBitSetters::rc_status(const RcStatusResponse* msg) { - return *msg->rc_status_; +const ::mavsdk::rpc::telemetry::Health& +HealthResponse::HasBitSetters::health(const HealthResponse* msg) { + return *msg->health_; } #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int RcStatusResponse::kRcStatusFieldNumber; +const int HealthResponse::kHealthFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -RcStatusResponse::RcStatusResponse() +HealthResponse::HealthResponse() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.RcStatusResponse) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.HealthResponse) } -RcStatusResponse::RcStatusResponse(const RcStatusResponse& from) +HealthResponse::HealthResponse(const HealthResponse& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - if (from.has_rc_status()) { - rc_status_ = new ::mavsdk::rpc::telemetry::RcStatus(*from.rc_status_); + if (from.has_health()) { + health_ = new ::mavsdk::rpc::telemetry::Health(*from.health_); } else { - rc_status_ = nullptr; + health_ = nullptr; } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.RcStatusResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.HealthResponse) } -void RcStatusResponse::SharedCtor() { +void HealthResponse::SharedCtor() { ::google::protobuf::internal::InitSCC( - &scc_info_RcStatusResponse_telemetry_2ftelemetry_2eproto.base); - rc_status_ = nullptr; + &scc_info_HealthResponse_telemetry_2ftelemetry_2eproto.base); + health_ = nullptr; } -RcStatusResponse::~RcStatusResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.RcStatusResponse) +HealthResponse::~HealthResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.HealthResponse) SharedDtor(); } -void RcStatusResponse::SharedDtor() { - if (this != internal_default_instance()) delete rc_status_; +void HealthResponse::SharedDtor() { + if (this != internal_default_instance()) delete health_; } -void RcStatusResponse::SetCachedSize(int size) const { +void HealthResponse::SetCachedSize(int size) const { _cached_size_.Set(size); } -const RcStatusResponse& RcStatusResponse::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_RcStatusResponse_telemetry_2ftelemetry_2eproto.base); +const HealthResponse& HealthResponse::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_HealthResponse_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void RcStatusResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.RcStatusResponse) +void HealthResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.HealthResponse) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - if (GetArenaNoVirtual() == nullptr && rc_status_ != nullptr) { - delete rc_status_; + if (GetArenaNoVirtual() == nullptr && health_ != nullptr) { + delete health_; } - rc_status_ = nullptr; + health_ = nullptr; _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* RcStatusResponse::_InternalParse(const char* begin, const char* end, void* object, +const char* HealthResponse::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -7985,13 +8264,13 @@ const char* RcStatusResponse::_InternalParse(const char* begin, const char* end, ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; + // .mavsdk.rpc.telemetry.Health health = 1; case 1: { if (static_cast<::google::protobuf::uint8>(tag) != 10) goto handle_unusual; ptr = ::google::protobuf::io::ReadSize(ptr, &size); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - parser_till_end = ::mavsdk::rpc::telemetry::RcStatus::_InternalParse; - object = msg->mutable_rc_status(); + parser_till_end = ::mavsdk::rpc::telemetry::Health::_InternalParse; + object = msg->mutable_health(); if (size > end - ptr) goto len_delim_till_end; ptr += size; GOOGLE_PROTOBUF_PARSER_ASSERT(ctx->ParseExactRange( @@ -8018,21 +8297,21 @@ const char* RcStatusResponse::_InternalParse(const char* begin, const char* end, {parser_till_end, object}, size); } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool RcStatusResponse::MergePartialFromCodedStream( +bool HealthResponse::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.RcStatusResponse) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.HealthResponse) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; + // .mavsdk.rpc.telemetry.Health health = 1; case 1: { if (static_cast< ::google::protobuf::uint8>(tag) == (10 & 0xFF)) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( - input, mutable_rc_status())); + input, mutable_health())); } else { goto handle_unusual; } @@ -8051,57 +8330,57 @@ bool RcStatusResponse::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.RcStatusResponse) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.HealthResponse) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.RcStatusResponse) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.HealthResponse) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void RcStatusResponse::SerializeWithCachedSizes( +void HealthResponse::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.RcStatusResponse) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.HealthResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; - if (this->has_rc_status()) { + // .mavsdk.rpc.telemetry.Health health = 1; + if (this->has_health()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, HasBitSetters::rc_status(this), output); + 1, HasBitSetters::health(this), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.RcStatusResponse) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.HealthResponse) } -::google::protobuf::uint8* RcStatusResponse::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* HealthResponse::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.RcStatusResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.HealthResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; - if (this->has_rc_status()) { + // .mavsdk.rpc.telemetry.Health health = 1; + if (this->has_health()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageToArray( - 1, HasBitSetters::rc_status(this), target); + 1, HasBitSetters::health(this), target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.RcStatusResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.HealthResponse) return target; } -size_t RcStatusResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.RcStatusResponse) +size_t HealthResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.HealthResponse) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -8113,11 +8392,11 @@ size_t RcStatusResponse::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; - if (this->has_rc_status()) { + // .mavsdk.rpc.telemetry.Health health = 1; + if (this->has_health()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSize( - *rc_status_); + *health_); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -8125,62 +8404,62 @@ size_t RcStatusResponse::ByteSizeLong() const { return total_size; } -void RcStatusResponse::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.RcStatusResponse) +void HealthResponse::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.HealthResponse) GOOGLE_DCHECK_NE(&from, this); - const RcStatusResponse* source = - ::google::protobuf::DynamicCastToGenerated( + const HealthResponse* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.RcStatusResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.HealthResponse) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.RcStatusResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.HealthResponse) MergeFrom(*source); } } -void RcStatusResponse::MergeFrom(const RcStatusResponse& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.RcStatusResponse) +void HealthResponse::MergeFrom(const HealthResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.HealthResponse) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.has_rc_status()) { - mutable_rc_status()->::mavsdk::rpc::telemetry::RcStatus::MergeFrom(from.rc_status()); + if (from.has_health()) { + mutable_health()->::mavsdk::rpc::telemetry::Health::MergeFrom(from.health()); } } -void RcStatusResponse::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.RcStatusResponse) +void HealthResponse::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.HealthResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void RcStatusResponse::CopyFrom(const RcStatusResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.RcStatusResponse) +void HealthResponse::CopyFrom(const HealthResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.HealthResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool RcStatusResponse::IsInitialized() const { +bool HealthResponse::IsInitialized() const { return true; } -void RcStatusResponse::Swap(RcStatusResponse* other) { +void HealthResponse::Swap(HealthResponse* other) { if (other == this) return; InternalSwap(other); } -void RcStatusResponse::InternalSwap(RcStatusResponse* other) { +void HealthResponse::InternalSwap(HealthResponse* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(rc_status_, other->rc_status_); + swap(health_, other->health_); } -::google::protobuf::Metadata RcStatusResponse::GetMetadata() const { +::google::protobuf::Metadata HealthResponse::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -8188,49 +8467,49 @@ ::google::protobuf::Metadata RcStatusResponse::GetMetadata() const { // =================================================================== -void SubscribeStatusTextRequest::InitAsDefaultInstance() { +void SubscribeRcStatusRequest::InitAsDefaultInstance() { } -class SubscribeStatusTextRequest::HasBitSetters { +class SubscribeRcStatusRequest::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -SubscribeStatusTextRequest::SubscribeStatusTextRequest() +SubscribeRcStatusRequest::SubscribeRcStatusRequest() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) } -SubscribeStatusTextRequest::SubscribeStatusTextRequest(const SubscribeStatusTextRequest& from) +SubscribeRcStatusRequest::SubscribeRcStatusRequest(const SubscribeRcStatusRequest& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) } -void SubscribeStatusTextRequest::SharedCtor() { +void SubscribeRcStatusRequest::SharedCtor() { } -SubscribeStatusTextRequest::~SubscribeStatusTextRequest() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) +SubscribeRcStatusRequest::~SubscribeRcStatusRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) SharedDtor(); } -void SubscribeStatusTextRequest::SharedDtor() { +void SubscribeRcStatusRequest::SharedDtor() { } -void SubscribeStatusTextRequest::SetCachedSize(int size) const { +void SubscribeRcStatusRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -const SubscribeStatusTextRequest& SubscribeStatusTextRequest::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeStatusTextRequest_telemetry_2ftelemetry_2eproto.base); +const SubscribeRcStatusRequest& SubscribeRcStatusRequest::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeRcStatusRequest_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void SubscribeStatusTextRequest::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) +void SubscribeRcStatusRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; @@ -8239,9 +8518,9 @@ void SubscribeStatusTextRequest::Clear() { } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* SubscribeStatusTextRequest::_InternalParse(const char* begin, const char* end, void* object, +const char* SubscribeRcStatusRequest::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -8267,11 +8546,11 @@ const char* SubscribeStatusTextRequest::_InternalParse(const char* begin, const return ptr; } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool SubscribeStatusTextRequest::MergePartialFromCodedStream( +bool SubscribeRcStatusRequest::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; @@ -8284,18 +8563,18 @@ bool SubscribeStatusTextRequest::MergePartialFromCodedStream( input, tag, _internal_metadata_.mutable_unknown_fields())); } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void SubscribeStatusTextRequest::SerializeWithCachedSizes( +void SubscribeRcStatusRequest::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -8303,12 +8582,12 @@ void SubscribeStatusTextRequest::SerializeWithCachedSizes( ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) } -::google::protobuf::uint8* SubscribeStatusTextRequest::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* SubscribeRcStatusRequest::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; @@ -8316,12 +8595,12 @@ ::google::protobuf::uint8* SubscribeStatusTextRequest::InternalSerializeWithCach target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) return target; } -size_t SubscribeStatusTextRequest::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) +size_t SubscribeRcStatusRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -8338,23 +8617,23 @@ size_t SubscribeStatusTextRequest::ByteSizeLong() const { return total_size; } -void SubscribeStatusTextRequest::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) +void SubscribeRcStatusRequest::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) GOOGLE_DCHECK_NE(&from, this); - const SubscribeStatusTextRequest* source = - ::google::protobuf::DynamicCastToGenerated( + const SubscribeRcStatusRequest* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) MergeFrom(*source); } } -void SubscribeStatusTextRequest::MergeFrom(const SubscribeStatusTextRequest& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) +void SubscribeRcStatusRequest::MergeFrom(const SubscribeRcStatusRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; @@ -8362,34 +8641,34 @@ void SubscribeStatusTextRequest::MergeFrom(const SubscribeStatusTextRequest& fro } -void SubscribeStatusTextRequest::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) +void SubscribeRcStatusRequest::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) if (&from == this) return; Clear(); MergeFrom(from); } -void SubscribeStatusTextRequest::CopyFrom(const SubscribeStatusTextRequest& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) +void SubscribeRcStatusRequest::CopyFrom(const SubscribeRcStatusRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeRcStatusRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool SubscribeStatusTextRequest::IsInitialized() const { +bool SubscribeRcStatusRequest::IsInitialized() const { return true; } -void SubscribeStatusTextRequest::Swap(SubscribeStatusTextRequest* other) { +void SubscribeRcStatusRequest::Swap(SubscribeRcStatusRequest* other) { if (other == this) return; InternalSwap(other); } -void SubscribeStatusTextRequest::InternalSwap(SubscribeStatusTextRequest* other) { +void SubscribeRcStatusRequest::InternalSwap(SubscribeRcStatusRequest* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); } -::google::protobuf::Metadata SubscribeStatusTextRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeRcStatusRequest::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -8397,81 +8676,81 @@ ::google::protobuf::Metadata SubscribeStatusTextRequest::GetMetadata() const { // =================================================================== -void StatusTextResponse::InitAsDefaultInstance() { - ::mavsdk::rpc::telemetry::_StatusTextResponse_default_instance_._instance.get_mutable()->status_text_ = const_cast< ::mavsdk::rpc::telemetry::StatusText*>( - ::mavsdk::rpc::telemetry::StatusText::internal_default_instance()); +void RcStatusResponse::InitAsDefaultInstance() { + ::mavsdk::rpc::telemetry::_RcStatusResponse_default_instance_._instance.get_mutable()->rc_status_ = const_cast< ::mavsdk::rpc::telemetry::RcStatus*>( + ::mavsdk::rpc::telemetry::RcStatus::internal_default_instance()); } -class StatusTextResponse::HasBitSetters { +class RcStatusResponse::HasBitSetters { public: - static const ::mavsdk::rpc::telemetry::StatusText& status_text(const StatusTextResponse* msg); + static const ::mavsdk::rpc::telemetry::RcStatus& rc_status(const RcStatusResponse* msg); }; -const ::mavsdk::rpc::telemetry::StatusText& -StatusTextResponse::HasBitSetters::status_text(const StatusTextResponse* msg) { - return *msg->status_text_; +const ::mavsdk::rpc::telemetry::RcStatus& +RcStatusResponse::HasBitSetters::rc_status(const RcStatusResponse* msg) { + return *msg->rc_status_; } #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int StatusTextResponse::kStatusTextFieldNumber; +const int RcStatusResponse::kRcStatusFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -StatusTextResponse::StatusTextResponse() +RcStatusResponse::RcStatusResponse() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.RcStatusResponse) } -StatusTextResponse::StatusTextResponse(const StatusTextResponse& from) +RcStatusResponse::RcStatusResponse(const RcStatusResponse& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - if (from.has_status_text()) { - status_text_ = new ::mavsdk::rpc::telemetry::StatusText(*from.status_text_); + if (from.has_rc_status()) { + rc_status_ = new ::mavsdk::rpc::telemetry::RcStatus(*from.rc_status_); } else { - status_text_ = nullptr; + rc_status_ = nullptr; } - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.RcStatusResponse) } -void StatusTextResponse::SharedCtor() { +void RcStatusResponse::SharedCtor() { ::google::protobuf::internal::InitSCC( - &scc_info_StatusTextResponse_telemetry_2ftelemetry_2eproto.base); - status_text_ = nullptr; + &scc_info_RcStatusResponse_telemetry_2ftelemetry_2eproto.base); + rc_status_ = nullptr; } -StatusTextResponse::~StatusTextResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.StatusTextResponse) +RcStatusResponse::~RcStatusResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.RcStatusResponse) SharedDtor(); } -void StatusTextResponse::SharedDtor() { - if (this != internal_default_instance()) delete status_text_; +void RcStatusResponse::SharedDtor() { + if (this != internal_default_instance()) delete rc_status_; } -void StatusTextResponse::SetCachedSize(int size) const { +void RcStatusResponse::SetCachedSize(int size) const { _cached_size_.Set(size); } -const StatusTextResponse& StatusTextResponse::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_StatusTextResponse_telemetry_2ftelemetry_2eproto.base); +const RcStatusResponse& RcStatusResponse::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_RcStatusResponse_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void StatusTextResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.StatusTextResponse) +void RcStatusResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.RcStatusResponse) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - if (GetArenaNoVirtual() == nullptr && status_text_ != nullptr) { - delete status_text_; + if (GetArenaNoVirtual() == nullptr && rc_status_ != nullptr) { + delete rc_status_; } - status_text_ = nullptr; + rc_status_ = nullptr; _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* StatusTextResponse::_InternalParse(const char* begin, const char* end, void* object, +const char* RcStatusResponse::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -8481,13 +8760,13 @@ const char* StatusTextResponse::_InternalParse(const char* begin, const char* en ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // .mavsdk.rpc.telemetry.StatusText status_text = 1; + // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; case 1: { if (static_cast<::google::protobuf::uint8>(tag) != 10) goto handle_unusual; ptr = ::google::protobuf::io::ReadSize(ptr, &size); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - parser_till_end = ::mavsdk::rpc::telemetry::StatusText::_InternalParse; - object = msg->mutable_status_text(); + parser_till_end = ::mavsdk::rpc::telemetry::RcStatus::_InternalParse; + object = msg->mutable_rc_status(); if (size > end - ptr) goto len_delim_till_end; ptr += size; GOOGLE_PROTOBUF_PARSER_ASSERT(ctx->ParseExactRange( @@ -8514,21 +8793,21 @@ const char* StatusTextResponse::_InternalParse(const char* begin, const char* en {parser_till_end, object}, size); } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool StatusTextResponse::MergePartialFromCodedStream( +bool RcStatusResponse::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.RcStatusResponse) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // .mavsdk.rpc.telemetry.StatusText status_text = 1; + // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; case 1: { if (static_cast< ::google::protobuf::uint8>(tag) == (10 & 0xFF)) { DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( - input, mutable_status_text())); + input, mutable_rc_status())); } else { goto handle_unusual; } @@ -8547,57 +8826,57 @@ bool StatusTextResponse::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.RcStatusResponse) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.RcStatusResponse) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void StatusTextResponse::SerializeWithCachedSizes( +void RcStatusResponse::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.RcStatusResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.StatusText status_text = 1; - if (this->has_status_text()) { + // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; + if (this->has_rc_status()) { ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, HasBitSetters::status_text(this), output); + 1, HasBitSetters::rc_status(this), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.RcStatusResponse) } -::google::protobuf::uint8* StatusTextResponse::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* RcStatusResponse::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.RcStatusResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.StatusText status_text = 1; - if (this->has_status_text()) { + // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; + if (this->has_rc_status()) { target = ::google::protobuf::internal::WireFormatLite:: InternalWriteMessageToArray( - 1, HasBitSetters::status_text(this), target); + 1, HasBitSetters::rc_status(this), target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.RcStatusResponse) return target; } -size_t StatusTextResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.StatusTextResponse) +size_t RcStatusResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.RcStatusResponse) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -8609,11 +8888,11 @@ size_t StatusTextResponse::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.telemetry.StatusText status_text = 1; - if (this->has_status_text()) { + // .mavsdk.rpc.telemetry.RcStatus rc_status = 1; + if (this->has_rc_status()) { total_size += 1 + ::google::protobuf::internal::WireFormatLite::MessageSize( - *status_text_); + *rc_status_); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -8621,62 +8900,62 @@ size_t StatusTextResponse::ByteSizeLong() const { return total_size; } -void StatusTextResponse::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.StatusTextResponse) +void RcStatusResponse::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.RcStatusResponse) GOOGLE_DCHECK_NE(&from, this); - const StatusTextResponse* source = - ::google::protobuf::DynamicCastToGenerated( + const RcStatusResponse* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.RcStatusResponse) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.StatusTextResponse) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.RcStatusResponse) MergeFrom(*source); } } -void StatusTextResponse::MergeFrom(const StatusTextResponse& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.StatusTextResponse) +void RcStatusResponse::MergeFrom(const RcStatusResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.RcStatusResponse) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.has_status_text()) { - mutable_status_text()->::mavsdk::rpc::telemetry::StatusText::MergeFrom(from.status_text()); + if (from.has_rc_status()) { + mutable_rc_status()->::mavsdk::rpc::telemetry::RcStatus::MergeFrom(from.rc_status()); } } -void StatusTextResponse::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.StatusTextResponse) +void RcStatusResponse::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.RcStatusResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void StatusTextResponse::CopyFrom(const StatusTextResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.StatusTextResponse) +void RcStatusResponse::CopyFrom(const RcStatusResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.RcStatusResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool StatusTextResponse::IsInitialized() const { +bool RcStatusResponse::IsInitialized() const { return true; } -void StatusTextResponse::Swap(StatusTextResponse* other) { +void RcStatusResponse::Swap(RcStatusResponse* other) { if (other == this) return; InternalSwap(other); } -void StatusTextResponse::InternalSwap(StatusTextResponse* other) { +void RcStatusResponse::InternalSwap(RcStatusResponse* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(status_text_, other->status_text_); + swap(rc_status_, other->rc_status_); } -::google::protobuf::Metadata StatusTextResponse::GetMetadata() const { +::google::protobuf::Metadata RcStatusResponse::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -8684,73 +8963,60 @@ ::google::protobuf::Metadata StatusTextResponse::GetMetadata() const { // =================================================================== -void Position::InitAsDefaultInstance() { +void SubscribeStatusTextRequest::InitAsDefaultInstance() { } -class Position::HasBitSetters { +class SubscribeStatusTextRequest::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int Position::kLatitudeDegFieldNumber; -const int Position::kLongitudeDegFieldNumber; -const int Position::kAbsoluteAltitudeMFieldNumber; -const int Position::kRelativeAltitudeMFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -Position::Position() +SubscribeStatusTextRequest::SubscribeStatusTextRequest() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.Position) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) } -Position::Position(const Position& from) +SubscribeStatusTextRequest::SubscribeStatusTextRequest(const SubscribeStatusTextRequest& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - ::memcpy(&latitude_deg_, &from.latitude_deg_, - static_cast(reinterpret_cast(&relative_altitude_m_) - - reinterpret_cast(&latitude_deg_)) + sizeof(relative_altitude_m_)); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.Position) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) } -void Position::SharedCtor() { - ::memset(&latitude_deg_, 0, static_cast( - reinterpret_cast(&relative_altitude_m_) - - reinterpret_cast(&latitude_deg_)) + sizeof(relative_altitude_m_)); +void SubscribeStatusTextRequest::SharedCtor() { } -Position::~Position() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.Position) +SubscribeStatusTextRequest::~SubscribeStatusTextRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) SharedDtor(); } -void Position::SharedDtor() { +void SubscribeStatusTextRequest::SharedDtor() { } -void Position::SetCachedSize(int size) const { +void SubscribeStatusTextRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -const Position& Position::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_Position_telemetry_2ftelemetry_2eproto.base); +const SubscribeStatusTextRequest& SubscribeStatusTextRequest::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeStatusTextRequest_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void Position::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.Position) +void SubscribeStatusTextRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&latitude_deg_, 0, static_cast( - reinterpret_cast(&relative_altitude_m_) - - reinterpret_cast(&latitude_deg_)) + sizeof(relative_altitude_m_)); _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* Position::_InternalParse(const char* begin, const char* end, void* object, +const char* SubscribeStatusTextRequest::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -8760,36 +9026,7 @@ const char* Position::_InternalParse(const char* begin, const char* end, void* o ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // double latitude_deg = 1; - case 1: { - if (static_cast<::google::protobuf::uint8>(tag) != 9) goto handle_unusual; - msg->set_latitude_deg(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(double); - break; - } - // double longitude_deg = 2; - case 2: { - if (static_cast<::google::protobuf::uint8>(tag) != 17) goto handle_unusual; - msg->set_longitude_deg(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(double); - break; - } - // float absolute_altitude_m = 3; - case 3: { - if (static_cast<::google::protobuf::uint8>(tag) != 29) goto handle_unusual; - msg->set_absolute_altitude_m(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(float); - break; - } - // float relative_altitude_m = 4; - case 4: { - if (static_cast<::google::protobuf::uint8>(tag) != 37) goto handle_unusual; - msg->set_relative_altitude_m(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(float); - break; - } default: { - handle_unusual: if ((tag & 7) == 4 || tag == 0) { ctx->EndGroup(tag); return ptr; @@ -8805,158 +9042,61 @@ const char* Position::_InternalParse(const char* begin, const char* end, void* o return ptr; } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool Position::MergePartialFromCodedStream( +bool SubscribeStatusTextRequest::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.Position) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // double latitude_deg = 1; - case 1: { - if (static_cast< ::google::protobuf::uint8>(tag) == (9 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &latitude_deg_))); - } else { - goto handle_unusual; - } - break; - } - - // double longitude_deg = 2; - case 2: { - if (static_cast< ::google::protobuf::uint8>(tag) == (17 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &longitude_deg_))); - } else { - goto handle_unusual; - } - break; - } - - // float absolute_altitude_m = 3; - case 3: { - if (static_cast< ::google::protobuf::uint8>(tag) == (29 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &absolute_altitude_m_))); - } else { - goto handle_unusual; - } - break; - } - - // float relative_altitude_m = 4; - case 4: { - if (static_cast< ::google::protobuf::uint8>(tag) == (37 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &relative_altitude_m_))); - } else { - goto handle_unusual; - } - break; - } - - default: { - handle_unusual: - if (tag == 0) { - goto success; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, _internal_metadata_.mutable_unknown_fields())); - break; - } + handle_unusual: + if (tag == 0) { + goto success; } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.Position) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.Position) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void Position::SerializeWithCachedSizes( +void SubscribeStatusTextRequest::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.Position) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // double latitude_deg = 1; - if (this->latitude_deg() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->latitude_deg(), output); - } - - // double longitude_deg = 2; - if (this->longitude_deg() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->longitude_deg(), output); - } - - // float absolute_altitude_m = 3; - if (this->absolute_altitude_m() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->absolute_altitude_m(), output); - } - - // float relative_altitude_m = 4; - if (this->relative_altitude_m() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->relative_altitude_m(), output); - } - if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.Position) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) } -::google::protobuf::uint8* Position::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* SubscribeStatusTextRequest::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.Position) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // double latitude_deg = 1; - if (this->latitude_deg() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->latitude_deg(), target); - } - - // double longitude_deg = 2; - if (this->longitude_deg() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->longitude_deg(), target); - } - - // float absolute_altitude_m = 3; - if (this->absolute_altitude_m() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->absolute_altitude_m(), target); - } - - // float relative_altitude_m = 4; - if (this->relative_altitude_m() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->relative_altitude_m(), target); - } - if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.Position) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) return target; } -size_t Position::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.Position) +size_t SubscribeStatusTextRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -8968,99 +9108,63 @@ size_t Position::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // double latitude_deg = 1; - if (this->latitude_deg() != 0) { - total_size += 1 + 8; - } - - // double longitude_deg = 2; - if (this->longitude_deg() != 0) { - total_size += 1 + 8; - } - - // float absolute_altitude_m = 3; - if (this->absolute_altitude_m() != 0) { - total_size += 1 + 4; - } - - // float relative_altitude_m = 4; - if (this->relative_altitude_m() != 0) { - total_size += 1 + 4; - } - int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); SetCachedSize(cached_size); return total_size; } -void Position::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.Position) +void SubscribeStatusTextRequest::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) GOOGLE_DCHECK_NE(&from, this); - const Position* source = - ::google::protobuf::DynamicCastToGenerated( + const SubscribeStatusTextRequest* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.Position) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.Position) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) MergeFrom(*source); } } -void Position::MergeFrom(const Position& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.Position) +void SubscribeStatusTextRequest::MergeFrom(const SubscribeStatusTextRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.latitude_deg() != 0) { - set_latitude_deg(from.latitude_deg()); - } - if (from.longitude_deg() != 0) { - set_longitude_deg(from.longitude_deg()); - } - if (from.absolute_altitude_m() != 0) { - set_absolute_altitude_m(from.absolute_altitude_m()); - } - if (from.relative_altitude_m() != 0) { - set_relative_altitude_m(from.relative_altitude_m()); - } } -void Position::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.Position) +void SubscribeStatusTextRequest::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) if (&from == this) return; Clear(); MergeFrom(from); } -void Position::CopyFrom(const Position& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.Position) +void SubscribeStatusTextRequest::CopyFrom(const SubscribeStatusTextRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeStatusTextRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool Position::IsInitialized() const { +bool SubscribeStatusTextRequest::IsInitialized() const { return true; } -void Position::Swap(Position* other) { +void SubscribeStatusTextRequest::Swap(SubscribeStatusTextRequest* other) { if (other == this) return; InternalSwap(other); } -void Position::InternalSwap(Position* other) { +void SubscribeStatusTextRequest::InternalSwap(SubscribeStatusTextRequest* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(latitude_deg_, other->latitude_deg_); - swap(longitude_deg_, other->longitude_deg_); - swap(absolute_altitude_m_, other->absolute_altitude_m_); - swap(relative_altitude_m_, other->relative_altitude_m_); } -::google::protobuf::Metadata Position::GetMetadata() const { +::google::protobuf::Metadata SubscribeStatusTextRequest::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -9068,73 +9172,81 @@ ::google::protobuf::Metadata Position::GetMetadata() const { // =================================================================== -void Quaternion::InitAsDefaultInstance() { +void StatusTextResponse::InitAsDefaultInstance() { + ::mavsdk::rpc::telemetry::_StatusTextResponse_default_instance_._instance.get_mutable()->status_text_ = const_cast< ::mavsdk::rpc::telemetry::StatusText*>( + ::mavsdk::rpc::telemetry::StatusText::internal_default_instance()); } -class Quaternion::HasBitSetters { +class StatusTextResponse::HasBitSetters { public: + static const ::mavsdk::rpc::telemetry::StatusText& status_text(const StatusTextResponse* msg); }; +const ::mavsdk::rpc::telemetry::StatusText& +StatusTextResponse::HasBitSetters::status_text(const StatusTextResponse* msg) { + return *msg->status_text_; +} #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int Quaternion::kWFieldNumber; -const int Quaternion::kXFieldNumber; -const int Quaternion::kYFieldNumber; -const int Quaternion::kZFieldNumber; +const int StatusTextResponse::kStatusTextFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -Quaternion::Quaternion() +StatusTextResponse::StatusTextResponse() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.Quaternion) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.StatusTextResponse) } -Quaternion::Quaternion(const Quaternion& from) +StatusTextResponse::StatusTextResponse(const StatusTextResponse& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - ::memcpy(&w_, &from.w_, - static_cast(reinterpret_cast(&z_) - - reinterpret_cast(&w_)) + sizeof(z_)); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.Quaternion) + if (from.has_status_text()) { + status_text_ = new ::mavsdk::rpc::telemetry::StatusText(*from.status_text_); + } else { + status_text_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.StatusTextResponse) } -void Quaternion::SharedCtor() { - ::memset(&w_, 0, static_cast( - reinterpret_cast(&z_) - - reinterpret_cast(&w_)) + sizeof(z_)); +void StatusTextResponse::SharedCtor() { + ::google::protobuf::internal::InitSCC( + &scc_info_StatusTextResponse_telemetry_2ftelemetry_2eproto.base); + status_text_ = nullptr; } -Quaternion::~Quaternion() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.Quaternion) +StatusTextResponse::~StatusTextResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.StatusTextResponse) SharedDtor(); } -void Quaternion::SharedDtor() { +void StatusTextResponse::SharedDtor() { + if (this != internal_default_instance()) delete status_text_; } -void Quaternion::SetCachedSize(int size) const { +void StatusTextResponse::SetCachedSize(int size) const { _cached_size_.Set(size); } -const Quaternion& Quaternion::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_Quaternion_telemetry_2ftelemetry_2eproto.base); +const StatusTextResponse& StatusTextResponse::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_StatusTextResponse_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void Quaternion::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.Quaternion) +void StatusTextResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.StatusTextResponse) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&w_, 0, static_cast( - reinterpret_cast(&z_) - - reinterpret_cast(&w_)) + sizeof(z_)); + if (GetArenaNoVirtual() == nullptr && status_text_ != nullptr) { + delete status_text_; + } + status_text_ = nullptr; _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* Quaternion::_InternalParse(const char* begin, const char* end, void* object, +const char* StatusTextResponse::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -9144,32 +9256,17 @@ const char* Quaternion::_InternalParse(const char* begin, const char* end, void* ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // float w = 1; + // .mavsdk.rpc.telemetry.StatusText status_text = 1; case 1: { - if (static_cast<::google::protobuf::uint8>(tag) != 13) goto handle_unusual; - msg->set_w(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(float); - break; - } - // float x = 2; - case 2: { - if (static_cast<::google::protobuf::uint8>(tag) != 21) goto handle_unusual; - msg->set_x(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(float); - break; - } - // float y = 3; - case 3: { - if (static_cast<::google::protobuf::uint8>(tag) != 29) goto handle_unusual; - msg->set_y(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(float); - break; - } - // float z = 4; - case 4: { - if (static_cast<::google::protobuf::uint8>(tag) != 37) goto handle_unusual; - msg->set_z(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(float); + if (static_cast<::google::protobuf::uint8>(tag) != 10) goto handle_unusual; + ptr = ::google::protobuf::io::ReadSize(ptr, &size); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + parser_till_end = ::mavsdk::rpc::telemetry::StatusText::_InternalParse; + object = msg->mutable_status_text(); + if (size > end - ptr) goto len_delim_till_end; + ptr += size; + GOOGLE_PROTOBUF_PARSER_ASSERT(ctx->ParseExactRange( + {parser_till_end, object}, ptr - size, ptr)); break; } default: { @@ -9187,64 +9284,26 @@ const char* Quaternion::_InternalParse(const char* begin, const char* end, void* } // switch } // while return ptr; +len_delim_till_end: + return ctx->StoreAndTailCall(ptr, end, {_InternalParse, msg}, + {parser_till_end, object}, size); } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool Quaternion::MergePartialFromCodedStream( +bool StatusTextResponse::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.Quaternion) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.StatusTextResponse) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // float w = 1; + // .mavsdk.rpc.telemetry.StatusText status_text = 1; case 1: { - if (static_cast< ::google::protobuf::uint8>(tag) == (13 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &w_))); - } else { - goto handle_unusual; - } - break; - } - - // float x = 2; - case 2: { - if (static_cast< ::google::protobuf::uint8>(tag) == (21 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &x_))); - } else { - goto handle_unusual; - } - break; - } - - // float y = 3; - case 3: { - if (static_cast< ::google::protobuf::uint8>(tag) == (29 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &y_))); - } else { - goto handle_unusual; - } - break; - } - - // float z = 4; - case 4: { - if (static_cast< ::google::protobuf::uint8>(tag) == (37 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &z_))); + if (static_cast< ::google::protobuf::uint8>(tag) == (10 & 0xFF)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_status_text())); } else { goto handle_unusual; } @@ -9263,84 +9322,57 @@ bool Quaternion::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.Quaternion) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.StatusTextResponse) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.Quaternion) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.StatusTextResponse) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void Quaternion::SerializeWithCachedSizes( +void StatusTextResponse::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.Quaternion) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.StatusTextResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // float w = 1; - if (this->w() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->w(), output); - } - - // float x = 2; - if (this->x() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->x(), output); - } - - // float y = 3; - if (this->y() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->y(), output); - } - - // float z = 4; - if (this->z() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->z(), output); + // .mavsdk.rpc.telemetry.StatusText status_text = 1; + if (this->has_status_text()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, HasBitSetters::status_text(this), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.Quaternion) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.StatusTextResponse) } -::google::protobuf::uint8* Quaternion::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* StatusTextResponse::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.Quaternion) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.StatusTextResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // float w = 1; - if (this->w() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->w(), target); - } - - // float x = 2; - if (this->x() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->x(), target); - } - - // float y = 3; - if (this->y() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->y(), target); - } - - // float z = 4; - if (this->z() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->z(), target); + // .mavsdk.rpc.telemetry.StatusText status_text = 1; + if (this->has_status_text()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, HasBitSetters::status_text(this), target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.Quaternion) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.StatusTextResponse) return target; } -size_t Quaternion::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.Quaternion) +size_t StatusTextResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.StatusTextResponse) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -9352,24 +9384,11 @@ size_t Quaternion::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float w = 1; - if (this->w() != 0) { - total_size += 1 + 4; - } - - // float x = 2; - if (this->x() != 0) { - total_size += 1 + 4; - } - - // float y = 3; - if (this->y() != 0) { - total_size += 1 + 4; - } - - // float z = 4; - if (this->z() != 0) { - total_size += 1 + 4; + // .mavsdk.rpc.telemetry.StatusText status_text = 1; + if (this->has_status_text()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *status_text_); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -9377,74 +9396,62 @@ size_t Quaternion::ByteSizeLong() const { return total_size; } -void Quaternion::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.Quaternion) +void StatusTextResponse::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.StatusTextResponse) GOOGLE_DCHECK_NE(&from, this); - const Quaternion* source = - ::google::protobuf::DynamicCastToGenerated( + const StatusTextResponse* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.Quaternion) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.StatusTextResponse) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.Quaternion) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.StatusTextResponse) MergeFrom(*source); } } -void Quaternion::MergeFrom(const Quaternion& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.Quaternion) +void StatusTextResponse::MergeFrom(const StatusTextResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.StatusTextResponse) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.w() != 0) { - set_w(from.w()); - } - if (from.x() != 0) { - set_x(from.x()); - } - if (from.y() != 0) { - set_y(from.y()); - } - if (from.z() != 0) { - set_z(from.z()); + if (from.has_status_text()) { + mutable_status_text()->::mavsdk::rpc::telemetry::StatusText::MergeFrom(from.status_text()); } } -void Quaternion::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.Quaternion) +void StatusTextResponse::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.StatusTextResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void Quaternion::CopyFrom(const Quaternion& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.Quaternion) +void StatusTextResponse::CopyFrom(const StatusTextResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.StatusTextResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool Quaternion::IsInitialized() const { +bool StatusTextResponse::IsInitialized() const { return true; } -void Quaternion::Swap(Quaternion* other) { +void StatusTextResponse::Swap(StatusTextResponse* other) { if (other == this) return; InternalSwap(other); } -void Quaternion::InternalSwap(Quaternion* other) { +void StatusTextResponse::InternalSwap(StatusTextResponse* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(w_, other->w_); - swap(x_, other->x_); - swap(y_, other->y_); - swap(z_, other->z_); + swap(status_text_, other->status_text_); } -::google::protobuf::Metadata Quaternion::GetMetadata() const { +::google::protobuf::Metadata StatusTextResponse::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -9452,72 +9459,60 @@ ::google::protobuf::Metadata Quaternion::GetMetadata() const { // =================================================================== -void EulerAngle::InitAsDefaultInstance() { +void SubscribeActuatorControlTargetRequest::InitAsDefaultInstance() { } -class EulerAngle::HasBitSetters { +class SubscribeActuatorControlTargetRequest::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int EulerAngle::kRollDegFieldNumber; -const int EulerAngle::kPitchDegFieldNumber; -const int EulerAngle::kYawDegFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -EulerAngle::EulerAngle() +SubscribeActuatorControlTargetRequest::SubscribeActuatorControlTargetRequest() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.EulerAngle) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) } -EulerAngle::EulerAngle(const EulerAngle& from) +SubscribeActuatorControlTargetRequest::SubscribeActuatorControlTargetRequest(const SubscribeActuatorControlTargetRequest& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - ::memcpy(&roll_deg_, &from.roll_deg_, - static_cast(reinterpret_cast(&yaw_deg_) - - reinterpret_cast(&roll_deg_)) + sizeof(yaw_deg_)); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.EulerAngle) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) } -void EulerAngle::SharedCtor() { - ::memset(&roll_deg_, 0, static_cast( - reinterpret_cast(&yaw_deg_) - - reinterpret_cast(&roll_deg_)) + sizeof(yaw_deg_)); +void SubscribeActuatorControlTargetRequest::SharedCtor() { } -EulerAngle::~EulerAngle() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.EulerAngle) +SubscribeActuatorControlTargetRequest::~SubscribeActuatorControlTargetRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) SharedDtor(); } -void EulerAngle::SharedDtor() { +void SubscribeActuatorControlTargetRequest::SharedDtor() { } -void EulerAngle::SetCachedSize(int size) const { +void SubscribeActuatorControlTargetRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -const EulerAngle& EulerAngle::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_EulerAngle_telemetry_2ftelemetry_2eproto.base); +const SubscribeActuatorControlTargetRequest& SubscribeActuatorControlTargetRequest::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeActuatorControlTargetRequest_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void EulerAngle::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.EulerAngle) +void SubscribeActuatorControlTargetRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&roll_deg_, 0, static_cast( - reinterpret_cast(&yaw_deg_) - - reinterpret_cast(&roll_deg_)) + sizeof(yaw_deg_)); _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* EulerAngle::_InternalParse(const char* begin, const char* end, void* object, +const char* SubscribeActuatorControlTargetRequest::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -9527,29 +9522,7 @@ const char* EulerAngle::_InternalParse(const char* begin, const char* end, void* ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // float roll_deg = 1; - case 1: { - if (static_cast<::google::protobuf::uint8>(tag) != 13) goto handle_unusual; - msg->set_roll_deg(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(float); - break; - } - // float pitch_deg = 2; - case 2: { - if (static_cast<::google::protobuf::uint8>(tag) != 21) goto handle_unusual; - msg->set_pitch_deg(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(float); - break; - } - // float yaw_deg = 3; - case 3: { - if (static_cast<::google::protobuf::uint8>(tag) != 29) goto handle_unusual; - msg->set_yaw_deg(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(float); - break; - } default: { - handle_unusual: if ((tag & 7) == 4 || tag == 0) { ctx->EndGroup(tag); return ptr; @@ -9565,135 +9538,61 @@ const char* EulerAngle::_InternalParse(const char* begin, const char* end, void* return ptr; } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool EulerAngle::MergePartialFromCodedStream( +bool SubscribeActuatorControlTargetRequest::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.EulerAngle) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // float roll_deg = 1; - case 1: { - if (static_cast< ::google::protobuf::uint8>(tag) == (13 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &roll_deg_))); - } else { - goto handle_unusual; - } - break; - } - - // float pitch_deg = 2; - case 2: { - if (static_cast< ::google::protobuf::uint8>(tag) == (21 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &pitch_deg_))); - } else { - goto handle_unusual; - } - break; - } - - // float yaw_deg = 3; - case 3: { - if (static_cast< ::google::protobuf::uint8>(tag) == (29 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &yaw_deg_))); - } else { - goto handle_unusual; - } - break; - } - - default: { - handle_unusual: - if (tag == 0) { - goto success; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, _internal_metadata_.mutable_unknown_fields())); - break; - } + handle_unusual: + if (tag == 0) { + goto success; } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.EulerAngle) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.EulerAngle) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void EulerAngle::SerializeWithCachedSizes( +void SubscribeActuatorControlTargetRequest::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.EulerAngle) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // float roll_deg = 1; - if (this->roll_deg() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->roll_deg(), output); - } - - // float pitch_deg = 2; - if (this->pitch_deg() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->pitch_deg(), output); - } - - // float yaw_deg = 3; - if (this->yaw_deg() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->yaw_deg(), output); - } - if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.EulerAngle) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) } -::google::protobuf::uint8* EulerAngle::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* SubscribeActuatorControlTargetRequest::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.EulerAngle) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // float roll_deg = 1; - if (this->roll_deg() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->roll_deg(), target); - } - - // float pitch_deg = 2; - if (this->pitch_deg() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->pitch_deg(), target); - } - - // float yaw_deg = 3; - if (this->yaw_deg() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->yaw_deg(), target); - } - if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.EulerAngle) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) return target; } -size_t EulerAngle::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.EulerAngle) +size_t SubscribeActuatorControlTargetRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -9705,90 +9604,63 @@ size_t EulerAngle::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float roll_deg = 1; - if (this->roll_deg() != 0) { - total_size += 1 + 4; - } - - // float pitch_deg = 2; - if (this->pitch_deg() != 0) { - total_size += 1 + 4; - } - - // float yaw_deg = 3; - if (this->yaw_deg() != 0) { - total_size += 1 + 4; - } - int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); SetCachedSize(cached_size); return total_size; } -void EulerAngle::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.EulerAngle) +void SubscribeActuatorControlTargetRequest::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) GOOGLE_DCHECK_NE(&from, this); - const EulerAngle* source = - ::google::protobuf::DynamicCastToGenerated( + const SubscribeActuatorControlTargetRequest* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.EulerAngle) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.EulerAngle) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) MergeFrom(*source); } } -void EulerAngle::MergeFrom(const EulerAngle& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.EulerAngle) +void SubscribeActuatorControlTargetRequest::MergeFrom(const SubscribeActuatorControlTargetRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.roll_deg() != 0) { - set_roll_deg(from.roll_deg()); - } - if (from.pitch_deg() != 0) { - set_pitch_deg(from.pitch_deg()); - } - if (from.yaw_deg() != 0) { - set_yaw_deg(from.yaw_deg()); - } } -void EulerAngle::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.EulerAngle) +void SubscribeActuatorControlTargetRequest::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) if (&from == this) return; Clear(); MergeFrom(from); } -void EulerAngle::CopyFrom(const EulerAngle& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.EulerAngle) +void SubscribeActuatorControlTargetRequest::CopyFrom(const SubscribeActuatorControlTargetRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) if (&from == this) return; Clear(); MergeFrom(from); } -bool EulerAngle::IsInitialized() const { +bool SubscribeActuatorControlTargetRequest::IsInitialized() const { return true; } -void EulerAngle::Swap(EulerAngle* other) { +void SubscribeActuatorControlTargetRequest::Swap(SubscribeActuatorControlTargetRequest* other) { if (other == this) return; InternalSwap(other); } -void EulerAngle::InternalSwap(EulerAngle* other) { +void SubscribeActuatorControlTargetRequest::InternalSwap(SubscribeActuatorControlTargetRequest* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(roll_deg_, other->roll_deg_); - swap(pitch_deg_, other->pitch_deg_); - swap(yaw_deg_, other->yaw_deg_); } -::google::protobuf::Metadata EulerAngle::GetMetadata() const { +::google::protobuf::Metadata SubscribeActuatorControlTargetRequest::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -9796,72 +9668,81 @@ ::google::protobuf::Metadata EulerAngle::GetMetadata() const { // =================================================================== -void SpeedNed::InitAsDefaultInstance() { +void ActuatorControlTargetResponse::InitAsDefaultInstance() { + ::mavsdk::rpc::telemetry::_ActuatorControlTargetResponse_default_instance_._instance.get_mutable()->actuator_control_target_ = const_cast< ::mavsdk::rpc::telemetry::ActuatorControlTarget*>( + ::mavsdk::rpc::telemetry::ActuatorControlTarget::internal_default_instance()); } -class SpeedNed::HasBitSetters { +class ActuatorControlTargetResponse::HasBitSetters { public: + static const ::mavsdk::rpc::telemetry::ActuatorControlTarget& actuator_control_target(const ActuatorControlTargetResponse* msg); }; +const ::mavsdk::rpc::telemetry::ActuatorControlTarget& +ActuatorControlTargetResponse::HasBitSetters::actuator_control_target(const ActuatorControlTargetResponse* msg) { + return *msg->actuator_control_target_; +} #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int SpeedNed::kVelocityNorthMSFieldNumber; -const int SpeedNed::kVelocityEastMSFieldNumber; -const int SpeedNed::kVelocityDownMSFieldNumber; +const int ActuatorControlTargetResponse::kActuatorControlTargetFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -SpeedNed::SpeedNed() +ActuatorControlTargetResponse::ActuatorControlTargetResponse() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SpeedNed) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) } -SpeedNed::SpeedNed(const SpeedNed& from) +ActuatorControlTargetResponse::ActuatorControlTargetResponse(const ActuatorControlTargetResponse& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - ::memcpy(&velocity_north_m_s_, &from.velocity_north_m_s_, - static_cast(reinterpret_cast(&velocity_down_m_s_) - - reinterpret_cast(&velocity_north_m_s_)) + sizeof(velocity_down_m_s_)); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SpeedNed) + if (from.has_actuator_control_target()) { + actuator_control_target_ = new ::mavsdk::rpc::telemetry::ActuatorControlTarget(*from.actuator_control_target_); + } else { + actuator_control_target_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) } -void SpeedNed::SharedCtor() { - ::memset(&velocity_north_m_s_, 0, static_cast( - reinterpret_cast(&velocity_down_m_s_) - - reinterpret_cast(&velocity_north_m_s_)) + sizeof(velocity_down_m_s_)); +void ActuatorControlTargetResponse::SharedCtor() { + ::google::protobuf::internal::InitSCC( + &scc_info_ActuatorControlTargetResponse_telemetry_2ftelemetry_2eproto.base); + actuator_control_target_ = nullptr; } -SpeedNed::~SpeedNed() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SpeedNed) +ActuatorControlTargetResponse::~ActuatorControlTargetResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) SharedDtor(); } -void SpeedNed::SharedDtor() { +void ActuatorControlTargetResponse::SharedDtor() { + if (this != internal_default_instance()) delete actuator_control_target_; } -void SpeedNed::SetCachedSize(int size) const { +void ActuatorControlTargetResponse::SetCachedSize(int size) const { _cached_size_.Set(size); } -const SpeedNed& SpeedNed::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_SpeedNed_telemetry_2ftelemetry_2eproto.base); +const ActuatorControlTargetResponse& ActuatorControlTargetResponse::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_ActuatorControlTargetResponse_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void SpeedNed::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SpeedNed) +void ActuatorControlTargetResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&velocity_north_m_s_, 0, static_cast( - reinterpret_cast(&velocity_down_m_s_) - - reinterpret_cast(&velocity_north_m_s_)) + sizeof(velocity_down_m_s_)); + if (GetArenaNoVirtual() == nullptr && actuator_control_target_ != nullptr) { + delete actuator_control_target_; + } + actuator_control_target_ = nullptr; _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* SpeedNed::_InternalParse(const char* begin, const char* end, void* object, +const char* ActuatorControlTargetResponse::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -9871,25 +9752,17 @@ const char* SpeedNed::_InternalParse(const char* begin, const char* end, void* o ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // float velocity_north_m_s = 1; + // .mavsdk.rpc.telemetry.ActuatorControlTarget actuator_control_target = 1; case 1: { - if (static_cast<::google::protobuf::uint8>(tag) != 13) goto handle_unusual; - msg->set_velocity_north_m_s(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(float); - break; - } - // float velocity_east_m_s = 2; - case 2: { - if (static_cast<::google::protobuf::uint8>(tag) != 21) goto handle_unusual; - msg->set_velocity_east_m_s(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(float); - break; - } - // float velocity_down_m_s = 3; - case 3: { - if (static_cast<::google::protobuf::uint8>(tag) != 29) goto handle_unusual; - msg->set_velocity_down_m_s(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(float); + if (static_cast<::google::protobuf::uint8>(tag) != 10) goto handle_unusual; + ptr = ::google::protobuf::io::ReadSize(ptr, &size); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + parser_till_end = ::mavsdk::rpc::telemetry::ActuatorControlTarget::_InternalParse; + object = msg->mutable_actuator_control_target(); + if (size > end - ptr) goto len_delim_till_end; + ptr += size; + GOOGLE_PROTOBUF_PARSER_ASSERT(ctx->ParseExactRange( + {parser_till_end, object}, ptr - size, ptr)); break; } default: { @@ -9907,51 +9780,26 @@ const char* SpeedNed::_InternalParse(const char* begin, const char* end, void* o } // switch } // while return ptr; +len_delim_till_end: + return ctx->StoreAndTailCall(ptr, end, {_InternalParse, msg}, + {parser_till_end, object}, size); } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool SpeedNed::MergePartialFromCodedStream( +bool ActuatorControlTargetResponse::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SpeedNed) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // float velocity_north_m_s = 1; + // .mavsdk.rpc.telemetry.ActuatorControlTarget actuator_control_target = 1; case 1: { - if (static_cast< ::google::protobuf::uint8>(tag) == (13 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &velocity_north_m_s_))); - } else { - goto handle_unusual; - } - break; - } - - // float velocity_east_m_s = 2; - case 2: { - if (static_cast< ::google::protobuf::uint8>(tag) == (21 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &velocity_east_m_s_))); - } else { - goto handle_unusual; - } - break; - } - - // float velocity_down_m_s = 3; - case 3: { - if (static_cast< ::google::protobuf::uint8>(tag) == (29 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &velocity_down_m_s_))); + if (static_cast< ::google::protobuf::uint8>(tag) == (10 & 0xFF)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_actuator_control_target())); } else { goto handle_unusual; } @@ -9970,74 +9818,57 @@ bool SpeedNed::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SpeedNed) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SpeedNed) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void SpeedNed::SerializeWithCachedSizes( +void ActuatorControlTargetResponse::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SpeedNed) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // float velocity_north_m_s = 1; - if (this->velocity_north_m_s() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->velocity_north_m_s(), output); - } - - // float velocity_east_m_s = 2; - if (this->velocity_east_m_s() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->velocity_east_m_s(), output); - } - - // float velocity_down_m_s = 3; - if (this->velocity_down_m_s() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->velocity_down_m_s(), output); + // .mavsdk.rpc.telemetry.ActuatorControlTarget actuator_control_target = 1; + if (this->has_actuator_control_target()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, HasBitSetters::actuator_control_target(this), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SpeedNed) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) } -::google::protobuf::uint8* SpeedNed::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* ActuatorControlTargetResponse::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SpeedNed) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // float velocity_north_m_s = 1; - if (this->velocity_north_m_s() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->velocity_north_m_s(), target); - } - - // float velocity_east_m_s = 2; - if (this->velocity_east_m_s() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->velocity_east_m_s(), target); - } - - // float velocity_down_m_s = 3; - if (this->velocity_down_m_s() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->velocity_down_m_s(), target); + // .mavsdk.rpc.telemetry.ActuatorControlTarget actuator_control_target = 1; + if (this->has_actuator_control_target()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, HasBitSetters::actuator_control_target(this), target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SpeedNed) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) return target; } -size_t SpeedNed::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SpeedNed) +size_t ActuatorControlTargetResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -10049,19 +9880,11 @@ size_t SpeedNed::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float velocity_north_m_s = 1; - if (this->velocity_north_m_s() != 0) { - total_size += 1 + 4; - } - - // float velocity_east_m_s = 2; - if (this->velocity_east_m_s() != 0) { - total_size += 1 + 4; - } - - // float velocity_down_m_s = 3; - if (this->velocity_down_m_s() != 0) { - total_size += 1 + 4; + // .mavsdk.rpc.telemetry.ActuatorControlTarget actuator_control_target = 1; + if (this->has_actuator_control_target()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *actuator_control_target_); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -10069,70 +9892,62 @@ size_t SpeedNed::ByteSizeLong() const { return total_size; } -void SpeedNed::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SpeedNed) +void ActuatorControlTargetResponse::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) GOOGLE_DCHECK_NE(&from, this); - const SpeedNed* source = - ::google::protobuf::DynamicCastToGenerated( + const ActuatorControlTargetResponse* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SpeedNed) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SpeedNed) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) MergeFrom(*source); } } -void SpeedNed::MergeFrom(const SpeedNed& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SpeedNed) +void ActuatorControlTargetResponse::MergeFrom(const ActuatorControlTargetResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.velocity_north_m_s() != 0) { - set_velocity_north_m_s(from.velocity_north_m_s()); - } - if (from.velocity_east_m_s() != 0) { - set_velocity_east_m_s(from.velocity_east_m_s()); - } - if (from.velocity_down_m_s() != 0) { - set_velocity_down_m_s(from.velocity_down_m_s()); + if (from.has_actuator_control_target()) { + mutable_actuator_control_target()->::mavsdk::rpc::telemetry::ActuatorControlTarget::MergeFrom(from.actuator_control_target()); } } -void SpeedNed::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SpeedNed) +void ActuatorControlTargetResponse::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) if (&from == this) return; Clear(); MergeFrom(from); } -void SpeedNed::CopyFrom(const SpeedNed& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SpeedNed) +void ActuatorControlTargetResponse::CopyFrom(const ActuatorControlTargetResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) if (&from == this) return; Clear(); MergeFrom(from); } -bool SpeedNed::IsInitialized() const { +bool ActuatorControlTargetResponse::IsInitialized() const { return true; } -void SpeedNed::Swap(SpeedNed* other) { +void ActuatorControlTargetResponse::Swap(ActuatorControlTargetResponse* other) { if (other == this) return; InternalSwap(other); } -void SpeedNed::InternalSwap(SpeedNed* other) { +void ActuatorControlTargetResponse::InternalSwap(ActuatorControlTargetResponse* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(velocity_north_m_s_, other->velocity_north_m_s_); - swap(velocity_east_m_s_, other->velocity_east_m_s_); - swap(velocity_down_m_s_, other->velocity_down_m_s_); + swap(actuator_control_target_, other->actuator_control_target_); } -::google::protobuf::Metadata SpeedNed::GetMetadata() const { +::google::protobuf::Metadata ActuatorControlTargetResponse::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -10140,71 +9955,60 @@ ::google::protobuf::Metadata SpeedNed::GetMetadata() const { // =================================================================== -void GpsInfo::InitAsDefaultInstance() { +void SubscribeActuatorOutputStatusRequest::InitAsDefaultInstance() { } -class GpsInfo::HasBitSetters { +class SubscribeActuatorOutputStatusRequest::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int GpsInfo::kNumSatellitesFieldNumber; -const int GpsInfo::kFixTypeFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -GpsInfo::GpsInfo() +SubscribeActuatorOutputStatusRequest::SubscribeActuatorOutputStatusRequest() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.GpsInfo) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) } -GpsInfo::GpsInfo(const GpsInfo& from) +SubscribeActuatorOutputStatusRequest::SubscribeActuatorOutputStatusRequest(const SubscribeActuatorOutputStatusRequest& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - ::memcpy(&num_satellites_, &from.num_satellites_, - static_cast(reinterpret_cast(&fix_type_) - - reinterpret_cast(&num_satellites_)) + sizeof(fix_type_)); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.GpsInfo) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) } -void GpsInfo::SharedCtor() { - ::memset(&num_satellites_, 0, static_cast( - reinterpret_cast(&fix_type_) - - reinterpret_cast(&num_satellites_)) + sizeof(fix_type_)); +void SubscribeActuatorOutputStatusRequest::SharedCtor() { } -GpsInfo::~GpsInfo() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.GpsInfo) +SubscribeActuatorOutputStatusRequest::~SubscribeActuatorOutputStatusRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) SharedDtor(); } -void GpsInfo::SharedDtor() { +void SubscribeActuatorOutputStatusRequest::SharedDtor() { } -void GpsInfo::SetCachedSize(int size) const { +void SubscribeActuatorOutputStatusRequest::SetCachedSize(int size) const { _cached_size_.Set(size); } -const GpsInfo& GpsInfo::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_GpsInfo_telemetry_2ftelemetry_2eproto.base); +const SubscribeActuatorOutputStatusRequest& SubscribeActuatorOutputStatusRequest::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_SubscribeActuatorOutputStatusRequest_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void GpsInfo::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.GpsInfo) +void SubscribeActuatorOutputStatusRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&num_satellites_, 0, static_cast( - reinterpret_cast(&fix_type_) - - reinterpret_cast(&num_satellites_)) + sizeof(fix_type_)); _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* GpsInfo::_InternalParse(const char* begin, const char* end, void* object, +const char* SubscribeActuatorOutputStatusRequest::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -10214,23 +10018,7 @@ const char* GpsInfo::_InternalParse(const char* begin, const char* end, void* ob ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // int32 num_satellites = 1; - case 1: { - if (static_cast<::google::protobuf::uint8>(tag) != 8) goto handle_unusual; - msg->set_num_satellites(::google::protobuf::internal::ReadVarint(&ptr)); - GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - break; - } - // .mavsdk.rpc.telemetry.FixType fix_type = 2; - case 2: { - if (static_cast<::google::protobuf::uint8>(tag) != 16) goto handle_unusual; - ::google::protobuf::uint64 val = ::google::protobuf::internal::ReadVarint(&ptr); - msg->set_fix_type(static_cast<::mavsdk::rpc::telemetry::FixType>(val)); - GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - break; - } default: { - handle_unusual: if ((tag & 7) == 4 || tag == 0) { ctx->EndGroup(tag); return ptr; @@ -10246,115 +10034,61 @@ const char* GpsInfo::_InternalParse(const char* begin, const char* end, void* ob return ptr; } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool GpsInfo::MergePartialFromCodedStream( +bool SubscribeActuatorOutputStatusRequest::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.GpsInfo) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // int32 num_satellites = 1; - case 1: { - if (static_cast< ::google::protobuf::uint8>(tag) == (8 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &num_satellites_))); - } else { - goto handle_unusual; - } - break; - } - - // .mavsdk.rpc.telemetry.FixType fix_type = 2; - case 2: { - if (static_cast< ::google::protobuf::uint8>(tag) == (16 & 0xFF)) { - int value = 0; - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( - input, &value))); - set_fix_type(static_cast< ::mavsdk::rpc::telemetry::FixType >(value)); - } else { - goto handle_unusual; - } - break; - } - - default: { - handle_unusual: - if (tag == 0) { - goto success; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, _internal_metadata_.mutable_unknown_fields())); - break; - } + handle_unusual: + if (tag == 0) { + goto success; } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.GpsInfo) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.GpsInfo) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void GpsInfo::SerializeWithCachedSizes( +void SubscribeActuatorOutputStatusRequest::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.GpsInfo) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // int32 num_satellites = 1; - if (this->num_satellites() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->num_satellites(), output); - } - - // .mavsdk.rpc.telemetry.FixType fix_type = 2; - if (this->fix_type() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteEnum( - 2, this->fix_type(), output); - } - if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.GpsInfo) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) } -::google::protobuf::uint8* GpsInfo::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* SubscribeActuatorOutputStatusRequest::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.GpsInfo) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // int32 num_satellites = 1; - if (this->num_satellites() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->num_satellites(), target); - } - - // .mavsdk.rpc.telemetry.FixType fix_type = 2; - if (this->fix_type() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( - 2, this->fix_type(), target); - } - if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.GpsInfo) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) return target; } -size_t GpsInfo::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.GpsInfo) +size_t SubscribeActuatorOutputStatusRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -10366,84 +10100,3269 @@ size_t GpsInfo::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // int32 num_satellites = 1; - if (this->num_satellites() != 0) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->num_satellites()); - } - - // .mavsdk.rpc.telemetry.FixType fix_type = 2; - if (this->fix_type() != 0) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::EnumSize(this->fix_type()); - } - int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); SetCachedSize(cached_size); return total_size; } -void GpsInfo::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.GpsInfo) +void SubscribeActuatorOutputStatusRequest::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) + GOOGLE_DCHECK_NE(&from, this); + const SubscribeActuatorOutputStatusRequest* source = + ::google::protobuf::DynamicCastToGenerated( + &from); + if (source == nullptr) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) + MergeFrom(*source); + } +} + +void SubscribeActuatorOutputStatusRequest::MergeFrom(const SubscribeActuatorOutputStatusRequest& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + +} + +void SubscribeActuatorOutputStatusRequest::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void SubscribeActuatorOutputStatusRequest::CopyFrom(const SubscribeActuatorOutputStatusRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SubscribeActuatorOutputStatusRequest::IsInitialized() const { + return true; +} + +void SubscribeActuatorOutputStatusRequest::Swap(SubscribeActuatorOutputStatusRequest* other) { + if (other == this) return; + InternalSwap(other); +} +void SubscribeActuatorOutputStatusRequest::InternalSwap(SubscribeActuatorOutputStatusRequest* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); +} + +::google::protobuf::Metadata SubscribeActuatorOutputStatusRequest::GetMetadata() const { + ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); + return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; +} + + +// =================================================================== + +void ActuatorOutputStatusResponse::InitAsDefaultInstance() { + ::mavsdk::rpc::telemetry::_ActuatorOutputStatusResponse_default_instance_._instance.get_mutable()->actuator_output_status_ = const_cast< ::mavsdk::rpc::telemetry::ActuatorOutputStatus*>( + ::mavsdk::rpc::telemetry::ActuatorOutputStatus::internal_default_instance()); +} +class ActuatorOutputStatusResponse::HasBitSetters { + public: + static const ::mavsdk::rpc::telemetry::ActuatorOutputStatus& actuator_output_status(const ActuatorOutputStatusResponse* msg); +}; + +const ::mavsdk::rpc::telemetry::ActuatorOutputStatus& +ActuatorOutputStatusResponse::HasBitSetters::actuator_output_status(const ActuatorOutputStatusResponse* msg) { + return *msg->actuator_output_status_; +} +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int ActuatorOutputStatusResponse::kActuatorOutputStatusFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +ActuatorOutputStatusResponse::ActuatorOutputStatusResponse() + : ::google::protobuf::Message(), _internal_metadata_(nullptr) { + SharedCtor(); + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) +} +ActuatorOutputStatusResponse::ActuatorOutputStatusResponse(const ActuatorOutputStatusResponse& from) + : ::google::protobuf::Message(), + _internal_metadata_(nullptr) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + if (from.has_actuator_output_status()) { + actuator_output_status_ = new ::mavsdk::rpc::telemetry::ActuatorOutputStatus(*from.actuator_output_status_); + } else { + actuator_output_status_ = nullptr; + } + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) +} + +void ActuatorOutputStatusResponse::SharedCtor() { + ::google::protobuf::internal::InitSCC( + &scc_info_ActuatorOutputStatusResponse_telemetry_2ftelemetry_2eproto.base); + actuator_output_status_ = nullptr; +} + +ActuatorOutputStatusResponse::~ActuatorOutputStatusResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + SharedDtor(); +} + +void ActuatorOutputStatusResponse::SharedDtor() { + if (this != internal_default_instance()) delete actuator_output_status_; +} + +void ActuatorOutputStatusResponse::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const ActuatorOutputStatusResponse& ActuatorOutputStatusResponse::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_ActuatorOutputStatusResponse_telemetry_2ftelemetry_2eproto.base); + return *internal_default_instance(); +} + + +void ActuatorOutputStatusResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + if (GetArenaNoVirtual() == nullptr && actuator_output_status_ != nullptr) { + delete actuator_output_status_; + } + actuator_output_status_ = nullptr; + _internal_metadata_.Clear(); +} + +#if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +const char* ActuatorOutputStatusResponse::_InternalParse(const char* begin, const char* end, void* object, + ::google::protobuf::internal::ParseContext* ctx) { + auto msg = static_cast(object); + ::google::protobuf::int32 size; (void)size; + int depth; (void)depth; + ::google::protobuf::uint32 tag; + ::google::protobuf::internal::ParseFunc parser_till_end; (void)parser_till_end; + auto ptr = begin; + while (ptr < end) { + ptr = ::google::protobuf::io::Parse32(ptr, &tag); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + switch (tag >> 3) { + // .mavsdk.rpc.telemetry.ActuatorOutputStatus actuator_output_status = 1; + case 1: { + if (static_cast<::google::protobuf::uint8>(tag) != 10) goto handle_unusual; + ptr = ::google::protobuf::io::ReadSize(ptr, &size); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + parser_till_end = ::mavsdk::rpc::telemetry::ActuatorOutputStatus::_InternalParse; + object = msg->mutable_actuator_output_status(); + if (size > end - ptr) goto len_delim_till_end; + ptr += size; + GOOGLE_PROTOBUF_PARSER_ASSERT(ctx->ParseExactRange( + {parser_till_end, object}, ptr - size, ptr)); + break; + } + default: { + handle_unusual: + if ((tag & 7) == 4 || tag == 0) { + ctx->EndGroup(tag); + return ptr; + } + auto res = UnknownFieldParse(tag, {_InternalParse, msg}, + ptr, end, msg->_internal_metadata_.mutable_unknown_fields(), ctx); + ptr = res.first; + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr != nullptr); + if (res.second) return ptr; + } + } // switch + } // while + return ptr; +len_delim_till_end: + return ctx->StoreAndTailCall(ptr, end, {_InternalParse, msg}, + {parser_till_end, object}, size); +} +#else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +bool ActuatorOutputStatusResponse::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // .mavsdk.rpc.telemetry.ActuatorOutputStatus actuator_output_status = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == (10 & 0xFF)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadMessage( + input, mutable_actuator_output_status())); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + return true; +failure: + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + return false; +#undef DO_ +} +#endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + +void ActuatorOutputStatusResponse::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.telemetry.ActuatorOutputStatus actuator_output_status = 1; + if (this->has_actuator_output_status()) { + ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( + 1, HasBitSetters::actuator_output_status(this), output); + } + + if (_internal_metadata_.have_unknown_fields()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + _internal_metadata_.unknown_fields(), output); + } + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) +} + +::google::protobuf::uint8* ActuatorOutputStatusResponse::InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // .mavsdk.rpc.telemetry.ActuatorOutputStatus actuator_output_status = 1; + if (this->has_actuator_output_status()) { + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessageToArray( + 1, HasBitSetters::actuator_output_status(this), target); + } + + if (_internal_metadata_.have_unknown_fields()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + return target; +} + +size_t ActuatorOutputStatusResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + size_t total_size = 0; + + if (_internal_metadata_.have_unknown_fields()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + _internal_metadata_.unknown_fields()); + } + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.telemetry.ActuatorOutputStatus actuator_output_status = 1; + if (this->has_actuator_output_status()) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::MessageSize( + *actuator_output_status_); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void ActuatorOutputStatusResponse::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + GOOGLE_DCHECK_NE(&from, this); + const ActuatorOutputStatusResponse* source = + ::google::protobuf::DynamicCastToGenerated( + &from); + if (source == nullptr) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + MergeFrom(*source); + } +} + +void ActuatorOutputStatusResponse::MergeFrom(const ActuatorOutputStatusResponse& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.has_actuator_output_status()) { + mutable_actuator_output_status()->::mavsdk::rpc::telemetry::ActuatorOutputStatus::MergeFrom(from.actuator_output_status()); + } +} + +void ActuatorOutputStatusResponse::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void ActuatorOutputStatusResponse::CopyFrom(const ActuatorOutputStatusResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool ActuatorOutputStatusResponse::IsInitialized() const { + return true; +} + +void ActuatorOutputStatusResponse::Swap(ActuatorOutputStatusResponse* other) { + if (other == this) return; + InternalSwap(other); +} +void ActuatorOutputStatusResponse::InternalSwap(ActuatorOutputStatusResponse* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); + swap(actuator_output_status_, other->actuator_output_status_); +} + +::google::protobuf::Metadata ActuatorOutputStatusResponse::GetMetadata() const { + ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); + return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; +} + + +// =================================================================== + +void Position::InitAsDefaultInstance() { +} +class Position::HasBitSetters { + public: +}; + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Position::kLatitudeDegFieldNumber; +const int Position::kLongitudeDegFieldNumber; +const int Position::kAbsoluteAltitudeMFieldNumber; +const int Position::kRelativeAltitudeMFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Position::Position() + : ::google::protobuf::Message(), _internal_metadata_(nullptr) { + SharedCtor(); + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.Position) +} +Position::Position(const Position& from) + : ::google::protobuf::Message(), + _internal_metadata_(nullptr) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&latitude_deg_, &from.latitude_deg_, + static_cast(reinterpret_cast(&relative_altitude_m_) - + reinterpret_cast(&latitude_deg_)) + sizeof(relative_altitude_m_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.Position) +} + +void Position::SharedCtor() { + ::memset(&latitude_deg_, 0, static_cast( + reinterpret_cast(&relative_altitude_m_) - + reinterpret_cast(&latitude_deg_)) + sizeof(relative_altitude_m_)); +} + +Position::~Position() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.Position) + SharedDtor(); +} + +void Position::SharedDtor() { +} + +void Position::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const Position& Position::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_Position_telemetry_2ftelemetry_2eproto.base); + return *internal_default_instance(); +} + + +void Position::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.Position) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&latitude_deg_, 0, static_cast( + reinterpret_cast(&relative_altitude_m_) - + reinterpret_cast(&latitude_deg_)) + sizeof(relative_altitude_m_)); + _internal_metadata_.Clear(); +} + +#if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +const char* Position::_InternalParse(const char* begin, const char* end, void* object, + ::google::protobuf::internal::ParseContext* ctx) { + auto msg = static_cast(object); + ::google::protobuf::int32 size; (void)size; + int depth; (void)depth; + ::google::protobuf::uint32 tag; + ::google::protobuf::internal::ParseFunc parser_till_end; (void)parser_till_end; + auto ptr = begin; + while (ptr < end) { + ptr = ::google::protobuf::io::Parse32(ptr, &tag); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + switch (tag >> 3) { + // double latitude_deg = 1; + case 1: { + if (static_cast<::google::protobuf::uint8>(tag) != 9) goto handle_unusual; + msg->set_latitude_deg(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(double); + break; + } + // double longitude_deg = 2; + case 2: { + if (static_cast<::google::protobuf::uint8>(tag) != 17) goto handle_unusual; + msg->set_longitude_deg(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(double); + break; + } + // float absolute_altitude_m = 3; + case 3: { + if (static_cast<::google::protobuf::uint8>(tag) != 29) goto handle_unusual; + msg->set_absolute_altitude_m(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + // float relative_altitude_m = 4; + case 4: { + if (static_cast<::google::protobuf::uint8>(tag) != 37) goto handle_unusual; + msg->set_relative_altitude_m(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + default: { + handle_unusual: + if ((tag & 7) == 4 || tag == 0) { + ctx->EndGroup(tag); + return ptr; + } + auto res = UnknownFieldParse(tag, {_InternalParse, msg}, + ptr, end, msg->_internal_metadata_.mutable_unknown_fields(), ctx); + ptr = res.first; + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr != nullptr); + if (res.second) return ptr; + } + } // switch + } // while + return ptr; +} +#else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +bool Position::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.Position) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // double latitude_deg = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == (9 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &latitude_deg_))); + } else { + goto handle_unusual; + } + break; + } + + // double longitude_deg = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == (17 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( + input, &longitude_deg_))); + } else { + goto handle_unusual; + } + break; + } + + // float absolute_altitude_m = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == (29 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &absolute_altitude_m_))); + } else { + goto handle_unusual; + } + break; + } + + // float relative_altitude_m = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == (37 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &relative_altitude_m_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.Position) + return true; +failure: + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.Position) + return false; +#undef DO_ +} +#endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + +void Position::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.Position) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double latitude_deg = 1; + if (this->latitude_deg() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->latitude_deg(), output); + } + + // double longitude_deg = 2; + if (this->longitude_deg() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->longitude_deg(), output); + } + + // float absolute_altitude_m = 3; + if (this->absolute_altitude_m() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->absolute_altitude_m(), output); + } + + // float relative_altitude_m = 4; + if (this->relative_altitude_m() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->relative_altitude_m(), output); + } + + if (_internal_metadata_.have_unknown_fields()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + _internal_metadata_.unknown_fields(), output); + } + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.Position) +} + +::google::protobuf::uint8* Position::InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.Position) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // double latitude_deg = 1; + if (this->latitude_deg() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->latitude_deg(), target); + } + + // double longitude_deg = 2; + if (this->longitude_deg() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->longitude_deg(), target); + } + + // float absolute_altitude_m = 3; + if (this->absolute_altitude_m() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->absolute_altitude_m(), target); + } + + // float relative_altitude_m = 4; + if (this->relative_altitude_m() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->relative_altitude_m(), target); + } + + if (_internal_metadata_.have_unknown_fields()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.Position) + return target; +} + +size_t Position::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.Position) + size_t total_size = 0; + + if (_internal_metadata_.have_unknown_fields()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + _internal_metadata_.unknown_fields()); + } + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // double latitude_deg = 1; + if (this->latitude_deg() != 0) { + total_size += 1 + 8; + } + + // double longitude_deg = 2; + if (this->longitude_deg() != 0) { + total_size += 1 + 8; + } + + // float absolute_altitude_m = 3; + if (this->absolute_altitude_m() != 0) { + total_size += 1 + 4; + } + + // float relative_altitude_m = 4; + if (this->relative_altitude_m() != 0) { + total_size += 1 + 4; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Position::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.Position) + GOOGLE_DCHECK_NE(&from, this); + const Position* source = + ::google::protobuf::DynamicCastToGenerated( + &from); + if (source == nullptr) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.Position) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.Position) + MergeFrom(*source); + } +} + +void Position::MergeFrom(const Position& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.Position) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.latitude_deg() != 0) { + set_latitude_deg(from.latitude_deg()); + } + if (from.longitude_deg() != 0) { + set_longitude_deg(from.longitude_deg()); + } + if (from.absolute_altitude_m() != 0) { + set_absolute_altitude_m(from.absolute_altitude_m()); + } + if (from.relative_altitude_m() != 0) { + set_relative_altitude_m(from.relative_altitude_m()); + } +} + +void Position::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.Position) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Position::CopyFrom(const Position& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.Position) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Position::IsInitialized() const { + return true; +} + +void Position::Swap(Position* other) { + if (other == this) return; + InternalSwap(other); +} +void Position::InternalSwap(Position* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); + swap(latitude_deg_, other->latitude_deg_); + swap(longitude_deg_, other->longitude_deg_); + swap(absolute_altitude_m_, other->absolute_altitude_m_); + swap(relative_altitude_m_, other->relative_altitude_m_); +} + +::google::protobuf::Metadata Position::GetMetadata() const { + ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); + return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; +} + + +// =================================================================== + +void Quaternion::InitAsDefaultInstance() { +} +class Quaternion::HasBitSetters { + public: +}; + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Quaternion::kWFieldNumber; +const int Quaternion::kXFieldNumber; +const int Quaternion::kYFieldNumber; +const int Quaternion::kZFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Quaternion::Quaternion() + : ::google::protobuf::Message(), _internal_metadata_(nullptr) { + SharedCtor(); + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.Quaternion) +} +Quaternion::Quaternion(const Quaternion& from) + : ::google::protobuf::Message(), + _internal_metadata_(nullptr) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&w_, &from.w_, + static_cast(reinterpret_cast(&z_) - + reinterpret_cast(&w_)) + sizeof(z_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.Quaternion) +} + +void Quaternion::SharedCtor() { + ::memset(&w_, 0, static_cast( + reinterpret_cast(&z_) - + reinterpret_cast(&w_)) + sizeof(z_)); +} + +Quaternion::~Quaternion() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.Quaternion) + SharedDtor(); +} + +void Quaternion::SharedDtor() { +} + +void Quaternion::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const Quaternion& Quaternion::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_Quaternion_telemetry_2ftelemetry_2eproto.base); + return *internal_default_instance(); +} + + +void Quaternion::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.Quaternion) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&w_, 0, static_cast( + reinterpret_cast(&z_) - + reinterpret_cast(&w_)) + sizeof(z_)); + _internal_metadata_.Clear(); +} + +#if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +const char* Quaternion::_InternalParse(const char* begin, const char* end, void* object, + ::google::protobuf::internal::ParseContext* ctx) { + auto msg = static_cast(object); + ::google::protobuf::int32 size; (void)size; + int depth; (void)depth; + ::google::protobuf::uint32 tag; + ::google::protobuf::internal::ParseFunc parser_till_end; (void)parser_till_end; + auto ptr = begin; + while (ptr < end) { + ptr = ::google::protobuf::io::Parse32(ptr, &tag); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + switch (tag >> 3) { + // float w = 1; + case 1: { + if (static_cast<::google::protobuf::uint8>(tag) != 13) goto handle_unusual; + msg->set_w(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + // float x = 2; + case 2: { + if (static_cast<::google::protobuf::uint8>(tag) != 21) goto handle_unusual; + msg->set_x(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + // float y = 3; + case 3: { + if (static_cast<::google::protobuf::uint8>(tag) != 29) goto handle_unusual; + msg->set_y(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + // float z = 4; + case 4: { + if (static_cast<::google::protobuf::uint8>(tag) != 37) goto handle_unusual; + msg->set_z(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + default: { + handle_unusual: + if ((tag & 7) == 4 || tag == 0) { + ctx->EndGroup(tag); + return ptr; + } + auto res = UnknownFieldParse(tag, {_InternalParse, msg}, + ptr, end, msg->_internal_metadata_.mutable_unknown_fields(), ctx); + ptr = res.first; + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr != nullptr); + if (res.second) return ptr; + } + } // switch + } // while + return ptr; +} +#else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +bool Quaternion::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.Quaternion) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // float w = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == (13 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &w_))); + } else { + goto handle_unusual; + } + break; + } + + // float x = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == (21 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &x_))); + } else { + goto handle_unusual; + } + break; + } + + // float y = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == (29 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &y_))); + } else { + goto handle_unusual; + } + break; + } + + // float z = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == (37 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &z_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.Quaternion) + return true; +failure: + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.Quaternion) + return false; +#undef DO_ +} +#endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + +void Quaternion::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.Quaternion) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // float w = 1; + if (this->w() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->w(), output); + } + + // float x = 2; + if (this->x() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->x(), output); + } + + // float y = 3; + if (this->y() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->y(), output); + } + + // float z = 4; + if (this->z() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->z(), output); + } + + if (_internal_metadata_.have_unknown_fields()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + _internal_metadata_.unknown_fields(), output); + } + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.Quaternion) +} + +::google::protobuf::uint8* Quaternion::InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.Quaternion) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // float w = 1; + if (this->w() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->w(), target); + } + + // float x = 2; + if (this->x() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->x(), target); + } + + // float y = 3; + if (this->y() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->y(), target); + } + + // float z = 4; + if (this->z() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->z(), target); + } + + if (_internal_metadata_.have_unknown_fields()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.Quaternion) + return target; +} + +size_t Quaternion::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.Quaternion) + size_t total_size = 0; + + if (_internal_metadata_.have_unknown_fields()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + _internal_metadata_.unknown_fields()); + } + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // float w = 1; + if (this->w() != 0) { + total_size += 1 + 4; + } + + // float x = 2; + if (this->x() != 0) { + total_size += 1 + 4; + } + + // float y = 3; + if (this->y() != 0) { + total_size += 1 + 4; + } + + // float z = 4; + if (this->z() != 0) { + total_size += 1 + 4; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Quaternion::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.Quaternion) + GOOGLE_DCHECK_NE(&from, this); + const Quaternion* source = + ::google::protobuf::DynamicCastToGenerated( + &from); + if (source == nullptr) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.Quaternion) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.Quaternion) + MergeFrom(*source); + } +} + +void Quaternion::MergeFrom(const Quaternion& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.Quaternion) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.w() != 0) { + set_w(from.w()); + } + if (from.x() != 0) { + set_x(from.x()); + } + if (from.y() != 0) { + set_y(from.y()); + } + if (from.z() != 0) { + set_z(from.z()); + } +} + +void Quaternion::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.Quaternion) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Quaternion::CopyFrom(const Quaternion& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.Quaternion) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Quaternion::IsInitialized() const { + return true; +} + +void Quaternion::Swap(Quaternion* other) { + if (other == this) return; + InternalSwap(other); +} +void Quaternion::InternalSwap(Quaternion* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); + swap(w_, other->w_); + swap(x_, other->x_); + swap(y_, other->y_); + swap(z_, other->z_); +} + +::google::protobuf::Metadata Quaternion::GetMetadata() const { + ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); + return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; +} + + +// =================================================================== + +void EulerAngle::InitAsDefaultInstance() { +} +class EulerAngle::HasBitSetters { + public: +}; + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int EulerAngle::kRollDegFieldNumber; +const int EulerAngle::kPitchDegFieldNumber; +const int EulerAngle::kYawDegFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +EulerAngle::EulerAngle() + : ::google::protobuf::Message(), _internal_metadata_(nullptr) { + SharedCtor(); + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.EulerAngle) +} +EulerAngle::EulerAngle(const EulerAngle& from) + : ::google::protobuf::Message(), + _internal_metadata_(nullptr) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&roll_deg_, &from.roll_deg_, + static_cast(reinterpret_cast(&yaw_deg_) - + reinterpret_cast(&roll_deg_)) + sizeof(yaw_deg_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.EulerAngle) +} + +void EulerAngle::SharedCtor() { + ::memset(&roll_deg_, 0, static_cast( + reinterpret_cast(&yaw_deg_) - + reinterpret_cast(&roll_deg_)) + sizeof(yaw_deg_)); +} + +EulerAngle::~EulerAngle() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.EulerAngle) + SharedDtor(); +} + +void EulerAngle::SharedDtor() { +} + +void EulerAngle::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const EulerAngle& EulerAngle::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_EulerAngle_telemetry_2ftelemetry_2eproto.base); + return *internal_default_instance(); +} + + +void EulerAngle::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.EulerAngle) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&roll_deg_, 0, static_cast( + reinterpret_cast(&yaw_deg_) - + reinterpret_cast(&roll_deg_)) + sizeof(yaw_deg_)); + _internal_metadata_.Clear(); +} + +#if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +const char* EulerAngle::_InternalParse(const char* begin, const char* end, void* object, + ::google::protobuf::internal::ParseContext* ctx) { + auto msg = static_cast(object); + ::google::protobuf::int32 size; (void)size; + int depth; (void)depth; + ::google::protobuf::uint32 tag; + ::google::protobuf::internal::ParseFunc parser_till_end; (void)parser_till_end; + auto ptr = begin; + while (ptr < end) { + ptr = ::google::protobuf::io::Parse32(ptr, &tag); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + switch (tag >> 3) { + // float roll_deg = 1; + case 1: { + if (static_cast<::google::protobuf::uint8>(tag) != 13) goto handle_unusual; + msg->set_roll_deg(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + // float pitch_deg = 2; + case 2: { + if (static_cast<::google::protobuf::uint8>(tag) != 21) goto handle_unusual; + msg->set_pitch_deg(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + // float yaw_deg = 3; + case 3: { + if (static_cast<::google::protobuf::uint8>(tag) != 29) goto handle_unusual; + msg->set_yaw_deg(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + default: { + handle_unusual: + if ((tag & 7) == 4 || tag == 0) { + ctx->EndGroup(tag); + return ptr; + } + auto res = UnknownFieldParse(tag, {_InternalParse, msg}, + ptr, end, msg->_internal_metadata_.mutable_unknown_fields(), ctx); + ptr = res.first; + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr != nullptr); + if (res.second) return ptr; + } + } // switch + } // while + return ptr; +} +#else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +bool EulerAngle::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.EulerAngle) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // float roll_deg = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == (13 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &roll_deg_))); + } else { + goto handle_unusual; + } + break; + } + + // float pitch_deg = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == (21 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &pitch_deg_))); + } else { + goto handle_unusual; + } + break; + } + + // float yaw_deg = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == (29 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &yaw_deg_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.EulerAngle) + return true; +failure: + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.EulerAngle) + return false; +#undef DO_ +} +#endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + +void EulerAngle::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.EulerAngle) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // float roll_deg = 1; + if (this->roll_deg() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->roll_deg(), output); + } + + // float pitch_deg = 2; + if (this->pitch_deg() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->pitch_deg(), output); + } + + // float yaw_deg = 3; + if (this->yaw_deg() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->yaw_deg(), output); + } + + if (_internal_metadata_.have_unknown_fields()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + _internal_metadata_.unknown_fields(), output); + } + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.EulerAngle) +} + +::google::protobuf::uint8* EulerAngle::InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.EulerAngle) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // float roll_deg = 1; + if (this->roll_deg() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->roll_deg(), target); + } + + // float pitch_deg = 2; + if (this->pitch_deg() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->pitch_deg(), target); + } + + // float yaw_deg = 3; + if (this->yaw_deg() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->yaw_deg(), target); + } + + if (_internal_metadata_.have_unknown_fields()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.EulerAngle) + return target; +} + +size_t EulerAngle::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.EulerAngle) + size_t total_size = 0; + + if (_internal_metadata_.have_unknown_fields()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + _internal_metadata_.unknown_fields()); + } + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // float roll_deg = 1; + if (this->roll_deg() != 0) { + total_size += 1 + 4; + } + + // float pitch_deg = 2; + if (this->pitch_deg() != 0) { + total_size += 1 + 4; + } + + // float yaw_deg = 3; + if (this->yaw_deg() != 0) { + total_size += 1 + 4; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void EulerAngle::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.EulerAngle) + GOOGLE_DCHECK_NE(&from, this); + const EulerAngle* source = + ::google::protobuf::DynamicCastToGenerated( + &from); + if (source == nullptr) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.EulerAngle) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.EulerAngle) + MergeFrom(*source); + } +} + +void EulerAngle::MergeFrom(const EulerAngle& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.EulerAngle) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.roll_deg() != 0) { + set_roll_deg(from.roll_deg()); + } + if (from.pitch_deg() != 0) { + set_pitch_deg(from.pitch_deg()); + } + if (from.yaw_deg() != 0) { + set_yaw_deg(from.yaw_deg()); + } +} + +void EulerAngle::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.EulerAngle) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void EulerAngle::CopyFrom(const EulerAngle& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.EulerAngle) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool EulerAngle::IsInitialized() const { + return true; +} + +void EulerAngle::Swap(EulerAngle* other) { + if (other == this) return; + InternalSwap(other); +} +void EulerAngle::InternalSwap(EulerAngle* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); + swap(roll_deg_, other->roll_deg_); + swap(pitch_deg_, other->pitch_deg_); + swap(yaw_deg_, other->yaw_deg_); +} + +::google::protobuf::Metadata EulerAngle::GetMetadata() const { + ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); + return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; +} + + +// =================================================================== + +void AngularVelocityBody::InitAsDefaultInstance() { +} +class AngularVelocityBody::HasBitSetters { + public: +}; + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int AngularVelocityBody::kRollRadSFieldNumber; +const int AngularVelocityBody::kPitchRadSFieldNumber; +const int AngularVelocityBody::kYawRadSFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +AngularVelocityBody::AngularVelocityBody() + : ::google::protobuf::Message(), _internal_metadata_(nullptr) { + SharedCtor(); + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.AngularVelocityBody) +} +AngularVelocityBody::AngularVelocityBody(const AngularVelocityBody& from) + : ::google::protobuf::Message(), + _internal_metadata_(nullptr) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&roll_rad_s_, &from.roll_rad_s_, + static_cast(reinterpret_cast(&yaw_rad_s_) - + reinterpret_cast(&roll_rad_s_)) + sizeof(yaw_rad_s_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.AngularVelocityBody) +} + +void AngularVelocityBody::SharedCtor() { + ::memset(&roll_rad_s_, 0, static_cast( + reinterpret_cast(&yaw_rad_s_) - + reinterpret_cast(&roll_rad_s_)) + sizeof(yaw_rad_s_)); +} + +AngularVelocityBody::~AngularVelocityBody() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.AngularVelocityBody) + SharedDtor(); +} + +void AngularVelocityBody::SharedDtor() { +} + +void AngularVelocityBody::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const AngularVelocityBody& AngularVelocityBody::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_AngularVelocityBody_telemetry_2ftelemetry_2eproto.base); + return *internal_default_instance(); +} + + +void AngularVelocityBody::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.AngularVelocityBody) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&roll_rad_s_, 0, static_cast( + reinterpret_cast(&yaw_rad_s_) - + reinterpret_cast(&roll_rad_s_)) + sizeof(yaw_rad_s_)); + _internal_metadata_.Clear(); +} + +#if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +const char* AngularVelocityBody::_InternalParse(const char* begin, const char* end, void* object, + ::google::protobuf::internal::ParseContext* ctx) { + auto msg = static_cast(object); + ::google::protobuf::int32 size; (void)size; + int depth; (void)depth; + ::google::protobuf::uint32 tag; + ::google::protobuf::internal::ParseFunc parser_till_end; (void)parser_till_end; + auto ptr = begin; + while (ptr < end) { + ptr = ::google::protobuf::io::Parse32(ptr, &tag); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + switch (tag >> 3) { + // float roll_rad_s = 1; + case 1: { + if (static_cast<::google::protobuf::uint8>(tag) != 13) goto handle_unusual; + msg->set_roll_rad_s(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + // float pitch_rad_s = 2; + case 2: { + if (static_cast<::google::protobuf::uint8>(tag) != 21) goto handle_unusual; + msg->set_pitch_rad_s(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + // float yaw_rad_s = 3; + case 3: { + if (static_cast<::google::protobuf::uint8>(tag) != 29) goto handle_unusual; + msg->set_yaw_rad_s(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + default: { + handle_unusual: + if ((tag & 7) == 4 || tag == 0) { + ctx->EndGroup(tag); + return ptr; + } + auto res = UnknownFieldParse(tag, {_InternalParse, msg}, + ptr, end, msg->_internal_metadata_.mutable_unknown_fields(), ctx); + ptr = res.first; + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr != nullptr); + if (res.second) return ptr; + } + } // switch + } // while + return ptr; +} +#else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +bool AngularVelocityBody::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.AngularVelocityBody) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // float roll_rad_s = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == (13 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &roll_rad_s_))); + } else { + goto handle_unusual; + } + break; + } + + // float pitch_rad_s = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == (21 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &pitch_rad_s_))); + } else { + goto handle_unusual; + } + break; + } + + // float yaw_rad_s = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == (29 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &yaw_rad_s_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.AngularVelocityBody) + return true; +failure: + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.AngularVelocityBody) + return false; +#undef DO_ +} +#endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + +void AngularVelocityBody::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.AngularVelocityBody) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // float roll_rad_s = 1; + if (this->roll_rad_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->roll_rad_s(), output); + } + + // float pitch_rad_s = 2; + if (this->pitch_rad_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->pitch_rad_s(), output); + } + + // float yaw_rad_s = 3; + if (this->yaw_rad_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->yaw_rad_s(), output); + } + + if (_internal_metadata_.have_unknown_fields()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + _internal_metadata_.unknown_fields(), output); + } + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.AngularVelocityBody) +} + +::google::protobuf::uint8* AngularVelocityBody::InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.AngularVelocityBody) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // float roll_rad_s = 1; + if (this->roll_rad_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->roll_rad_s(), target); + } + + // float pitch_rad_s = 2; + if (this->pitch_rad_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->pitch_rad_s(), target); + } + + // float yaw_rad_s = 3; + if (this->yaw_rad_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->yaw_rad_s(), target); + } + + if (_internal_metadata_.have_unknown_fields()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.AngularVelocityBody) + return target; +} + +size_t AngularVelocityBody::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.AngularVelocityBody) + size_t total_size = 0; + + if (_internal_metadata_.have_unknown_fields()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + _internal_metadata_.unknown_fields()); + } + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // float roll_rad_s = 1; + if (this->roll_rad_s() != 0) { + total_size += 1 + 4; + } + + // float pitch_rad_s = 2; + if (this->pitch_rad_s() != 0) { + total_size += 1 + 4; + } + + // float yaw_rad_s = 3; + if (this->yaw_rad_s() != 0) { + total_size += 1 + 4; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void AngularVelocityBody::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.AngularVelocityBody) + GOOGLE_DCHECK_NE(&from, this); + const AngularVelocityBody* source = + ::google::protobuf::DynamicCastToGenerated( + &from); + if (source == nullptr) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.AngularVelocityBody) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.AngularVelocityBody) + MergeFrom(*source); + } +} + +void AngularVelocityBody::MergeFrom(const AngularVelocityBody& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.AngularVelocityBody) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.roll_rad_s() != 0) { + set_roll_rad_s(from.roll_rad_s()); + } + if (from.pitch_rad_s() != 0) { + set_pitch_rad_s(from.pitch_rad_s()); + } + if (from.yaw_rad_s() != 0) { + set_yaw_rad_s(from.yaw_rad_s()); + } +} + +void AngularVelocityBody::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.AngularVelocityBody) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void AngularVelocityBody::CopyFrom(const AngularVelocityBody& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.AngularVelocityBody) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool AngularVelocityBody::IsInitialized() const { + return true; +} + +void AngularVelocityBody::Swap(AngularVelocityBody* other) { + if (other == this) return; + InternalSwap(other); +} +void AngularVelocityBody::InternalSwap(AngularVelocityBody* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); + swap(roll_rad_s_, other->roll_rad_s_); + swap(pitch_rad_s_, other->pitch_rad_s_); + swap(yaw_rad_s_, other->yaw_rad_s_); +} + +::google::protobuf::Metadata AngularVelocityBody::GetMetadata() const { + ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); + return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; +} + + +// =================================================================== + +void SpeedNed::InitAsDefaultInstance() { +} +class SpeedNed::HasBitSetters { + public: +}; + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int SpeedNed::kVelocityNorthMSFieldNumber; +const int SpeedNed::kVelocityEastMSFieldNumber; +const int SpeedNed::kVelocityDownMSFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +SpeedNed::SpeedNed() + : ::google::protobuf::Message(), _internal_metadata_(nullptr) { + SharedCtor(); + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.SpeedNed) +} +SpeedNed::SpeedNed(const SpeedNed& from) + : ::google::protobuf::Message(), + _internal_metadata_(nullptr) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&velocity_north_m_s_, &from.velocity_north_m_s_, + static_cast(reinterpret_cast(&velocity_down_m_s_) - + reinterpret_cast(&velocity_north_m_s_)) + sizeof(velocity_down_m_s_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.SpeedNed) +} + +void SpeedNed::SharedCtor() { + ::memset(&velocity_north_m_s_, 0, static_cast( + reinterpret_cast(&velocity_down_m_s_) - + reinterpret_cast(&velocity_north_m_s_)) + sizeof(velocity_down_m_s_)); +} + +SpeedNed::~SpeedNed() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.SpeedNed) + SharedDtor(); +} + +void SpeedNed::SharedDtor() { +} + +void SpeedNed::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const SpeedNed& SpeedNed::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_SpeedNed_telemetry_2ftelemetry_2eproto.base); + return *internal_default_instance(); +} + + +void SpeedNed::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.SpeedNed) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&velocity_north_m_s_, 0, static_cast( + reinterpret_cast(&velocity_down_m_s_) - + reinterpret_cast(&velocity_north_m_s_)) + sizeof(velocity_down_m_s_)); + _internal_metadata_.Clear(); +} + +#if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +const char* SpeedNed::_InternalParse(const char* begin, const char* end, void* object, + ::google::protobuf::internal::ParseContext* ctx) { + auto msg = static_cast(object); + ::google::protobuf::int32 size; (void)size; + int depth; (void)depth; + ::google::protobuf::uint32 tag; + ::google::protobuf::internal::ParseFunc parser_till_end; (void)parser_till_end; + auto ptr = begin; + while (ptr < end) { + ptr = ::google::protobuf::io::Parse32(ptr, &tag); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + switch (tag >> 3) { + // float velocity_north_m_s = 1; + case 1: { + if (static_cast<::google::protobuf::uint8>(tag) != 13) goto handle_unusual; + msg->set_velocity_north_m_s(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + // float velocity_east_m_s = 2; + case 2: { + if (static_cast<::google::protobuf::uint8>(tag) != 21) goto handle_unusual; + msg->set_velocity_east_m_s(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + // float velocity_down_m_s = 3; + case 3: { + if (static_cast<::google::protobuf::uint8>(tag) != 29) goto handle_unusual; + msg->set_velocity_down_m_s(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + default: { + handle_unusual: + if ((tag & 7) == 4 || tag == 0) { + ctx->EndGroup(tag); + return ptr; + } + auto res = UnknownFieldParse(tag, {_InternalParse, msg}, + ptr, end, msg->_internal_metadata_.mutable_unknown_fields(), ctx); + ptr = res.first; + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr != nullptr); + if (res.second) return ptr; + } + } // switch + } // while + return ptr; +} +#else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +bool SpeedNed::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.SpeedNed) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // float velocity_north_m_s = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == (13 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &velocity_north_m_s_))); + } else { + goto handle_unusual; + } + break; + } + + // float velocity_east_m_s = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == (21 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &velocity_east_m_s_))); + } else { + goto handle_unusual; + } + break; + } + + // float velocity_down_m_s = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == (29 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &velocity_down_m_s_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.SpeedNed) + return true; +failure: + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.SpeedNed) + return false; +#undef DO_ +} +#endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + +void SpeedNed::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.SpeedNed) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // float velocity_north_m_s = 1; + if (this->velocity_north_m_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->velocity_north_m_s(), output); + } + + // float velocity_east_m_s = 2; + if (this->velocity_east_m_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->velocity_east_m_s(), output); + } + + // float velocity_down_m_s = 3; + if (this->velocity_down_m_s() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->velocity_down_m_s(), output); + } + + if (_internal_metadata_.have_unknown_fields()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + _internal_metadata_.unknown_fields(), output); + } + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.SpeedNed) +} + +::google::protobuf::uint8* SpeedNed::InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.SpeedNed) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // float velocity_north_m_s = 1; + if (this->velocity_north_m_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->velocity_north_m_s(), target); + } + + // float velocity_east_m_s = 2; + if (this->velocity_east_m_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->velocity_east_m_s(), target); + } + + // float velocity_down_m_s = 3; + if (this->velocity_down_m_s() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->velocity_down_m_s(), target); + } + + if (_internal_metadata_.have_unknown_fields()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.SpeedNed) + return target; +} + +size_t SpeedNed::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.SpeedNed) + size_t total_size = 0; + + if (_internal_metadata_.have_unknown_fields()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + _internal_metadata_.unknown_fields()); + } + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // float velocity_north_m_s = 1; + if (this->velocity_north_m_s() != 0) { + total_size += 1 + 4; + } + + // float velocity_east_m_s = 2; + if (this->velocity_east_m_s() != 0) { + total_size += 1 + 4; + } + + // float velocity_down_m_s = 3; + if (this->velocity_down_m_s() != 0) { + total_size += 1 + 4; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void SpeedNed::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.SpeedNed) + GOOGLE_DCHECK_NE(&from, this); + const SpeedNed* source = + ::google::protobuf::DynamicCastToGenerated( + &from); + if (source == nullptr) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.SpeedNed) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.SpeedNed) + MergeFrom(*source); + } +} + +void SpeedNed::MergeFrom(const SpeedNed& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.SpeedNed) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.velocity_north_m_s() != 0) { + set_velocity_north_m_s(from.velocity_north_m_s()); + } + if (from.velocity_east_m_s() != 0) { + set_velocity_east_m_s(from.velocity_east_m_s()); + } + if (from.velocity_down_m_s() != 0) { + set_velocity_down_m_s(from.velocity_down_m_s()); + } +} + +void SpeedNed::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.SpeedNed) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void SpeedNed::CopyFrom(const SpeedNed& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.SpeedNed) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool SpeedNed::IsInitialized() const { + return true; +} + +void SpeedNed::Swap(SpeedNed* other) { + if (other == this) return; + InternalSwap(other); +} +void SpeedNed::InternalSwap(SpeedNed* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); + swap(velocity_north_m_s_, other->velocity_north_m_s_); + swap(velocity_east_m_s_, other->velocity_east_m_s_); + swap(velocity_down_m_s_, other->velocity_down_m_s_); +} + +::google::protobuf::Metadata SpeedNed::GetMetadata() const { + ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); + return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; +} + + +// =================================================================== + +void GpsInfo::InitAsDefaultInstance() { +} +class GpsInfo::HasBitSetters { + public: +}; + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int GpsInfo::kNumSatellitesFieldNumber; +const int GpsInfo::kFixTypeFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +GpsInfo::GpsInfo() + : ::google::protobuf::Message(), _internal_metadata_(nullptr) { + SharedCtor(); + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.GpsInfo) +} +GpsInfo::GpsInfo(const GpsInfo& from) + : ::google::protobuf::Message(), + _internal_metadata_(nullptr) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&num_satellites_, &from.num_satellites_, + static_cast(reinterpret_cast(&fix_type_) - + reinterpret_cast(&num_satellites_)) + sizeof(fix_type_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.GpsInfo) +} + +void GpsInfo::SharedCtor() { + ::memset(&num_satellites_, 0, static_cast( + reinterpret_cast(&fix_type_) - + reinterpret_cast(&num_satellites_)) + sizeof(fix_type_)); +} + +GpsInfo::~GpsInfo() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.GpsInfo) + SharedDtor(); +} + +void GpsInfo::SharedDtor() { +} + +void GpsInfo::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const GpsInfo& GpsInfo::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_GpsInfo_telemetry_2ftelemetry_2eproto.base); + return *internal_default_instance(); +} + + +void GpsInfo::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.GpsInfo) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&num_satellites_, 0, static_cast( + reinterpret_cast(&fix_type_) - + reinterpret_cast(&num_satellites_)) + sizeof(fix_type_)); + _internal_metadata_.Clear(); +} + +#if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +const char* GpsInfo::_InternalParse(const char* begin, const char* end, void* object, + ::google::protobuf::internal::ParseContext* ctx) { + auto msg = static_cast(object); + ::google::protobuf::int32 size; (void)size; + int depth; (void)depth; + ::google::protobuf::uint32 tag; + ::google::protobuf::internal::ParseFunc parser_till_end; (void)parser_till_end; + auto ptr = begin; + while (ptr < end) { + ptr = ::google::protobuf::io::Parse32(ptr, &tag); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + switch (tag >> 3) { + // int32 num_satellites = 1; + case 1: { + if (static_cast<::google::protobuf::uint8>(tag) != 8) goto handle_unusual; + msg->set_num_satellites(::google::protobuf::internal::ReadVarint(&ptr)); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + break; + } + // .mavsdk.rpc.telemetry.FixType fix_type = 2; + case 2: { + if (static_cast<::google::protobuf::uint8>(tag) != 16) goto handle_unusual; + ::google::protobuf::uint64 val = ::google::protobuf::internal::ReadVarint(&ptr); + msg->set_fix_type(static_cast<::mavsdk::rpc::telemetry::FixType>(val)); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + break; + } + default: { + handle_unusual: + if ((tag & 7) == 4 || tag == 0) { + ctx->EndGroup(tag); + return ptr; + } + auto res = UnknownFieldParse(tag, {_InternalParse, msg}, + ptr, end, msg->_internal_metadata_.mutable_unknown_fields(), ctx); + ptr = res.first; + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr != nullptr); + if (res.second) return ptr; + } + } // switch + } // while + return ptr; +} +#else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +bool GpsInfo::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.GpsInfo) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // int32 num_satellites = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == (8 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &num_satellites_))); + } else { + goto handle_unusual; + } + break; + } + + // .mavsdk.rpc.telemetry.FixType fix_type = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == (16 & 0xFF)) { + int value = 0; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_fix_type(static_cast< ::mavsdk::rpc::telemetry::FixType >(value)); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.GpsInfo) + return true; +failure: + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.GpsInfo) + return false; +#undef DO_ +} +#endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + +void GpsInfo::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.GpsInfo) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // int32 num_satellites = 1; + if (this->num_satellites() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->num_satellites(), output); + } + + // .mavsdk.rpc.telemetry.FixType fix_type = 2; + if (this->fix_type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 2, this->fix_type(), output); + } + + if (_internal_metadata_.have_unknown_fields()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + _internal_metadata_.unknown_fields(), output); + } + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.GpsInfo) +} + +::google::protobuf::uint8* GpsInfo::InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.GpsInfo) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // int32 num_satellites = 1; + if (this->num_satellites() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->num_satellites(), target); + } + + // .mavsdk.rpc.telemetry.FixType fix_type = 2; + if (this->fix_type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 2, this->fix_type(), target); + } + + if (_internal_metadata_.have_unknown_fields()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.GpsInfo) + return target; +} + +size_t GpsInfo::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.GpsInfo) + size_t total_size = 0; + + if (_internal_metadata_.have_unknown_fields()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + _internal_metadata_.unknown_fields()); + } + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 num_satellites = 1; + if (this->num_satellites() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->num_satellites()); + } + + // .mavsdk.rpc.telemetry.FixType fix_type = 2; + if (this->fix_type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->fix_type()); + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void GpsInfo::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.GpsInfo) + GOOGLE_DCHECK_NE(&from, this); + const GpsInfo* source = + ::google::protobuf::DynamicCastToGenerated( + &from); + if (source == nullptr) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.GpsInfo) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.GpsInfo) + MergeFrom(*source); + } +} + +void GpsInfo::MergeFrom(const GpsInfo& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.GpsInfo) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.num_satellites() != 0) { + set_num_satellites(from.num_satellites()); + } + if (from.fix_type() != 0) { + set_fix_type(from.fix_type()); + } +} + +void GpsInfo::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.GpsInfo) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void GpsInfo::CopyFrom(const GpsInfo& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.GpsInfo) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool GpsInfo::IsInitialized() const { + return true; +} + +void GpsInfo::Swap(GpsInfo* other) { + if (other == this) return; + InternalSwap(other); +} +void GpsInfo::InternalSwap(GpsInfo* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); + swap(num_satellites_, other->num_satellites_); + swap(fix_type_, other->fix_type_); +} + +::google::protobuf::Metadata GpsInfo::GetMetadata() const { + ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); + return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; +} + + +// =================================================================== + +void Battery::InitAsDefaultInstance() { +} +class Battery::HasBitSetters { + public: +}; + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Battery::kVoltageVFieldNumber; +const int Battery::kRemainingPercentFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Battery::Battery() + : ::google::protobuf::Message(), _internal_metadata_(nullptr) { + SharedCtor(); + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.Battery) +} +Battery::Battery(const Battery& from) + : ::google::protobuf::Message(), + _internal_metadata_(nullptr) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&voltage_v_, &from.voltage_v_, + static_cast(reinterpret_cast(&remaining_percent_) - + reinterpret_cast(&voltage_v_)) + sizeof(remaining_percent_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.Battery) +} + +void Battery::SharedCtor() { + ::memset(&voltage_v_, 0, static_cast( + reinterpret_cast(&remaining_percent_) - + reinterpret_cast(&voltage_v_)) + sizeof(remaining_percent_)); +} + +Battery::~Battery() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.Battery) + SharedDtor(); +} + +void Battery::SharedDtor() { +} + +void Battery::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const Battery& Battery::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_Battery_telemetry_2ftelemetry_2eproto.base); + return *internal_default_instance(); +} + + +void Battery::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.Battery) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&voltage_v_, 0, static_cast( + reinterpret_cast(&remaining_percent_) - + reinterpret_cast(&voltage_v_)) + sizeof(remaining_percent_)); + _internal_metadata_.Clear(); +} + +#if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +const char* Battery::_InternalParse(const char* begin, const char* end, void* object, + ::google::protobuf::internal::ParseContext* ctx) { + auto msg = static_cast(object); + ::google::protobuf::int32 size; (void)size; + int depth; (void)depth; + ::google::protobuf::uint32 tag; + ::google::protobuf::internal::ParseFunc parser_till_end; (void)parser_till_end; + auto ptr = begin; + while (ptr < end) { + ptr = ::google::protobuf::io::Parse32(ptr, &tag); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + switch (tag >> 3) { + // float voltage_v = 1; + case 1: { + if (static_cast<::google::protobuf::uint8>(tag) != 13) goto handle_unusual; + msg->set_voltage_v(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + // float remaining_percent = 2; + case 2: { + if (static_cast<::google::protobuf::uint8>(tag) != 21) goto handle_unusual; + msg->set_remaining_percent(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + break; + } + default: { + handle_unusual: + if ((tag & 7) == 4 || tag == 0) { + ctx->EndGroup(tag); + return ptr; + } + auto res = UnknownFieldParse(tag, {_InternalParse, msg}, + ptr, end, msg->_internal_metadata_.mutable_unknown_fields(), ctx); + ptr = res.first; + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr != nullptr); + if (res.second) return ptr; + } + } // switch + } // while + return ptr; +} +#else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +bool Battery::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.Battery) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // float voltage_v = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == (13 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &voltage_v_))); + } else { + goto handle_unusual; + } + break; + } + + // float remaining_percent = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == (21 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, &remaining_percent_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.Battery) + return true; +failure: + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.Battery) + return false; +#undef DO_ +} +#endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + +void Battery::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.Battery) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // float voltage_v = 1; + if (this->voltage_v() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->voltage_v(), output); + } + + // float remaining_percent = 2; + if (this->remaining_percent() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->remaining_percent(), output); + } + + if (_internal_metadata_.have_unknown_fields()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + _internal_metadata_.unknown_fields(), output); + } + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.Battery) +} + +::google::protobuf::uint8* Battery::InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.Battery) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // float voltage_v = 1; + if (this->voltage_v() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->voltage_v(), target); + } + + // float remaining_percent = 2; + if (this->remaining_percent() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->remaining_percent(), target); + } + + if (_internal_metadata_.have_unknown_fields()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.Battery) + return target; +} + +size_t Battery::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.Battery) + size_t total_size = 0; + + if (_internal_metadata_.have_unknown_fields()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + _internal_metadata_.unknown_fields()); + } + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // float voltage_v = 1; + if (this->voltage_v() != 0) { + total_size += 1 + 4; + } + + // float remaining_percent = 2; + if (this->remaining_percent() != 0) { + total_size += 1 + 4; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Battery::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.Battery) + GOOGLE_DCHECK_NE(&from, this); + const Battery* source = + ::google::protobuf::DynamicCastToGenerated( + &from); + if (source == nullptr) { + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.Battery) + ::google::protobuf::internal::ReflectionOps::Merge(from, this); + } else { + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.Battery) + MergeFrom(*source); + } +} + +void Battery::MergeFrom(const Battery& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.Battery) + GOOGLE_DCHECK_NE(&from, this); + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + if (from.voltage_v() != 0) { + set_voltage_v(from.voltage_v()); + } + if (from.remaining_percent() != 0) { + set_remaining_percent(from.remaining_percent()); + } +} + +void Battery::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.Battery) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +void Battery::CopyFrom(const Battery& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.Battery) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +bool Battery::IsInitialized() const { + return true; +} + +void Battery::Swap(Battery* other) { + if (other == this) return; + InternalSwap(other); +} +void Battery::InternalSwap(Battery* other) { + using std::swap; + _internal_metadata_.Swap(&other->_internal_metadata_); + swap(voltage_v_, other->voltage_v_); + swap(remaining_percent_, other->remaining_percent_); +} + +::google::protobuf::Metadata Battery::GetMetadata() const { + ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); + return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; +} + + +// =================================================================== + +void Health::InitAsDefaultInstance() { +} +class Health::HasBitSetters { + public: +}; + +#if !defined(_MSC_VER) || _MSC_VER >= 1900 +const int Health::kIsGyrometerCalibrationOkFieldNumber; +const int Health::kIsAccelerometerCalibrationOkFieldNumber; +const int Health::kIsMagnetometerCalibrationOkFieldNumber; +const int Health::kIsLevelCalibrationOkFieldNumber; +const int Health::kIsLocalPositionOkFieldNumber; +const int Health::kIsGlobalPositionOkFieldNumber; +const int Health::kIsHomePositionOkFieldNumber; +#endif // !defined(_MSC_VER) || _MSC_VER >= 1900 + +Health::Health() + : ::google::protobuf::Message(), _internal_metadata_(nullptr) { + SharedCtor(); + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.Health) +} +Health::Health(const Health& from) + : ::google::protobuf::Message(), + _internal_metadata_(nullptr) { + _internal_metadata_.MergeFrom(from._internal_metadata_); + ::memcpy(&is_gyrometer_calibration_ok_, &from.is_gyrometer_calibration_ok_, + static_cast(reinterpret_cast(&is_home_position_ok_) - + reinterpret_cast(&is_gyrometer_calibration_ok_)) + sizeof(is_home_position_ok_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.Health) +} + +void Health::SharedCtor() { + ::memset(&is_gyrometer_calibration_ok_, 0, static_cast( + reinterpret_cast(&is_home_position_ok_) - + reinterpret_cast(&is_gyrometer_calibration_ok_)) + sizeof(is_home_position_ok_)); +} + +Health::~Health() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.Health) + SharedDtor(); +} + +void Health::SharedDtor() { +} + +void Health::SetCachedSize(int size) const { + _cached_size_.Set(size); +} +const Health& Health::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_Health_telemetry_2ftelemetry_2eproto.base); + return *internal_default_instance(); +} + + +void Health::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.Health) + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&is_gyrometer_calibration_ok_, 0, static_cast( + reinterpret_cast(&is_home_position_ok_) - + reinterpret_cast(&is_gyrometer_calibration_ok_)) + sizeof(is_home_position_ok_)); + _internal_metadata_.Clear(); +} + +#if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +const char* Health::_InternalParse(const char* begin, const char* end, void* object, + ::google::protobuf::internal::ParseContext* ctx) { + auto msg = static_cast(object); + ::google::protobuf::int32 size; (void)size; + int depth; (void)depth; + ::google::protobuf::uint32 tag; + ::google::protobuf::internal::ParseFunc parser_till_end; (void)parser_till_end; + auto ptr = begin; + while (ptr < end) { + ptr = ::google::protobuf::io::Parse32(ptr, &tag); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + switch (tag >> 3) { + // bool is_gyrometer_calibration_ok = 1; + case 1: { + if (static_cast<::google::protobuf::uint8>(tag) != 8) goto handle_unusual; + msg->set_is_gyrometer_calibration_ok(::google::protobuf::internal::ReadVarint(&ptr)); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + break; + } + // bool is_accelerometer_calibration_ok = 2; + case 2: { + if (static_cast<::google::protobuf::uint8>(tag) != 16) goto handle_unusual; + msg->set_is_accelerometer_calibration_ok(::google::protobuf::internal::ReadVarint(&ptr)); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + break; + } + // bool is_magnetometer_calibration_ok = 3; + case 3: { + if (static_cast<::google::protobuf::uint8>(tag) != 24) goto handle_unusual; + msg->set_is_magnetometer_calibration_ok(::google::protobuf::internal::ReadVarint(&ptr)); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + break; + } + // bool is_level_calibration_ok = 4; + case 4: { + if (static_cast<::google::protobuf::uint8>(tag) != 32) goto handle_unusual; + msg->set_is_level_calibration_ok(::google::protobuf::internal::ReadVarint(&ptr)); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + break; + } + // bool is_local_position_ok = 5; + case 5: { + if (static_cast<::google::protobuf::uint8>(tag) != 40) goto handle_unusual; + msg->set_is_local_position_ok(::google::protobuf::internal::ReadVarint(&ptr)); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + break; + } + // bool is_global_position_ok = 6; + case 6: { + if (static_cast<::google::protobuf::uint8>(tag) != 48) goto handle_unusual; + msg->set_is_global_position_ok(::google::protobuf::internal::ReadVarint(&ptr)); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + break; + } + // bool is_home_position_ok = 7; + case 7: { + if (static_cast<::google::protobuf::uint8>(tag) != 56) goto handle_unusual; + msg->set_is_home_position_ok(::google::protobuf::internal::ReadVarint(&ptr)); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + break; + } + default: { + handle_unusual: + if ((tag & 7) == 4 || tag == 0) { + ctx->EndGroup(tag); + return ptr; + } + auto res = UnknownFieldParse(tag, {_InternalParse, msg}, + ptr, end, msg->_internal_metadata_.mutable_unknown_fields(), ctx); + ptr = res.first; + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr != nullptr); + if (res.second) return ptr; + } + } // switch + } // while + return ptr; +} +#else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER +bool Health::MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) { +#define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure + ::google::protobuf::uint32 tag; + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.Health) + for (;;) { + ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); + tag = p.first; + if (!p.second) goto handle_unusual; + switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { + // bool is_gyrometer_calibration_ok = 1; + case 1: { + if (static_cast< ::google::protobuf::uint8>(tag) == (8 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_gyrometer_calibration_ok_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_accelerometer_calibration_ok = 2; + case 2: { + if (static_cast< ::google::protobuf::uint8>(tag) == (16 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_accelerometer_calibration_ok_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_magnetometer_calibration_ok = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == (24 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_magnetometer_calibration_ok_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_level_calibration_ok = 4; + case 4: { + if (static_cast< ::google::protobuf::uint8>(tag) == (32 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_level_calibration_ok_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_local_position_ok = 5; + case 5: { + if (static_cast< ::google::protobuf::uint8>(tag) == (40 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_local_position_ok_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_global_position_ok = 6; + case 6: { + if (static_cast< ::google::protobuf::uint8>(tag) == (48 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_global_position_ok_))); + } else { + goto handle_unusual; + } + break; + } + + // bool is_home_position_ok = 7; + case 7: { + if (static_cast< ::google::protobuf::uint8>(tag) == (56 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_home_position_ok_))); + } else { + goto handle_unusual; + } + break; + } + + default: { + handle_unusual: + if (tag == 0) { + goto success; + } + DO_(::google::protobuf::internal::WireFormat::SkipField( + input, tag, _internal_metadata_.mutable_unknown_fields())); + break; + } + } + } +success: + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.Health) + return true; +failure: + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.Health) + return false; +#undef DO_ +} +#endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + +void Health::SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const { + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.Health) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_gyrometer_calibration_ok = 1; + if (this->is_gyrometer_calibration_ok() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_gyrometer_calibration_ok(), output); + } + + // bool is_accelerometer_calibration_ok = 2; + if (this->is_accelerometer_calibration_ok() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->is_accelerometer_calibration_ok(), output); + } + + // bool is_magnetometer_calibration_ok = 3; + if (this->is_magnetometer_calibration_ok() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(3, this->is_magnetometer_calibration_ok(), output); + } + + // bool is_level_calibration_ok = 4; + if (this->is_level_calibration_ok() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(4, this->is_level_calibration_ok(), output); + } + + // bool is_local_position_ok = 5; + if (this->is_local_position_ok() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(5, this->is_local_position_ok(), output); + } + + // bool is_global_position_ok = 6; + if (this->is_global_position_ok() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(6, this->is_global_position_ok(), output); + } + + // bool is_home_position_ok = 7; + if (this->is_home_position_ok() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(7, this->is_home_position_ok(), output); + } + + if (_internal_metadata_.have_unknown_fields()) { + ::google::protobuf::internal::WireFormat::SerializeUnknownFields( + _internal_metadata_.unknown_fields(), output); + } + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.Health) +} + +::google::protobuf::uint8* Health::InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.Health) + ::google::protobuf::uint32 cached_has_bits = 0; + (void) cached_has_bits; + + // bool is_gyrometer_calibration_ok = 1; + if (this->is_gyrometer_calibration_ok() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_gyrometer_calibration_ok(), target); + } + + // bool is_accelerometer_calibration_ok = 2; + if (this->is_accelerometer_calibration_ok() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->is_accelerometer_calibration_ok(), target); + } + + // bool is_magnetometer_calibration_ok = 3; + if (this->is_magnetometer_calibration_ok() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(3, this->is_magnetometer_calibration_ok(), target); + } + + // bool is_level_calibration_ok = 4; + if (this->is_level_calibration_ok() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(4, this->is_level_calibration_ok(), target); + } + + // bool is_local_position_ok = 5; + if (this->is_local_position_ok() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(5, this->is_local_position_ok(), target); + } + + // bool is_global_position_ok = 6; + if (this->is_global_position_ok() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(6, this->is_global_position_ok(), target); + } + + // bool is_home_position_ok = 7; + if (this->is_home_position_ok() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(7, this->is_home_position_ok(), target); + } + + if (_internal_metadata_.have_unknown_fields()) { + target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields(), target); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.Health) + return target; +} + +size_t Health::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.Health) + size_t total_size = 0; + + if (_internal_metadata_.have_unknown_fields()) { + total_size += + ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( + _internal_metadata_.unknown_fields()); + } + ::google::protobuf::uint32 cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // bool is_gyrometer_calibration_ok = 1; + if (this->is_gyrometer_calibration_ok() != 0) { + total_size += 1 + 1; + } + + // bool is_accelerometer_calibration_ok = 2; + if (this->is_accelerometer_calibration_ok() != 0) { + total_size += 1 + 1; + } + + // bool is_magnetometer_calibration_ok = 3; + if (this->is_magnetometer_calibration_ok() != 0) { + total_size += 1 + 1; + } + + // bool is_level_calibration_ok = 4; + if (this->is_level_calibration_ok() != 0) { + total_size += 1 + 1; + } + + // bool is_local_position_ok = 5; + if (this->is_local_position_ok() != 0) { + total_size += 1 + 1; + } + + // bool is_global_position_ok = 6; + if (this->is_global_position_ok() != 0) { + total_size += 1 + 1; + } + + // bool is_home_position_ok = 7; + if (this->is_home_position_ok() != 0) { + total_size += 1 + 1; + } + + int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); + SetCachedSize(cached_size); + return total_size; +} + +void Health::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.Health) GOOGLE_DCHECK_NE(&from, this); - const GpsInfo* source = - ::google::protobuf::DynamicCastToGenerated( + const Health* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.GpsInfo) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.Health) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.GpsInfo) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.Health) MergeFrom(*source); } } -void GpsInfo::MergeFrom(const GpsInfo& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.GpsInfo) +void Health::MergeFrom(const Health& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.Health) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.num_satellites() != 0) { - set_num_satellites(from.num_satellites()); + if (from.is_gyrometer_calibration_ok() != 0) { + set_is_gyrometer_calibration_ok(from.is_gyrometer_calibration_ok()); } - if (from.fix_type() != 0) { - set_fix_type(from.fix_type()); + if (from.is_accelerometer_calibration_ok() != 0) { + set_is_accelerometer_calibration_ok(from.is_accelerometer_calibration_ok()); + } + if (from.is_magnetometer_calibration_ok() != 0) { + set_is_magnetometer_calibration_ok(from.is_magnetometer_calibration_ok()); + } + if (from.is_level_calibration_ok() != 0) { + set_is_level_calibration_ok(from.is_level_calibration_ok()); + } + if (from.is_local_position_ok() != 0) { + set_is_local_position_ok(from.is_local_position_ok()); + } + if (from.is_global_position_ok() != 0) { + set_is_global_position_ok(from.is_global_position_ok()); + } + if (from.is_home_position_ok() != 0) { + set_is_home_position_ok(from.is_home_position_ok()); } } -void GpsInfo::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.GpsInfo) +void Health::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.Health) if (&from == this) return; Clear(); MergeFrom(from); } -void GpsInfo::CopyFrom(const GpsInfo& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.GpsInfo) +void Health::CopyFrom(const Health& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.Health) if (&from == this) return; Clear(); MergeFrom(from); } -bool GpsInfo::IsInitialized() const { +bool Health::IsInitialized() const { return true; } -void GpsInfo::Swap(GpsInfo* other) { +void Health::Swap(Health* other) { if (other == this) return; InternalSwap(other); } -void GpsInfo::InternalSwap(GpsInfo* other) { +void Health::InternalSwap(Health* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(num_satellites_, other->num_satellites_); - swap(fix_type_, other->fix_type_); + swap(is_gyrometer_calibration_ok_, other->is_gyrometer_calibration_ok_); + swap(is_accelerometer_calibration_ok_, other->is_accelerometer_calibration_ok_); + swap(is_magnetometer_calibration_ok_, other->is_magnetometer_calibration_ok_); + swap(is_level_calibration_ok_, other->is_level_calibration_ok_); + swap(is_local_position_ok_, other->is_local_position_ok_); + swap(is_global_position_ok_, other->is_global_position_ok_); + swap(is_home_position_ok_, other->is_home_position_ok_); } -::google::protobuf::Metadata GpsInfo::GetMetadata() const { +::google::protobuf::Metadata Health::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -10451,71 +13370,72 @@ ::google::protobuf::Metadata GpsInfo::GetMetadata() const { // =================================================================== -void Battery::InitAsDefaultInstance() { +void RcStatus::InitAsDefaultInstance() { } -class Battery::HasBitSetters { +class RcStatus::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int Battery::kVoltageVFieldNumber; -const int Battery::kRemainingPercentFieldNumber; +const int RcStatus::kWasAvailableOnceFieldNumber; +const int RcStatus::kIsAvailableFieldNumber; +const int RcStatus::kSignalStrengthPercentFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -Battery::Battery() +RcStatus::RcStatus() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.Battery) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.RcStatus) } -Battery::Battery(const Battery& from) +RcStatus::RcStatus(const RcStatus& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - ::memcpy(&voltage_v_, &from.voltage_v_, - static_cast(reinterpret_cast(&remaining_percent_) - - reinterpret_cast(&voltage_v_)) + sizeof(remaining_percent_)); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.Battery) + ::memcpy(&was_available_once_, &from.was_available_once_, + static_cast(reinterpret_cast(&signal_strength_percent_) - + reinterpret_cast(&was_available_once_)) + sizeof(signal_strength_percent_)); + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.RcStatus) } -void Battery::SharedCtor() { - ::memset(&voltage_v_, 0, static_cast( - reinterpret_cast(&remaining_percent_) - - reinterpret_cast(&voltage_v_)) + sizeof(remaining_percent_)); +void RcStatus::SharedCtor() { + ::memset(&was_available_once_, 0, static_cast( + reinterpret_cast(&signal_strength_percent_) - + reinterpret_cast(&was_available_once_)) + sizeof(signal_strength_percent_)); } -Battery::~Battery() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.Battery) +RcStatus::~RcStatus() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.RcStatus) SharedDtor(); } -void Battery::SharedDtor() { +void RcStatus::SharedDtor() { } -void Battery::SetCachedSize(int size) const { +void RcStatus::SetCachedSize(int size) const { _cached_size_.Set(size); } -const Battery& Battery::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_Battery_telemetry_2ftelemetry_2eproto.base); +const RcStatus& RcStatus::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_RcStatus_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void Battery::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.Battery) +void RcStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.RcStatus) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&voltage_v_, 0, static_cast( - reinterpret_cast(&remaining_percent_) - - reinterpret_cast(&voltage_v_)) + sizeof(remaining_percent_)); + ::memset(&was_available_once_, 0, static_cast( + reinterpret_cast(&signal_strength_percent_) - + reinterpret_cast(&was_available_once_)) + sizeof(signal_strength_percent_)); _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* Battery::_InternalParse(const char* begin, const char* end, void* object, +const char* RcStatus::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -10525,17 +13445,24 @@ const char* Battery::_InternalParse(const char* begin, const char* end, void* ob ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // float voltage_v = 1; + // bool was_available_once = 1; case 1: { - if (static_cast<::google::protobuf::uint8>(tag) != 13) goto handle_unusual; - msg->set_voltage_v(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(float); + if (static_cast<::google::protobuf::uint8>(tag) != 8) goto handle_unusual; + msg->set_was_available_once(::google::protobuf::internal::ReadVarint(&ptr)); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); break; } - // float remaining_percent = 2; + // bool is_available = 2; case 2: { - if (static_cast<::google::protobuf::uint8>(tag) != 21) goto handle_unusual; - msg->set_remaining_percent(::google::protobuf::io::UnalignedLoad(ptr)); + if (static_cast<::google::protobuf::uint8>(tag) != 16) goto handle_unusual; + msg->set_is_available(::google::protobuf::internal::ReadVarint(&ptr)); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + break; + } + // float signal_strength_percent = 3; + case 3: { + if (static_cast<::google::protobuf::uint8>(tag) != 29) goto handle_unusual; + msg->set_signal_strength_percent(::google::protobuf::io::UnalignedLoad(ptr)); ptr += sizeof(float); break; } @@ -10556,36 +13483,49 @@ const char* Battery::_InternalParse(const char* begin, const char* end, void* ob return ptr; } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool Battery::MergePartialFromCodedStream( +bool RcStatus::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.Battery) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.RcStatus) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // float voltage_v = 1; + // bool was_available_once = 1; case 1: { - if (static_cast< ::google::protobuf::uint8>(tag) == (13 & 0xFF)) { + if (static_cast< ::google::protobuf::uint8>(tag) == (8 & 0xFF)) { DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &voltage_v_))); + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &was_available_once_))); } else { goto handle_unusual; } break; } - // float remaining_percent = 2; + // bool is_available = 2; case 2: { - if (static_cast< ::google::protobuf::uint8>(tag) == (21 & 0xFF)) { + if (static_cast< ::google::protobuf::uint8>(tag) == (16 & 0xFF)) { + + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( + input, &is_available_))); + } else { + goto handle_unusual; + } + break; + } + + // float signal_strength_percent = 3; + case 3: { + if (static_cast< ::google::protobuf::uint8>(tag) == (29 & 0xFF)) { DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &remaining_percent_))); + input, &signal_strength_percent_))); } else { goto handle_unusual; } @@ -10604,64 +13544,74 @@ bool Battery::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.Battery) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.RcStatus) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.Battery) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.RcStatus) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void Battery::SerializeWithCachedSizes( +void RcStatus::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.Battery) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.RcStatus) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // float voltage_v = 1; - if (this->voltage_v() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->voltage_v(), output); + // bool was_available_once = 1; + if (this->was_available_once() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->was_available_once(), output); } - // float remaining_percent = 2; - if (this->remaining_percent() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->remaining_percent(), output); + // bool is_available = 2; + if (this->is_available() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->is_available(), output); + } + + // float signal_strength_percent = 3; + if (this->signal_strength_percent() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->signal_strength_percent(), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.Battery) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.RcStatus) } -::google::protobuf::uint8* Battery::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* RcStatus::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.Battery) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.RcStatus) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // float voltage_v = 1; - if (this->voltage_v() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->voltage_v(), target); + // bool was_available_once = 1; + if (this->was_available_once() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->was_available_once(), target); } - // float remaining_percent = 2; - if (this->remaining_percent() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->remaining_percent(), target); + // bool is_available = 2; + if (this->is_available() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->is_available(), target); + } + + // float signal_strength_percent = 3; + if (this->signal_strength_percent() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->signal_strength_percent(), target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.Battery) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.RcStatus) return target; } -size_t Battery::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.Battery) +size_t RcStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.RcStatus) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -10673,13 +13623,18 @@ size_t Battery::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float voltage_v = 1; - if (this->voltage_v() != 0) { - total_size += 1 + 4; + // bool was_available_once = 1; + if (this->was_available_once() != 0) { + total_size += 1 + 1; } - // float remaining_percent = 2; - if (this->remaining_percent() != 0) { + // bool is_available = 2; + if (this->is_available() != 0) { + total_size += 1 + 1; + } + + // float signal_strength_percent = 3; + if (this->signal_strength_percent() != 0) { total_size += 1 + 4; } @@ -10688,66 +13643,70 @@ size_t Battery::ByteSizeLong() const { return total_size; } -void Battery::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.Battery) +void RcStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.RcStatus) GOOGLE_DCHECK_NE(&from, this); - const Battery* source = - ::google::protobuf::DynamicCastToGenerated( + const RcStatus* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.Battery) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.RcStatus) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.Battery) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.RcStatus) MergeFrom(*source); } } - -void Battery::MergeFrom(const Battery& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.Battery) + +void RcStatus::MergeFrom(const RcStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.RcStatus) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.voltage_v() != 0) { - set_voltage_v(from.voltage_v()); + if (from.was_available_once() != 0) { + set_was_available_once(from.was_available_once()); } - if (from.remaining_percent() != 0) { - set_remaining_percent(from.remaining_percent()); + if (from.is_available() != 0) { + set_is_available(from.is_available()); + } + if (from.signal_strength_percent() != 0) { + set_signal_strength_percent(from.signal_strength_percent()); } } -void Battery::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.Battery) +void RcStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.RcStatus) if (&from == this) return; Clear(); MergeFrom(from); } -void Battery::CopyFrom(const Battery& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.Battery) +void RcStatus::CopyFrom(const RcStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.RcStatus) if (&from == this) return; Clear(); MergeFrom(from); } -bool Battery::IsInitialized() const { +bool RcStatus::IsInitialized() const { return true; } -void Battery::Swap(Battery* other) { +void RcStatus::Swap(RcStatus* other) { if (other == this) return; InternalSwap(other); } -void Battery::InternalSwap(Battery* other) { +void RcStatus::InternalSwap(RcStatus* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(voltage_v_, other->voltage_v_); - swap(remaining_percent_, other->remaining_percent_); + swap(was_available_once_, other->was_available_once_); + swap(is_available_, other->is_available_); + swap(signal_strength_percent_, other->signal_strength_percent_); } -::google::protobuf::Metadata Battery::GetMetadata() const { +::google::protobuf::Metadata RcStatus::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -10755,76 +13714,74 @@ ::google::protobuf::Metadata Battery::GetMetadata() const { // =================================================================== -void Health::InitAsDefaultInstance() { +void StatusText::InitAsDefaultInstance() { } -class Health::HasBitSetters { +class StatusText::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int Health::kIsGyrometerCalibrationOkFieldNumber; -const int Health::kIsAccelerometerCalibrationOkFieldNumber; -const int Health::kIsMagnetometerCalibrationOkFieldNumber; -const int Health::kIsLevelCalibrationOkFieldNumber; -const int Health::kIsLocalPositionOkFieldNumber; -const int Health::kIsGlobalPositionOkFieldNumber; -const int Health::kIsHomePositionOkFieldNumber; +const int StatusText::kTypeFieldNumber; +const int StatusText::kTextFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -Health::Health() +StatusText::StatusText() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.Health) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.StatusText) } -Health::Health(const Health& from) +StatusText::StatusText(const StatusText& from) : ::google::protobuf::Message(), _internal_metadata_(nullptr) { _internal_metadata_.MergeFrom(from._internal_metadata_); - ::memcpy(&is_gyrometer_calibration_ok_, &from.is_gyrometer_calibration_ok_, - static_cast(reinterpret_cast(&is_home_position_ok_) - - reinterpret_cast(&is_gyrometer_calibration_ok_)) + sizeof(is_home_position_ok_)); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.Health) + text_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + if (from.text().size() > 0) { + text_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.text_); + } + type_ = from.type_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.StatusText) } -void Health::SharedCtor() { - ::memset(&is_gyrometer_calibration_ok_, 0, static_cast( - reinterpret_cast(&is_home_position_ok_) - - reinterpret_cast(&is_gyrometer_calibration_ok_)) + sizeof(is_home_position_ok_)); +void StatusText::SharedCtor() { + ::google::protobuf::internal::InitSCC( + &scc_info_StatusText_telemetry_2ftelemetry_2eproto.base); + text_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + type_ = 0; } -Health::~Health() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.Health) +StatusText::~StatusText() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.StatusText) SharedDtor(); } -void Health::SharedDtor() { +void StatusText::SharedDtor() { + text_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); } -void Health::SetCachedSize(int size) const { +void StatusText::SetCachedSize(int size) const { _cached_size_.Set(size); } -const Health& Health::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_Health_telemetry_2ftelemetry_2eproto.base); +const StatusText& StatusText::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_StatusText_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void Health::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.Health) +void StatusText::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.StatusText) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&is_gyrometer_calibration_ok_, 0, static_cast( - reinterpret_cast(&is_home_position_ok_) - - reinterpret_cast(&is_gyrometer_calibration_ok_)) + sizeof(is_home_position_ok_)); + text_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); + type_ = 0; _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* Health::_InternalParse(const char* begin, const char* end, void* object, +const char* StatusText::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -10834,53 +13791,28 @@ const char* Health::_InternalParse(const char* begin, const char* end, void* obj ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // bool is_gyrometer_calibration_ok = 1; + // .mavsdk.rpc.telemetry.StatusText.StatusType type = 1; case 1: { if (static_cast<::google::protobuf::uint8>(tag) != 8) goto handle_unusual; - msg->set_is_gyrometer_calibration_ok(::google::protobuf::internal::ReadVarint(&ptr)); + ::google::protobuf::uint64 val = ::google::protobuf::internal::ReadVarint(&ptr); + msg->set_type(static_cast<::mavsdk::rpc::telemetry::StatusText_StatusType>(val)); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); break; } - // bool is_accelerometer_calibration_ok = 2; + // string text = 2; case 2: { - if (static_cast<::google::protobuf::uint8>(tag) != 16) goto handle_unusual; - msg->set_is_accelerometer_calibration_ok(::google::protobuf::internal::ReadVarint(&ptr)); - GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - break; - } - // bool is_magnetometer_calibration_ok = 3; - case 3: { - if (static_cast<::google::protobuf::uint8>(tag) != 24) goto handle_unusual; - msg->set_is_magnetometer_calibration_ok(::google::protobuf::internal::ReadVarint(&ptr)); - GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - break; - } - // bool is_level_calibration_ok = 4; - case 4: { - if (static_cast<::google::protobuf::uint8>(tag) != 32) goto handle_unusual; - msg->set_is_level_calibration_ok(::google::protobuf::internal::ReadVarint(&ptr)); - GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - break; - } - // bool is_local_position_ok = 5; - case 5: { - if (static_cast<::google::protobuf::uint8>(tag) != 40) goto handle_unusual; - msg->set_is_local_position_ok(::google::protobuf::internal::ReadVarint(&ptr)); - GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - break; - } - // bool is_global_position_ok = 6; - case 6: { - if (static_cast<::google::protobuf::uint8>(tag) != 48) goto handle_unusual; - msg->set_is_global_position_ok(::google::protobuf::internal::ReadVarint(&ptr)); - GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - break; - } - // bool is_home_position_ok = 7; - case 7: { - if (static_cast<::google::protobuf::uint8>(tag) != 56) goto handle_unusual; - msg->set_is_home_position_ok(::google::protobuf::internal::ReadVarint(&ptr)); + if (static_cast<::google::protobuf::uint8>(tag) != 18) goto handle_unusual; + ptr = ::google::protobuf::io::ReadSize(ptr, &size); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + ctx->extra_parse_data().SetFieldName("mavsdk.rpc.telemetry.StatusText.text"); + object = msg->mutable_text(); + if (size > end - ptr + ::google::protobuf::internal::ParseContext::kSlopBytes) { + parser_till_end = ::google::protobuf::internal::GreedyStringParserUTF8; + goto string_till_end; + } + GOOGLE_PROTOBUF_PARSER_ASSERT(::google::protobuf::internal::StringCheckUTF8(ptr, size, ctx)); + ::google::protobuf::internal::InlineGreedyStringParser(object, ptr, size, ctx); + ptr += size; break; } default: { @@ -10898,103 +13830,48 @@ const char* Health::_InternalParse(const char* begin, const char* end, void* obj } // switch } // while return ptr; +string_till_end: + static_cast<::std::string*>(object)->clear(); + static_cast<::std::string*>(object)->reserve(size); + goto len_delim_till_end; +len_delim_till_end: + return ctx->StoreAndTailCall(ptr, end, {_InternalParse, msg}, + {parser_till_end, object}, size); } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool Health::MergePartialFromCodedStream( +bool StatusText::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.Health) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.StatusText) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // bool is_gyrometer_calibration_ok = 1; + // .mavsdk.rpc.telemetry.StatusText.StatusType type = 1; case 1: { if (static_cast< ::google::protobuf::uint8>(tag) == (8 & 0xFF)) { - + int value = 0; DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( - input, &is_gyrometer_calibration_ok_))); + int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( + input, &value))); + set_type(static_cast< ::mavsdk::rpc::telemetry::StatusText_StatusType >(value)); } else { goto handle_unusual; } break; } - // bool is_accelerometer_calibration_ok = 2; + // string text = 2; case 2: { - if (static_cast< ::google::protobuf::uint8>(tag) == (16 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( - input, &is_accelerometer_calibration_ok_))); - } else { - goto handle_unusual; - } - break; - } - - // bool is_magnetometer_calibration_ok = 3; - case 3: { - if (static_cast< ::google::protobuf::uint8>(tag) == (24 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( - input, &is_magnetometer_calibration_ok_))); - } else { - goto handle_unusual; - } - break; - } - - // bool is_level_calibration_ok = 4; - case 4: { - if (static_cast< ::google::protobuf::uint8>(tag) == (32 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( - input, &is_level_calibration_ok_))); - } else { - goto handle_unusual; - } - break; - } - - // bool is_local_position_ok = 5; - case 5: { - if (static_cast< ::google::protobuf::uint8>(tag) == (40 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( - input, &is_local_position_ok_))); - } else { - goto handle_unusual; - } - break; - } - - // bool is_global_position_ok = 6; - case 6: { - if (static_cast< ::google::protobuf::uint8>(tag) == (48 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( - input, &is_global_position_ok_))); - } else { - goto handle_unusual; - } - break; - } - - // bool is_home_position_ok = 7; - case 7: { - if (static_cast< ::google::protobuf::uint8>(tag) == (56 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( - input, &is_home_position_ok_))); + if (static_cast< ::google::protobuf::uint8>(tag) == (18 & 0xFF)) { + DO_(::google::protobuf::internal::WireFormatLite::ReadString( + input, this->mutable_text())); + DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->text().data(), static_cast(this->text().length()), + ::google::protobuf::internal::WireFormatLite::PARSE, + "mavsdk.rpc.telemetry.StatusText.text")); } else { goto handle_unusual; } @@ -11013,114 +13890,77 @@ bool Health::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.Health) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.StatusText) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.Health) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.StatusText) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void Health::SerializeWithCachedSizes( +void StatusText::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.Health) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.StatusText) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // bool is_gyrometer_calibration_ok = 1; - if (this->is_gyrometer_calibration_ok() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->is_gyrometer_calibration_ok(), output); - } - - // bool is_accelerometer_calibration_ok = 2; - if (this->is_accelerometer_calibration_ok() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->is_accelerometer_calibration_ok(), output); - } - - // bool is_magnetometer_calibration_ok = 3; - if (this->is_magnetometer_calibration_ok() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteBool(3, this->is_magnetometer_calibration_ok(), output); - } - - // bool is_level_calibration_ok = 4; - if (this->is_level_calibration_ok() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteBool(4, this->is_level_calibration_ok(), output); - } - - // bool is_local_position_ok = 5; - if (this->is_local_position_ok() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteBool(5, this->is_local_position_ok(), output); - } - - // bool is_global_position_ok = 6; - if (this->is_global_position_ok() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteBool(6, this->is_global_position_ok(), output); + // .mavsdk.rpc.telemetry.StatusText.StatusType type = 1; + if (this->type() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteEnum( + 1, this->type(), output); } - // bool is_home_position_ok = 7; - if (this->is_home_position_ok() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteBool(7, this->is_home_position_ok(), output); + // string text = 2; + if (this->text().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->text().data(), static_cast(this->text().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "mavsdk.rpc.telemetry.StatusText.text"); + ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( + 2, this->text(), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.Health) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.StatusText) } -::google::protobuf::uint8* Health::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* StatusText::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.Health) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.StatusText) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // bool is_gyrometer_calibration_ok = 1; - if (this->is_gyrometer_calibration_ok() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->is_gyrometer_calibration_ok(), target); - } - - // bool is_accelerometer_calibration_ok = 2; - if (this->is_accelerometer_calibration_ok() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->is_accelerometer_calibration_ok(), target); - } - - // bool is_magnetometer_calibration_ok = 3; - if (this->is_magnetometer_calibration_ok() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(3, this->is_magnetometer_calibration_ok(), target); - } - - // bool is_level_calibration_ok = 4; - if (this->is_level_calibration_ok() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(4, this->is_level_calibration_ok(), target); - } - - // bool is_local_position_ok = 5; - if (this->is_local_position_ok() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(5, this->is_local_position_ok(), target); - } - - // bool is_global_position_ok = 6; - if (this->is_global_position_ok() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(6, this->is_global_position_ok(), target); + // .mavsdk.rpc.telemetry.StatusText.StatusType type = 1; + if (this->type() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( + 1, this->type(), target); } - // bool is_home_position_ok = 7; - if (this->is_home_position_ok() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(7, this->is_home_position_ok(), target); + // string text = 2; + if (this->text().size() > 0) { + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + this->text().data(), static_cast(this->text().length()), + ::google::protobuf::internal::WireFormatLite::SERIALIZE, + "mavsdk.rpc.telemetry.StatusText.text"); + target = + ::google::protobuf::internal::WireFormatLite::WriteStringToArray( + 2, this->text(), target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.Health) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.StatusText) return target; } -size_t Health::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.Health) +size_t StatusText::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.StatusText) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -11132,39 +13972,17 @@ size_t Health::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // bool is_gyrometer_calibration_ok = 1; - if (this->is_gyrometer_calibration_ok() != 0) { - total_size += 1 + 1; - } - - // bool is_accelerometer_calibration_ok = 2; - if (this->is_accelerometer_calibration_ok() != 0) { - total_size += 1 + 1; - } - - // bool is_magnetometer_calibration_ok = 3; - if (this->is_magnetometer_calibration_ok() != 0) { - total_size += 1 + 1; - } - - // bool is_level_calibration_ok = 4; - if (this->is_level_calibration_ok() != 0) { - total_size += 1 + 1; - } - - // bool is_local_position_ok = 5; - if (this->is_local_position_ok() != 0) { - total_size += 1 + 1; - } - - // bool is_global_position_ok = 6; - if (this->is_global_position_ok() != 0) { - total_size += 1 + 1; + // string text = 2; + if (this->text().size() > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::StringSize( + this->text()); } - // bool is_home_position_ok = 7; - if (this->is_home_position_ok() != 0) { - total_size += 1 + 1; + // .mavsdk.rpc.telemetry.StatusText.StatusType type = 1; + if (this->type() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::EnumSize(this->type()); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -11172,86 +13990,68 @@ size_t Health::ByteSizeLong() const { return total_size; } -void Health::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.Health) +void StatusText::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.StatusText) GOOGLE_DCHECK_NE(&from, this); - const Health* source = - ::google::protobuf::DynamicCastToGenerated( + const StatusText* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.Health) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.StatusText) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.Health) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.StatusText) MergeFrom(*source); } } -void Health::MergeFrom(const Health& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.Health) +void StatusText::MergeFrom(const StatusText& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.StatusText) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.is_gyrometer_calibration_ok() != 0) { - set_is_gyrometer_calibration_ok(from.is_gyrometer_calibration_ok()); - } - if (from.is_accelerometer_calibration_ok() != 0) { - set_is_accelerometer_calibration_ok(from.is_accelerometer_calibration_ok()); - } - if (from.is_magnetometer_calibration_ok() != 0) { - set_is_magnetometer_calibration_ok(from.is_magnetometer_calibration_ok()); - } - if (from.is_level_calibration_ok() != 0) { - set_is_level_calibration_ok(from.is_level_calibration_ok()); - } - if (from.is_local_position_ok() != 0) { - set_is_local_position_ok(from.is_local_position_ok()); - } - if (from.is_global_position_ok() != 0) { - set_is_global_position_ok(from.is_global_position_ok()); + if (from.text().size() > 0) { + + text_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.text_); } - if (from.is_home_position_ok() != 0) { - set_is_home_position_ok(from.is_home_position_ok()); + if (from.type() != 0) { + set_type(from.type()); } } -void Health::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.Health) +void StatusText::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.StatusText) if (&from == this) return; Clear(); MergeFrom(from); } -void Health::CopyFrom(const Health& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.Health) +void StatusText::CopyFrom(const StatusText& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.StatusText) if (&from == this) return; Clear(); MergeFrom(from); } -bool Health::IsInitialized() const { +bool StatusText::IsInitialized() const { return true; } -void Health::Swap(Health* other) { +void StatusText::Swap(StatusText* other) { if (other == this) return; InternalSwap(other); } -void Health::InternalSwap(Health* other) { +void StatusText::InternalSwap(StatusText* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(is_gyrometer_calibration_ok_, other->is_gyrometer_calibration_ok_); - swap(is_accelerometer_calibration_ok_, other->is_accelerometer_calibration_ok_); - swap(is_magnetometer_calibration_ok_, other->is_magnetometer_calibration_ok_); - swap(is_level_calibration_ok_, other->is_level_calibration_ok_); - swap(is_local_position_ok_, other->is_local_position_ok_); - swap(is_global_position_ok_, other->is_global_position_ok_); - swap(is_home_position_ok_, other->is_home_position_ok_); + text_.Swap(&other->text_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), + GetArenaNoVirtual()); + swap(type_, other->type_); } -::google::protobuf::Metadata Health::GetMetadata() const { +::google::protobuf::Metadata StatusText::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -11259,72 +14059,67 @@ ::google::protobuf::Metadata Health::GetMetadata() const { // =================================================================== -void RcStatus::InitAsDefaultInstance() { +void ActuatorControlTarget::InitAsDefaultInstance() { } -class RcStatus::HasBitSetters { +class ActuatorControlTarget::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int RcStatus::kWasAvailableOnceFieldNumber; -const int RcStatus::kIsAvailableFieldNumber; -const int RcStatus::kSignalStrengthPercentFieldNumber; +const int ActuatorControlTarget::kGroupFieldNumber; +const int ActuatorControlTarget::kControlsFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -RcStatus::RcStatus() +ActuatorControlTarget::ActuatorControlTarget() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.RcStatus) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.ActuatorControlTarget) } -RcStatus::RcStatus(const RcStatus& from) +ActuatorControlTarget::ActuatorControlTarget(const ActuatorControlTarget& from) : ::google::protobuf::Message(), - _internal_metadata_(nullptr) { + _internal_metadata_(nullptr), + controls_(from.controls_) { _internal_metadata_.MergeFrom(from._internal_metadata_); - ::memcpy(&was_available_once_, &from.was_available_once_, - static_cast(reinterpret_cast(&signal_strength_percent_) - - reinterpret_cast(&was_available_once_)) + sizeof(signal_strength_percent_)); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.RcStatus) + group_ = from.group_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.ActuatorControlTarget) } -void RcStatus::SharedCtor() { - ::memset(&was_available_once_, 0, static_cast( - reinterpret_cast(&signal_strength_percent_) - - reinterpret_cast(&was_available_once_)) + sizeof(signal_strength_percent_)); +void ActuatorControlTarget::SharedCtor() { + group_ = 0; } -RcStatus::~RcStatus() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.RcStatus) +ActuatorControlTarget::~ActuatorControlTarget() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.ActuatorControlTarget) SharedDtor(); } -void RcStatus::SharedDtor() { +void ActuatorControlTarget::SharedDtor() { } -void RcStatus::SetCachedSize(int size) const { +void ActuatorControlTarget::SetCachedSize(int size) const { _cached_size_.Set(size); } -const RcStatus& RcStatus::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_RcStatus_telemetry_2ftelemetry_2eproto.base); +const ActuatorControlTarget& ActuatorControlTarget::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_ActuatorControlTarget_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void RcStatus::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.RcStatus) +void ActuatorControlTarget::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.ActuatorControlTarget) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&was_available_once_, 0, static_cast( - reinterpret_cast(&signal_strength_percent_) - - reinterpret_cast(&was_available_once_)) + sizeof(signal_strength_percent_)); + controls_.Clear(); + group_ = 0; _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* RcStatus::_InternalParse(const char* begin, const char* end, void* object, +const char* ActuatorControlTarget::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -11334,27 +14129,33 @@ const char* RcStatus::_InternalParse(const char* begin, const char* end, void* o ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // bool was_available_once = 1; + // int32 group = 1; case 1: { if (static_cast<::google::protobuf::uint8>(tag) != 8) goto handle_unusual; - msg->set_was_available_once(::google::protobuf::internal::ReadVarint(&ptr)); - GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - break; - } - // bool is_available = 2; - case 2: { - if (static_cast<::google::protobuf::uint8>(tag) != 16) goto handle_unusual; - msg->set_is_available(::google::protobuf::internal::ReadVarint(&ptr)); + msg->set_group(::google::protobuf::internal::ReadVarint(&ptr)); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); break; } - // float signal_strength_percent = 3; - case 3: { - if (static_cast<::google::protobuf::uint8>(tag) != 29) goto handle_unusual; - msg->set_signal_strength_percent(::google::protobuf::io::UnalignedLoad(ptr)); - ptr += sizeof(float); - break; - } + // repeated float controls = 2; + case 2: { + if (static_cast<::google::protobuf::uint8>(tag) == 18) { + ptr = ::google::protobuf::io::ReadSize(ptr, &size); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + parser_till_end = ::google::protobuf::internal::PackedFloatParser; + object = msg->mutable_controls(); + if (size > end - ptr) goto len_delim_till_end; + auto newend = ptr + size; + if (size) ptr = parser_till_end(ptr, newend, object, ctx); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr == newend); + break; + } else if (static_cast<::google::protobuf::uint8>(tag) != 21) goto handle_unusual; + do { + msg->add_controls(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + if (ptr >= end) break; + } while ((::google::protobuf::io::UnalignedLoad<::google::protobuf::uint64>(ptr) & 255) == 21 && (ptr += 1)); + break; + } default: { handle_unusual: if ((tag & 7) == 4 || tag == 0) { @@ -11370,51 +14171,44 @@ const char* RcStatus::_InternalParse(const char* begin, const char* end, void* o } // switch } // while return ptr; +len_delim_till_end: + return ctx->StoreAndTailCall(ptr, end, {_InternalParse, msg}, + {parser_till_end, object}, size); } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool RcStatus::MergePartialFromCodedStream( +bool ActuatorControlTarget::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.RcStatus) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.ActuatorControlTarget) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // bool was_available_once = 1; + // int32 group = 1; case 1: { if (static_cast< ::google::protobuf::uint8>(tag) == (8 & 0xFF)) { DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( - input, &was_available_once_))); + ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( + input, &group_))); } else { goto handle_unusual; } break; } - // bool is_available = 2; + // repeated float controls = 2; case 2: { - if (static_cast< ::google::protobuf::uint8>(tag) == (16 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>( - input, &is_available_))); - } else { - goto handle_unusual; - } - break; - } - - // float signal_strength_percent = 3; - case 3: { - if (static_cast< ::google::protobuf::uint8>(tag) == (29 & 0xFF)) { - - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< + if (static_cast< ::google::protobuf::uint8>(tag) == (18 & 0xFF)) { + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &signal_strength_percent_))); + input, this->mutable_controls()))); + } else if (static_cast< ::google::protobuf::uint8>(tag) == (21 & 0xFF)) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + 1, 18u, input, this->mutable_controls()))); } else { goto handle_unusual; } @@ -11433,74 +14227,76 @@ bool RcStatus::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.RcStatus) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.ActuatorControlTarget) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.RcStatus) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.ActuatorControlTarget) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void RcStatus::SerializeWithCachedSizes( +void ActuatorControlTarget::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.RcStatus) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.ActuatorControlTarget) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // bool was_available_once = 1; - if (this->was_available_once() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteBool(1, this->was_available_once(), output); - } - - // bool is_available = 2; - if (this->is_available() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteBool(2, this->is_available(), output); + // int32 group = 1; + if (this->group() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->group(), output); } - // float signal_strength_percent = 3; - if (this->signal_strength_percent() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->signal_strength_percent(), output); + // repeated float controls = 2; + if (this->controls_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(2, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_controls_cached_byte_size_.load( + std::memory_order_relaxed)); + ::google::protobuf::internal::WireFormatLite::WriteFloatArray( + this->controls().data(), this->controls_size(), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.RcStatus) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.ActuatorControlTarget) } -::google::protobuf::uint8* RcStatus::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* ActuatorControlTarget::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.RcStatus) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.ActuatorControlTarget) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // bool was_available_once = 1; - if (this->was_available_once() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->was_available_once(), target); - } - - // bool is_available = 2; - if (this->is_available() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(2, this->is_available(), target); + // int32 group = 1; + if (this->group() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->group(), target); } - // float signal_strength_percent = 3; - if (this->signal_strength_percent() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->signal_strength_percent(), target); + // repeated float controls = 2; + if (this->controls_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 2, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _controls_cached_byte_size_.load(std::memory_order_relaxed), + target); + target = ::google::protobuf::internal::WireFormatLite:: + WriteFloatNoTagToArray(this->controls_, target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.RcStatus) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.ActuatorControlTarget) return target; } -size_t RcStatus::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.RcStatus) +size_t ActuatorControlTarget::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.ActuatorControlTarget) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -11512,19 +14308,26 @@ size_t RcStatus::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // bool was_available_once = 1; - if (this->was_available_once() != 0) { - total_size += 1 + 1; - } - - // bool is_available = 2; - if (this->is_available() != 0) { - total_size += 1 + 1; + // repeated float controls = 2; + { + unsigned int count = static_cast(this->controls_size()); + size_t data_size = 4UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + static_cast<::google::protobuf::int32>(data_size)); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + _controls_cached_byte_size_.store(cached_size, + std::memory_order_relaxed); + total_size += data_size; } - // float signal_strength_percent = 3; - if (this->signal_strength_percent() != 0) { - total_size += 1 + 4; + // int32 group = 1; + if (this->group() != 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + this->group()); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -11532,70 +14335,64 @@ size_t RcStatus::ByteSizeLong() const { return total_size; } -void RcStatus::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.RcStatus) +void ActuatorControlTarget::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.ActuatorControlTarget) GOOGLE_DCHECK_NE(&from, this); - const RcStatus* source = - ::google::protobuf::DynamicCastToGenerated( + const ActuatorControlTarget* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.RcStatus) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.ActuatorControlTarget) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.RcStatus) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.ActuatorControlTarget) MergeFrom(*source); } } -void RcStatus::MergeFrom(const RcStatus& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.RcStatus) +void ActuatorControlTarget::MergeFrom(const ActuatorControlTarget& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.ActuatorControlTarget) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.was_available_once() != 0) { - set_was_available_once(from.was_available_once()); - } - if (from.is_available() != 0) { - set_is_available(from.is_available()); - } - if (from.signal_strength_percent() != 0) { - set_signal_strength_percent(from.signal_strength_percent()); + controls_.MergeFrom(from.controls_); + if (from.group() != 0) { + set_group(from.group()); } } -void RcStatus::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.RcStatus) +void ActuatorControlTarget::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.ActuatorControlTarget) if (&from == this) return; Clear(); MergeFrom(from); } -void RcStatus::CopyFrom(const RcStatus& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.RcStatus) +void ActuatorControlTarget::CopyFrom(const ActuatorControlTarget& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.ActuatorControlTarget) if (&from == this) return; Clear(); MergeFrom(from); } -bool RcStatus::IsInitialized() const { +bool ActuatorControlTarget::IsInitialized() const { return true; } -void RcStatus::Swap(RcStatus* other) { +void ActuatorControlTarget::Swap(ActuatorControlTarget* other) { if (other == this) return; InternalSwap(other); } -void RcStatus::InternalSwap(RcStatus* other) { +void ActuatorControlTarget::InternalSwap(ActuatorControlTarget* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - swap(was_available_once_, other->was_available_once_); - swap(is_available_, other->is_available_); - swap(signal_strength_percent_, other->signal_strength_percent_); + controls_.InternalSwap(&other->controls_); + swap(group_, other->group_); } -::google::protobuf::Metadata RcStatus::GetMetadata() const { +::google::protobuf::Metadata ActuatorControlTarget::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -11603,74 +14400,67 @@ ::google::protobuf::Metadata RcStatus::GetMetadata() const { // =================================================================== -void StatusText::InitAsDefaultInstance() { +void ActuatorOutputStatus::InitAsDefaultInstance() { } -class StatusText::HasBitSetters { +class ActuatorOutputStatus::HasBitSetters { public: }; #if !defined(_MSC_VER) || _MSC_VER >= 1900 -const int StatusText::kTypeFieldNumber; -const int StatusText::kTextFieldNumber; +const int ActuatorOutputStatus::kActiveFieldNumber; +const int ActuatorOutputStatus::kActuatorFieldNumber; #endif // !defined(_MSC_VER) || _MSC_VER >= 1900 -StatusText::StatusText() +ActuatorOutputStatus::ActuatorOutputStatus() : ::google::protobuf::Message(), _internal_metadata_(nullptr) { SharedCtor(); - // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.StatusText) + // @@protoc_insertion_point(constructor:mavsdk.rpc.telemetry.ActuatorOutputStatus) } -StatusText::StatusText(const StatusText& from) +ActuatorOutputStatus::ActuatorOutputStatus(const ActuatorOutputStatus& from) : ::google::protobuf::Message(), - _internal_metadata_(nullptr) { + _internal_metadata_(nullptr), + actuator_(from.actuator_) { _internal_metadata_.MergeFrom(from._internal_metadata_); - text_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); - if (from.text().size() > 0) { - text_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.text_); - } - type_ = from.type_; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.StatusText) + active_ = from.active_; + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.telemetry.ActuatorOutputStatus) } -void StatusText::SharedCtor() { - ::google::protobuf::internal::InitSCC( - &scc_info_StatusText_telemetry_2ftelemetry_2eproto.base); - text_.UnsafeSetDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); - type_ = 0; +void ActuatorOutputStatus::SharedCtor() { + active_ = 0u; } -StatusText::~StatusText() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.StatusText) +ActuatorOutputStatus::~ActuatorOutputStatus() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.telemetry.ActuatorOutputStatus) SharedDtor(); } -void StatusText::SharedDtor() { - text_.DestroyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); +void ActuatorOutputStatus::SharedDtor() { } -void StatusText::SetCachedSize(int size) const { +void ActuatorOutputStatus::SetCachedSize(int size) const { _cached_size_.Set(size); } -const StatusText& StatusText::default_instance() { - ::google::protobuf::internal::InitSCC(&::scc_info_StatusText_telemetry_2ftelemetry_2eproto.base); +const ActuatorOutputStatus& ActuatorOutputStatus::default_instance() { + ::google::protobuf::internal::InitSCC(&::scc_info_ActuatorOutputStatus_telemetry_2ftelemetry_2eproto.base); return *internal_default_instance(); } -void StatusText::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.StatusText) +void ActuatorOutputStatus::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.telemetry.ActuatorOutputStatus) ::google::protobuf::uint32 cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - text_.ClearToEmptyNoArena(&::google::protobuf::internal::GetEmptyStringAlreadyInited()); - type_ = 0; + actuator_.Clear(); + active_ = 0u; _internal_metadata_.Clear(); } #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -const char* StatusText::_InternalParse(const char* begin, const char* end, void* object, +const char* ActuatorOutputStatus::_InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx) { - auto msg = static_cast(object); + auto msg = static_cast(object); ::google::protobuf::int32 size; (void)size; int depth; (void)depth; ::google::protobuf::uint32 tag; @@ -11680,28 +14470,31 @@ const char* StatusText::_InternalParse(const char* begin, const char* end, void* ptr = ::google::protobuf::io::Parse32(ptr, &tag); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); switch (tag >> 3) { - // .mavsdk.rpc.telemetry.StatusText.StatusType type = 1; + // uint32 active = 1; case 1: { if (static_cast<::google::protobuf::uint8>(tag) != 8) goto handle_unusual; - ::google::protobuf::uint64 val = ::google::protobuf::internal::ReadVarint(&ptr); - msg->set_type(static_cast<::mavsdk::rpc::telemetry::StatusText_StatusType>(val)); + msg->set_active(::google::protobuf::internal::ReadVarint(&ptr)); GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); break; } - // string text = 2; + // repeated float actuator = 2; case 2: { - if (static_cast<::google::protobuf::uint8>(tag) != 18) goto handle_unusual; - ptr = ::google::protobuf::io::ReadSize(ptr, &size); - GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); - ctx->extra_parse_data().SetFieldName("mavsdk.rpc.telemetry.StatusText.text"); - object = msg->mutable_text(); - if (size > end - ptr + ::google::protobuf::internal::ParseContext::kSlopBytes) { - parser_till_end = ::google::protobuf::internal::GreedyStringParserUTF8; - goto string_till_end; - } - GOOGLE_PROTOBUF_PARSER_ASSERT(::google::protobuf::internal::StringCheckUTF8(ptr, size, ctx)); - ::google::protobuf::internal::InlineGreedyStringParser(object, ptr, size, ctx); - ptr += size; + if (static_cast<::google::protobuf::uint8>(tag) == 18) { + ptr = ::google::protobuf::io::ReadSize(ptr, &size); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr); + parser_till_end = ::google::protobuf::internal::PackedFloatParser; + object = msg->mutable_actuator(); + if (size > end - ptr) goto len_delim_till_end; + auto newend = ptr + size; + if (size) ptr = parser_till_end(ptr, newend, object, ctx); + GOOGLE_PROTOBUF_PARSER_ASSERT(ptr == newend); + break; + } else if (static_cast<::google::protobuf::uint8>(tag) != 21) goto handle_unusual; + do { + msg->add_actuator(::google::protobuf::io::UnalignedLoad(ptr)); + ptr += sizeof(float); + if (ptr >= end) break; + } while ((::google::protobuf::io::UnalignedLoad<::google::protobuf::uint64>(ptr) & 255) == 21 && (ptr += 1)); break; } default: { @@ -11719,48 +14512,44 @@ const char* StatusText::_InternalParse(const char* begin, const char* end, void* } // switch } // while return ptr; -string_till_end: - static_cast<::std::string*>(object)->clear(); - static_cast<::std::string*>(object)->reserve(size); - goto len_delim_till_end; len_delim_till_end: return ctx->StoreAndTailCall(ptr, end, {_InternalParse, msg}, {parser_till_end, object}, size); } #else // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -bool StatusText::MergePartialFromCodedStream( +bool ActuatorOutputStatus::MergePartialFromCodedStream( ::google::protobuf::io::CodedInputStream* input) { #define DO_(EXPRESSION) if (!PROTOBUF_PREDICT_TRUE(EXPRESSION)) goto failure ::google::protobuf::uint32 tag; - // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.StatusText) + // @@protoc_insertion_point(parse_start:mavsdk.rpc.telemetry.ActuatorOutputStatus) for (;;) { ::std::pair<::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u); tag = p.first; if (!p.second) goto handle_unusual; switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // .mavsdk.rpc.telemetry.StatusText.StatusType type = 1; + // uint32 active = 1; case 1: { if (static_cast< ::google::protobuf::uint8>(tag) == (8 & 0xFF)) { - int value = 0; + DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( - input, &value))); - set_type(static_cast< ::mavsdk::rpc::telemetry::StatusText_StatusType >(value)); + ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( + input, &active_))); } else { goto handle_unusual; } break; } - // string text = 2; + // repeated float actuator = 2; case 2: { if (static_cast< ::google::protobuf::uint8>(tag) == (18 & 0xFF)) { - DO_(::google::protobuf::internal::WireFormatLite::ReadString( - input, this->mutable_text())); - DO_(::google::protobuf::internal::WireFormatLite::VerifyUtf8String( - this->text().data(), static_cast(this->text().length()), - ::google::protobuf::internal::WireFormatLite::PARSE, - "mavsdk.rpc.telemetry.StatusText.text")); + DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitive< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + input, this->mutable_actuator()))); + } else if (static_cast< ::google::protobuf::uint8>(tag) == (21 & 0xFF)) { + DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitiveNoInline< + float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( + 1, 18u, input, this->mutable_actuator()))); } else { goto handle_unusual; } @@ -11779,77 +14568,76 @@ bool StatusText::MergePartialFromCodedStream( } } success: - // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.StatusText) + // @@protoc_insertion_point(parse_success:mavsdk.rpc.telemetry.ActuatorOutputStatus) return true; failure: - // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.StatusText) + // @@protoc_insertion_point(parse_failure:mavsdk.rpc.telemetry.ActuatorOutputStatus) return false; #undef DO_ } #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER -void StatusText::SerializeWithCachedSizes( +void ActuatorOutputStatus::SerializeWithCachedSizes( ::google::protobuf::io::CodedOutputStream* output) const { - // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.StatusText) + // @@protoc_insertion_point(serialize_start:mavsdk.rpc.telemetry.ActuatorOutputStatus) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.StatusText.StatusType type = 1; - if (this->type() != 0) { - ::google::protobuf::internal::WireFormatLite::WriteEnum( - 1, this->type(), output); + // uint32 active = 1; + if (this->active() != 0) { + ::google::protobuf::internal::WireFormatLite::WriteUInt32(1, this->active(), output); } - // string text = 2; - if (this->text().size() > 0) { - ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( - this->text().data(), static_cast(this->text().length()), - ::google::protobuf::internal::WireFormatLite::SERIALIZE, - "mavsdk.rpc.telemetry.StatusText.text"); - ::google::protobuf::internal::WireFormatLite::WriteStringMaybeAliased( - 2, this->text(), output); + // repeated float actuator = 2; + if (this->actuator_size() > 0) { + ::google::protobuf::internal::WireFormatLite::WriteTag(2, ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, output); + output->WriteVarint32(_actuator_cached_byte_size_.load( + std::memory_order_relaxed)); + ::google::protobuf::internal::WireFormatLite::WriteFloatArray( + this->actuator().data(), this->actuator_size(), output); } if (_internal_metadata_.have_unknown_fields()) { ::google::protobuf::internal::WireFormat::SerializeUnknownFields( _internal_metadata_.unknown_fields(), output); } - // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.StatusText) + // @@protoc_insertion_point(serialize_end:mavsdk.rpc.telemetry.ActuatorOutputStatus) } -::google::protobuf::uint8* StatusText::InternalSerializeWithCachedSizesToArray( +::google::protobuf::uint8* ActuatorOutputStatus::InternalSerializeWithCachedSizesToArray( ::google::protobuf::uint8* target) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.StatusText) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.telemetry.ActuatorOutputStatus) ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - // .mavsdk.rpc.telemetry.StatusText.StatusType type = 1; - if (this->type() != 0) { - target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( - 1, this->type(), target); + // uint32 active = 1; + if (this->active() != 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(1, this->active(), target); } - // string text = 2; - if (this->text().size() > 0) { - ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( - this->text().data(), static_cast(this->text().length()), - ::google::protobuf::internal::WireFormatLite::SERIALIZE, - "mavsdk.rpc.telemetry.StatusText.text"); - target = - ::google::protobuf::internal::WireFormatLite::WriteStringToArray( - 2, this->text(), target); + // repeated float actuator = 2; + if (this->actuator_size() > 0) { + target = ::google::protobuf::internal::WireFormatLite::WriteTagToArray( + 2, + ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED, + target); + target = ::google::protobuf::io::CodedOutputStream::WriteVarint32ToArray( + _actuator_cached_byte_size_.load(std::memory_order_relaxed), + target); + target = ::google::protobuf::internal::WireFormatLite:: + WriteFloatNoTagToArray(this->actuator_, target); } if (_internal_metadata_.have_unknown_fields()) { target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields(), target); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.StatusText) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.telemetry.ActuatorOutputStatus) return target; } -size_t StatusText::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.StatusText) +size_t ActuatorOutputStatus::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.telemetry.ActuatorOutputStatus) size_t total_size = 0; if (_internal_metadata_.have_unknown_fields()) { @@ -11861,17 +14649,26 @@ size_t StatusText::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // string text = 2; - if (this->text().size() > 0) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::StringSize( - this->text()); + // repeated float actuator = 2; + { + unsigned int count = static_cast(this->actuator_size()); + size_t data_size = 4UL * count; + if (data_size > 0) { + total_size += 1 + + ::google::protobuf::internal::WireFormatLite::Int32Size( + static_cast<::google::protobuf::int32>(data_size)); + } + int cached_size = ::google::protobuf::internal::ToCachedSize(data_size); + _actuator_cached_byte_size_.store(cached_size, + std::memory_order_relaxed); + total_size += data_size; } - // .mavsdk.rpc.telemetry.StatusText.StatusType type = 1; - if (this->type() != 0) { + // uint32 active = 1; + if (this->active() != 0) { total_size += 1 + - ::google::protobuf::internal::WireFormatLite::EnumSize(this->type()); + ::google::protobuf::internal::WireFormatLite::UInt32Size( + this->active()); } int cached_size = ::google::protobuf::internal::ToCachedSize(total_size); @@ -11879,68 +14676,64 @@ size_t StatusText::ByteSizeLong() const { return total_size; } -void StatusText::MergeFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.StatusText) +void ActuatorOutputStatus::MergeFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_merge_from_start:mavsdk.rpc.telemetry.ActuatorOutputStatus) GOOGLE_DCHECK_NE(&from, this); - const StatusText* source = - ::google::protobuf::DynamicCastToGenerated( + const ActuatorOutputStatus* source = + ::google::protobuf::DynamicCastToGenerated( &from); if (source == nullptr) { - // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.StatusText) + // @@protoc_insertion_point(generalized_merge_from_cast_fail:mavsdk.rpc.telemetry.ActuatorOutputStatus) ::google::protobuf::internal::ReflectionOps::Merge(from, this); } else { - // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.StatusText) + // @@protoc_insertion_point(generalized_merge_from_cast_success:mavsdk.rpc.telemetry.ActuatorOutputStatus) MergeFrom(*source); } } -void StatusText::MergeFrom(const StatusText& from) { -// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.StatusText) +void ActuatorOutputStatus::MergeFrom(const ActuatorOutputStatus& from) { +// @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.telemetry.ActuatorOutputStatus) GOOGLE_DCHECK_NE(&from, this); _internal_metadata_.MergeFrom(from._internal_metadata_); ::google::protobuf::uint32 cached_has_bits = 0; (void) cached_has_bits; - if (from.text().size() > 0) { - - text_.AssignWithDefault(&::google::protobuf::internal::GetEmptyStringAlreadyInited(), from.text_); - } - if (from.type() != 0) { - set_type(from.type()); + actuator_.MergeFrom(from.actuator_); + if (from.active() != 0) { + set_active(from.active()); } } -void StatusText::CopyFrom(const ::google::protobuf::Message& from) { -// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.StatusText) +void ActuatorOutputStatus::CopyFrom(const ::google::protobuf::Message& from) { +// @@protoc_insertion_point(generalized_copy_from_start:mavsdk.rpc.telemetry.ActuatorOutputStatus) if (&from == this) return; Clear(); MergeFrom(from); } -void StatusText::CopyFrom(const StatusText& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.StatusText) +void ActuatorOutputStatus::CopyFrom(const ActuatorOutputStatus& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.telemetry.ActuatorOutputStatus) if (&from == this) return; Clear(); MergeFrom(from); } -bool StatusText::IsInitialized() const { +bool ActuatorOutputStatus::IsInitialized() const { return true; } -void StatusText::Swap(StatusText* other) { +void ActuatorOutputStatus::Swap(ActuatorOutputStatus* other) { if (other == this) return; InternalSwap(other); } -void StatusText::InternalSwap(StatusText* other) { +void ActuatorOutputStatus::InternalSwap(ActuatorOutputStatus* other) { using std::swap; _internal_metadata_.Swap(&other->_internal_metadata_); - text_.Swap(&other->text_, &::google::protobuf::internal::GetEmptyStringAlreadyInited(), - GetArenaNoVirtual()); - swap(type_, other->type_); + actuator_.InternalSwap(&other->actuator_); + swap(active_, other->active_); } -::google::protobuf::Metadata StatusText::GetMetadata() const { +::google::protobuf::Metadata ActuatorOutputStatus::GetMetadata() const { ::google::protobuf::internal::AssignDescriptors(&::assign_descriptors_table_telemetry_2ftelemetry_2eproto); return ::file_level_metadata_telemetry_2ftelemetry_2eproto[kIndexInFileMessages]; } @@ -11988,6 +14781,12 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerReq template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::AttitudeEulerResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::AttitudeEulerResponse >(Arena* arena) { return Arena::CreateInternal< ::mavsdk::rpc::telemetry::AttitudeEulerResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest >(Arena* arena) { + return Arena::CreateInternal< ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse >(Arena* arena) { + return Arena::CreateInternal< ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest >(Arena* arena) { return Arena::CreateInternal< ::mavsdk::rpc::telemetry::SubscribeCameraAttitudeQuaternionRequest >(arena); } @@ -12042,6 +14841,18 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::SubscribeStatusTextReques template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::StatusTextResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::StatusTextResponse >(Arena* arena) { return Arena::CreateInternal< ::mavsdk::rpc::telemetry::StatusTextResponse >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest >(Arena* arena) { + return Arena::CreateInternal< ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse >(Arena* arena) { + return Arena::CreateInternal< ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest >(Arena* arena) { + return Arena::CreateInternal< ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse >(Arena* arena) { + return Arena::CreateInternal< ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::Position* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::Position >(Arena* arena) { return Arena::CreateInternal< ::mavsdk::rpc::telemetry::Position >(arena); } @@ -12051,6 +14862,9 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::Quaternion* Arena::Create template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::EulerAngle* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::EulerAngle >(Arena* arena) { return Arena::CreateInternal< ::mavsdk::rpc::telemetry::EulerAngle >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::AngularVelocityBody* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::AngularVelocityBody >(Arena* arena) { + return Arena::CreateInternal< ::mavsdk::rpc::telemetry::AngularVelocityBody >(arena); +} template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::SpeedNed* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::SpeedNed >(Arena* arena) { return Arena::CreateInternal< ::mavsdk::rpc::telemetry::SpeedNed >(arena); } @@ -12069,6 +14883,12 @@ template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::RcStatus* Arena::CreateMa template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::StatusText* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::StatusText >(Arena* arena) { return Arena::CreateInternal< ::mavsdk::rpc::telemetry::StatusText >(arena); } +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::ActuatorControlTarget* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::ActuatorControlTarget >(Arena* arena) { + return Arena::CreateInternal< ::mavsdk::rpc::telemetry::ActuatorControlTarget >(arena); +} +template<> PROTOBUF_NOINLINE ::mavsdk::rpc::telemetry::ActuatorOutputStatus* Arena::CreateMaybeMessage< ::mavsdk::rpc::telemetry::ActuatorOutputStatus >(Arena* arena) { + return Arena::CreateInternal< ::mavsdk::rpc::telemetry::ActuatorOutputStatus >(arena); +} } // namespace protobuf } // namespace google diff --git a/src/backend/src/generated/telemetry/telemetry.pb.h b/src/backend/src/generated/telemetry/telemetry.pb.h index 1e20ce08a1..e77434079c 100644 --- a/src/backend/src/generated/telemetry/telemetry.pb.h +++ b/src/backend/src/generated/telemetry/telemetry.pb.h @@ -42,7 +42,7 @@ struct TableStruct_telemetry_2ftelemetry_2eproto { PROTOBUF_SECTION_VARIABLE(protodesc_cold); static const ::google::protobuf::internal::AuxillaryParseTableField aux[] PROTOBUF_SECTION_VARIABLE(protodesc_cold); - static const ::google::protobuf::internal::ParseTable schema[39] + static const ::google::protobuf::internal::ParseTable schema[48] PROTOBUF_SECTION_VARIABLE(protodesc_cold); static const ::google::protobuf::internal::FieldMetadata field_metadata[]; static const ::google::protobuf::internal::SerializationTable serialization_table[]; @@ -52,9 +52,27 @@ void AddDescriptors_telemetry_2ftelemetry_2eproto(); namespace mavsdk { namespace rpc { namespace telemetry { +class ActuatorControlTarget; +class ActuatorControlTargetDefaultTypeInternal; +extern ActuatorControlTargetDefaultTypeInternal _ActuatorControlTarget_default_instance_; +class ActuatorControlTargetResponse; +class ActuatorControlTargetResponseDefaultTypeInternal; +extern ActuatorControlTargetResponseDefaultTypeInternal _ActuatorControlTargetResponse_default_instance_; +class ActuatorOutputStatus; +class ActuatorOutputStatusDefaultTypeInternal; +extern ActuatorOutputStatusDefaultTypeInternal _ActuatorOutputStatus_default_instance_; +class ActuatorOutputStatusResponse; +class ActuatorOutputStatusResponseDefaultTypeInternal; +extern ActuatorOutputStatusResponseDefaultTypeInternal _ActuatorOutputStatusResponse_default_instance_; +class AngularVelocityBody; +class AngularVelocityBodyDefaultTypeInternal; +extern AngularVelocityBodyDefaultTypeInternal _AngularVelocityBody_default_instance_; class ArmedResponse; class ArmedResponseDefaultTypeInternal; extern ArmedResponseDefaultTypeInternal _ArmedResponse_default_instance_; +class AttitudeAngularVelocityBodyResponse; +class AttitudeAngularVelocityBodyResponseDefaultTypeInternal; +extern AttitudeAngularVelocityBodyResponseDefaultTypeInternal _AttitudeAngularVelocityBodyResponse_default_instance_; class AttitudeEulerResponse; class AttitudeEulerResponseDefaultTypeInternal; extern AttitudeEulerResponseDefaultTypeInternal _AttitudeEulerResponse_default_instance_; @@ -124,9 +142,18 @@ extern StatusTextDefaultTypeInternal _StatusText_default_instance_; class StatusTextResponse; class StatusTextResponseDefaultTypeInternal; extern StatusTextResponseDefaultTypeInternal _StatusTextResponse_default_instance_; +class SubscribeActuatorControlTargetRequest; +class SubscribeActuatorControlTargetRequestDefaultTypeInternal; +extern SubscribeActuatorControlTargetRequestDefaultTypeInternal _SubscribeActuatorControlTargetRequest_default_instance_; +class SubscribeActuatorOutputStatusRequest; +class SubscribeActuatorOutputStatusRequestDefaultTypeInternal; +extern SubscribeActuatorOutputStatusRequestDefaultTypeInternal _SubscribeActuatorOutputStatusRequest_default_instance_; class SubscribeArmedRequest; class SubscribeArmedRequestDefaultTypeInternal; extern SubscribeArmedRequestDefaultTypeInternal _SubscribeArmedRequest_default_instance_; +class SubscribeAttitudeAngularVelocityBodyRequest; +class SubscribeAttitudeAngularVelocityBodyRequestDefaultTypeInternal; +extern SubscribeAttitudeAngularVelocityBodyRequestDefaultTypeInternal _SubscribeAttitudeAngularVelocityBodyRequest_default_instance_; class SubscribeAttitudeEulerRequest; class SubscribeAttitudeEulerRequestDefaultTypeInternal; extern SubscribeAttitudeEulerRequestDefaultTypeInternal _SubscribeAttitudeEulerRequest_default_instance_; @@ -174,7 +201,13 @@ extern SubscribeStatusTextRequestDefaultTypeInternal _SubscribeStatusTextRequest } // namespace mavsdk namespace google { namespace protobuf { +template<> ::mavsdk::rpc::telemetry::ActuatorControlTarget* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::ActuatorControlTarget>(Arena*); +template<> ::mavsdk::rpc::telemetry::ActuatorControlTargetResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::ActuatorControlTargetResponse>(Arena*); +template<> ::mavsdk::rpc::telemetry::ActuatorOutputStatus* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::ActuatorOutputStatus>(Arena*); +template<> ::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::ActuatorOutputStatusResponse>(Arena*); +template<> ::mavsdk::rpc::telemetry::AngularVelocityBody* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::AngularVelocityBody>(Arena*); template<> ::mavsdk::rpc::telemetry::ArmedResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::ArmedResponse>(Arena*); +template<> ::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::AttitudeAngularVelocityBodyResponse>(Arena*); template<> ::mavsdk::rpc::telemetry::AttitudeEulerResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::AttitudeEulerResponse>(Arena*); template<> ::mavsdk::rpc::telemetry::AttitudeQuaternionResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::AttitudeQuaternionResponse>(Arena*); template<> ::mavsdk::rpc::telemetry::Battery* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::Battery>(Arena*); @@ -198,7 +231,10 @@ template<> ::mavsdk::rpc::telemetry::RcStatusResponse* Arena::CreateMaybeMessage template<> ::mavsdk::rpc::telemetry::SpeedNed* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SpeedNed>(Arena*); template<> ::mavsdk::rpc::telemetry::StatusText* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::StatusText>(Arena*); template<> ::mavsdk::rpc::telemetry::StatusTextResponse* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::StatusTextResponse>(Arena*); +template<> ::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SubscribeActuatorControlTargetRequest>(Arena*); +template<> ::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SubscribeActuatorOutputStatusRequest>(Arena*); template<> ::mavsdk::rpc::telemetry::SubscribeArmedRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SubscribeArmedRequest>(Arena*); +template<> ::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SubscribeAttitudeAngularVelocityBodyRequest>(Arena*); template<> ::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SubscribeAttitudeEulerRequest>(Arena*); template<> ::mavsdk::rpc::telemetry::SubscribeAttitudeQuaternionRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SubscribeAttitudeQuaternionRequest>(Arena*); template<> ::mavsdk::rpc::telemetry::SubscribeBatteryRequest* Arena::CreateMaybeMessage<::mavsdk::rpc::telemetry::SubscribeBatteryRequest>(Arena*); @@ -1611,6 +1647,226 @@ class AttitudeEulerResponse : }; // ------------------------------------------------------------------- +class SubscribeAttitudeAngularVelocityBodyRequest : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) */ { + public: + SubscribeAttitudeAngularVelocityBodyRequest(); + virtual ~SubscribeAttitudeAngularVelocityBodyRequest(); + + SubscribeAttitudeAngularVelocityBodyRequest(const SubscribeAttitudeAngularVelocityBodyRequest& from); + + inline SubscribeAttitudeAngularVelocityBodyRequest& operator=(const SubscribeAttitudeAngularVelocityBodyRequest& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + SubscribeAttitudeAngularVelocityBodyRequest(SubscribeAttitudeAngularVelocityBodyRequest&& from) noexcept + : SubscribeAttitudeAngularVelocityBodyRequest() { + *this = ::std::move(from); + } + + inline SubscribeAttitudeAngularVelocityBodyRequest& operator=(SubscribeAttitudeAngularVelocityBodyRequest&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor() { + return default_instance().GetDescriptor(); + } + static const SubscribeAttitudeAngularVelocityBodyRequest& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const SubscribeAttitudeAngularVelocityBodyRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeAttitudeAngularVelocityBodyRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 12; + + void Swap(SubscribeAttitudeAngularVelocityBodyRequest* other); + friend void swap(SubscribeAttitudeAngularVelocityBodyRequest& a, SubscribeAttitudeAngularVelocityBodyRequest& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline SubscribeAttitudeAngularVelocityBodyRequest* New() const final { + return CreateMaybeMessage(nullptr); + } + + SubscribeAttitudeAngularVelocityBodyRequest* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const SubscribeAttitudeAngularVelocityBodyRequest& from); + void MergeFrom(const SubscribeAttitudeAngularVelocityBodyRequest& from); + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + static const char* _InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx); + ::google::protobuf::internal::ParseFunc _ParseFunc() const final { return _InternalParse; } + #else + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SubscribeAttitudeAngularVelocityBodyRequest* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return nullptr; + } + inline void* MaybeArenaPtr() const { + return nullptr; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeAttitudeAngularVelocityBodyRequest) + private: + class HasBitSetters; + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; +}; +// ------------------------------------------------------------------- + +class AttitudeAngularVelocityBodyResponse : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) */ { + public: + AttitudeAngularVelocityBodyResponse(); + virtual ~AttitudeAngularVelocityBodyResponse(); + + AttitudeAngularVelocityBodyResponse(const AttitudeAngularVelocityBodyResponse& from); + + inline AttitudeAngularVelocityBodyResponse& operator=(const AttitudeAngularVelocityBodyResponse& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + AttitudeAngularVelocityBodyResponse(AttitudeAngularVelocityBodyResponse&& from) noexcept + : AttitudeAngularVelocityBodyResponse() { + *this = ::std::move(from); + } + + inline AttitudeAngularVelocityBodyResponse& operator=(AttitudeAngularVelocityBodyResponse&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor() { + return default_instance().GetDescriptor(); + } + static const AttitudeAngularVelocityBodyResponse& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const AttitudeAngularVelocityBodyResponse* internal_default_instance() { + return reinterpret_cast( + &_AttitudeAngularVelocityBodyResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 13; + + void Swap(AttitudeAngularVelocityBodyResponse* other); + friend void swap(AttitudeAngularVelocityBodyResponse& a, AttitudeAngularVelocityBodyResponse& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline AttitudeAngularVelocityBodyResponse* New() const final { + return CreateMaybeMessage(nullptr); + } + + AttitudeAngularVelocityBodyResponse* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const AttitudeAngularVelocityBodyResponse& from); + void MergeFrom(const AttitudeAngularVelocityBodyResponse& from); + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + static const char* _InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx); + ::google::protobuf::internal::ParseFunc _ParseFunc() const final { return _InternalParse; } + #else + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(AttitudeAngularVelocityBodyResponse* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return nullptr; + } + inline void* MaybeArenaPtr() const { + return nullptr; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // .mavsdk.rpc.telemetry.AngularVelocityBody attitude_angular_velocity_body = 1; + bool has_attitude_angular_velocity_body() const; + void clear_attitude_angular_velocity_body(); + static const int kAttitudeAngularVelocityBodyFieldNumber = 1; + const ::mavsdk::rpc::telemetry::AngularVelocityBody& attitude_angular_velocity_body() const; + ::mavsdk::rpc::telemetry::AngularVelocityBody* release_attitude_angular_velocity_body(); + ::mavsdk::rpc::telemetry::AngularVelocityBody* mutable_attitude_angular_velocity_body(); + void set_allocated_attitude_angular_velocity_body(::mavsdk::rpc::telemetry::AngularVelocityBody* attitude_angular_velocity_body); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse) + private: + class HasBitSetters; + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::mavsdk::rpc::telemetry::AngularVelocityBody* attitude_angular_velocity_body_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; +}; +// ------------------------------------------------------------------- + class SubscribeCameraAttitudeQuaternionRequest : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeCameraAttitudeQuaternionRequest) */ { public: @@ -1649,7 +1905,7 @@ class SubscribeCameraAttitudeQuaternionRequest : &_SubscribeCameraAttitudeQuaternionRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 12; + 14; void Swap(SubscribeCameraAttitudeQuaternionRequest* other); friend void swap(SubscribeCameraAttitudeQuaternionRequest& a, SubscribeCameraAttitudeQuaternionRequest& b) { @@ -1754,7 +2010,7 @@ class CameraAttitudeQuaternionResponse : &_CameraAttitudeQuaternionResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 13; + 15; void Swap(CameraAttitudeQuaternionResponse* other); friend void swap(CameraAttitudeQuaternionResponse& a, CameraAttitudeQuaternionResponse& b) { @@ -1869,7 +2125,7 @@ class SubscribeCameraAttitudeEulerRequest : &_SubscribeCameraAttitudeEulerRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 14; + 16; void Swap(SubscribeCameraAttitudeEulerRequest* other); friend void swap(SubscribeCameraAttitudeEulerRequest& a, SubscribeCameraAttitudeEulerRequest& b) { @@ -1974,7 +2230,7 @@ class CameraAttitudeEulerResponse : &_CameraAttitudeEulerResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 15; + 17; void Swap(CameraAttitudeEulerResponse* other); friend void swap(CameraAttitudeEulerResponse& a, CameraAttitudeEulerResponse& b) { @@ -2089,7 +2345,7 @@ class SubscribeGroundSpeedNedRequest : &_SubscribeGroundSpeedNedRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 16; + 18; void Swap(SubscribeGroundSpeedNedRequest* other); friend void swap(SubscribeGroundSpeedNedRequest& a, SubscribeGroundSpeedNedRequest& b) { @@ -2194,7 +2450,7 @@ class GroundSpeedNedResponse : &_GroundSpeedNedResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 17; + 19; void Swap(GroundSpeedNedResponse* other); friend void swap(GroundSpeedNedResponse& a, GroundSpeedNedResponse& b) { @@ -2309,7 +2565,7 @@ class SubscribeGpsInfoRequest : &_SubscribeGpsInfoRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 18; + 20; void Swap(SubscribeGpsInfoRequest* other); friend void swap(SubscribeGpsInfoRequest& a, SubscribeGpsInfoRequest& b) { @@ -2414,7 +2670,7 @@ class GpsInfoResponse : &_GpsInfoResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 19; + 21; void Swap(GpsInfoResponse* other); friend void swap(GpsInfoResponse& a, GpsInfoResponse& b) { @@ -2529,7 +2785,7 @@ class SubscribeBatteryRequest : &_SubscribeBatteryRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 20; + 22; void Swap(SubscribeBatteryRequest* other); friend void swap(SubscribeBatteryRequest& a, SubscribeBatteryRequest& b) { @@ -2634,7 +2890,7 @@ class BatteryResponse : &_BatteryResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 21; + 23; void Swap(BatteryResponse* other); friend void swap(BatteryResponse& a, BatteryResponse& b) { @@ -2749,7 +3005,7 @@ class SubscribeFlightModeRequest : &_SubscribeFlightModeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 22; + 24; void Swap(SubscribeFlightModeRequest* other); friend void swap(SubscribeFlightModeRequest& a, SubscribeFlightModeRequest& b) { @@ -2854,7 +3110,7 @@ class FlightModeResponse : &_FlightModeResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 23; + 25; void Swap(FlightModeResponse* other); friend void swap(FlightModeResponse& a, FlightModeResponse& b) { @@ -2966,7 +3222,7 @@ class SubscribeHealthRequest : &_SubscribeHealthRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 24; + 26; void Swap(SubscribeHealthRequest* other); friend void swap(SubscribeHealthRequest& a, SubscribeHealthRequest& b) { @@ -3071,7 +3327,7 @@ class HealthResponse : &_HealthResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 25; + 27; void Swap(HealthResponse* other); friend void swap(HealthResponse& a, HealthResponse& b) { @@ -3186,7 +3442,7 @@ class SubscribeRcStatusRequest : &_SubscribeRcStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 26; + 28; void Swap(SubscribeRcStatusRequest* other); friend void swap(SubscribeRcStatusRequest& a, SubscribeRcStatusRequest& b) { @@ -3291,7 +3547,7 @@ class RcStatusResponse : &_RcStatusResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 27; + 29; void Swap(RcStatusResponse* other); friend void swap(RcStatusResponse& a, RcStatusResponse& b) { @@ -3406,7 +3662,7 @@ class SubscribeStatusTextRequest : &_SubscribeStatusTextRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 28; + 30; void Swap(SubscribeStatusTextRequest* other); friend void swap(SubscribeStatusTextRequest& a, SubscribeStatusTextRequest& b) { @@ -3511,7 +3767,7 @@ class StatusTextResponse : &_StatusTextResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 29; + 31; void Swap(StatusTextResponse* other); friend void swap(StatusTextResponse& a, StatusTextResponse& b) { @@ -3588,25 +3844,25 @@ class StatusTextResponse : }; // ------------------------------------------------------------------- -class Position : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Position) */ { +class SubscribeActuatorControlTargetRequest : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) */ { public: - Position(); - virtual ~Position(); + SubscribeActuatorControlTargetRequest(); + virtual ~SubscribeActuatorControlTargetRequest(); - Position(const Position& from); + SubscribeActuatorControlTargetRequest(const SubscribeActuatorControlTargetRequest& from); - inline Position& operator=(const Position& from) { + inline SubscribeActuatorControlTargetRequest& operator=(const SubscribeActuatorControlTargetRequest& from) { CopyFrom(from); return *this; } #if LANG_CXX11 - Position(Position&& from) noexcept - : Position() { + SubscribeActuatorControlTargetRequest(SubscribeActuatorControlTargetRequest&& from) noexcept + : SubscribeActuatorControlTargetRequest() { *this = ::std::move(from); } - inline Position& operator=(Position&& from) noexcept { + inline SubscribeActuatorControlTargetRequest& operator=(SubscribeActuatorControlTargetRequest&& from) noexcept { if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { if (this != &from) InternalSwap(&from); } else { @@ -3618,34 +3874,34 @@ class Position : static const ::google::protobuf::Descriptor* descriptor() { return default_instance().GetDescriptor(); } - static const Position& default_instance(); + static const SubscribeActuatorControlTargetRequest& default_instance(); static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY - static inline const Position* internal_default_instance() { - return reinterpret_cast( - &_Position_default_instance_); + static inline const SubscribeActuatorControlTargetRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeActuatorControlTargetRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 30; + 32; - void Swap(Position* other); - friend void swap(Position& a, Position& b) { + void Swap(SubscribeActuatorControlTargetRequest* other); + friend void swap(SubscribeActuatorControlTargetRequest& a, SubscribeActuatorControlTargetRequest& b) { a.Swap(&b); } // implements Message ---------------------------------------------- - inline Position* New() const final { - return CreateMaybeMessage(nullptr); + inline SubscribeActuatorControlTargetRequest* New() const final { + return CreateMaybeMessage(nullptr); } - Position* New(::google::protobuf::Arena* arena) const final { - return CreateMaybeMessage(arena); + SubscribeActuatorControlTargetRequest* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); } void CopyFrom(const ::google::protobuf::Message& from) final; void MergeFrom(const ::google::protobuf::Message& from) final; - void CopyFrom(const Position& from); - void MergeFrom(const Position& from); + void CopyFrom(const SubscribeActuatorControlTargetRequest& from); + void MergeFrom(const SubscribeActuatorControlTargetRequest& from); PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; bool IsInitialized() const final; @@ -3667,7 +3923,7 @@ class Position : void SharedCtor(); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(Position* other); + void InternalSwap(SubscribeActuatorControlTargetRequest* other); private: inline ::google::protobuf::Arena* GetArenaNoVirtual() const { return nullptr; @@ -3683,63 +3939,35 @@ class Position : // accessors ------------------------------------------------------- - // double latitude_deg = 1; - void clear_latitude_deg(); - static const int kLatitudeDegFieldNumber = 1; - double latitude_deg() const; - void set_latitude_deg(double value); - - // double longitude_deg = 2; - void clear_longitude_deg(); - static const int kLongitudeDegFieldNumber = 2; - double longitude_deg() const; - void set_longitude_deg(double value); - - // float absolute_altitude_m = 3; - void clear_absolute_altitude_m(); - static const int kAbsoluteAltitudeMFieldNumber = 3; - float absolute_altitude_m() const; - void set_absolute_altitude_m(float value); - - // float relative_altitude_m = 4; - void clear_relative_altitude_m(); - static const int kRelativeAltitudeMFieldNumber = 4; - float relative_altitude_m() const; - void set_relative_altitude_m(float value); - - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Position) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeActuatorControlTargetRequest) private: class HasBitSetters; ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; - double latitude_deg_; - double longitude_deg_; - float absolute_altitude_m_; - float relative_altitude_m_; mutable ::google::protobuf::internal::CachedSize _cached_size_; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; }; // ------------------------------------------------------------------- -class Quaternion : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Quaternion) */ { +class ActuatorControlTargetResponse : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) */ { public: - Quaternion(); - virtual ~Quaternion(); + ActuatorControlTargetResponse(); + virtual ~ActuatorControlTargetResponse(); - Quaternion(const Quaternion& from); + ActuatorControlTargetResponse(const ActuatorControlTargetResponse& from); - inline Quaternion& operator=(const Quaternion& from) { + inline ActuatorControlTargetResponse& operator=(const ActuatorControlTargetResponse& from) { CopyFrom(from); return *this; } #if LANG_CXX11 - Quaternion(Quaternion&& from) noexcept - : Quaternion() { + ActuatorControlTargetResponse(ActuatorControlTargetResponse&& from) noexcept + : ActuatorControlTargetResponse() { *this = ::std::move(from); } - inline Quaternion& operator=(Quaternion&& from) noexcept { + inline ActuatorControlTargetResponse& operator=(ActuatorControlTargetResponse&& from) noexcept { if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { if (this != &from) InternalSwap(&from); } else { @@ -3751,34 +3979,34 @@ class Quaternion : static const ::google::protobuf::Descriptor* descriptor() { return default_instance().GetDescriptor(); } - static const Quaternion& default_instance(); + static const ActuatorControlTargetResponse& default_instance(); static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY - static inline const Quaternion* internal_default_instance() { - return reinterpret_cast( - &_Quaternion_default_instance_); + static inline const ActuatorControlTargetResponse* internal_default_instance() { + return reinterpret_cast( + &_ActuatorControlTargetResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 31; + 33; - void Swap(Quaternion* other); - friend void swap(Quaternion& a, Quaternion& b) { + void Swap(ActuatorControlTargetResponse* other); + friend void swap(ActuatorControlTargetResponse& a, ActuatorControlTargetResponse& b) { a.Swap(&b); } // implements Message ---------------------------------------------- - inline Quaternion* New() const final { - return CreateMaybeMessage(nullptr); + inline ActuatorControlTargetResponse* New() const final { + return CreateMaybeMessage(nullptr); } - Quaternion* New(::google::protobuf::Arena* arena) const final { - return CreateMaybeMessage(arena); + ActuatorControlTargetResponse* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); } void CopyFrom(const ::google::protobuf::Message& from) final; void MergeFrom(const ::google::protobuf::Message& from) final; - void CopyFrom(const Quaternion& from); - void MergeFrom(const Quaternion& from); + void CopyFrom(const ActuatorControlTargetResponse& from); + void MergeFrom(const ActuatorControlTargetResponse& from); PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; bool IsInitialized() const final; @@ -3800,7 +4028,7 @@ class Quaternion : void SharedCtor(); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(Quaternion* other); + void InternalSwap(ActuatorControlTargetResponse* other); private: inline ::google::protobuf::Arena* GetArenaNoVirtual() const { return nullptr; @@ -3816,63 +4044,45 @@ class Quaternion : // accessors ------------------------------------------------------- - // float w = 1; - void clear_w(); - static const int kWFieldNumber = 1; - float w() const; - void set_w(float value); - - // float x = 2; - void clear_x(); - static const int kXFieldNumber = 2; - float x() const; - void set_x(float value); - - // float y = 3; - void clear_y(); - static const int kYFieldNumber = 3; - float y() const; - void set_y(float value); - - // float z = 4; - void clear_z(); - static const int kZFieldNumber = 4; - float z() const; - void set_z(float value); + // .mavsdk.rpc.telemetry.ActuatorControlTarget actuator_control_target = 1; + bool has_actuator_control_target() const; + void clear_actuator_control_target(); + static const int kActuatorControlTargetFieldNumber = 1; + const ::mavsdk::rpc::telemetry::ActuatorControlTarget& actuator_control_target() const; + ::mavsdk::rpc::telemetry::ActuatorControlTarget* release_actuator_control_target(); + ::mavsdk::rpc::telemetry::ActuatorControlTarget* mutable_actuator_control_target(); + void set_allocated_actuator_control_target(::mavsdk::rpc::telemetry::ActuatorControlTarget* actuator_control_target); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Quaternion) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.ActuatorControlTargetResponse) private: class HasBitSetters; ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; - float w_; - float x_; - float y_; - float z_; + ::mavsdk::rpc::telemetry::ActuatorControlTarget* actuator_control_target_; mutable ::google::protobuf::internal::CachedSize _cached_size_; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; }; // ------------------------------------------------------------------- -class EulerAngle : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.EulerAngle) */ { +class SubscribeActuatorOutputStatusRequest : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) */ { public: - EulerAngle(); - virtual ~EulerAngle(); + SubscribeActuatorOutputStatusRequest(); + virtual ~SubscribeActuatorOutputStatusRequest(); - EulerAngle(const EulerAngle& from); + SubscribeActuatorOutputStatusRequest(const SubscribeActuatorOutputStatusRequest& from); - inline EulerAngle& operator=(const EulerAngle& from) { + inline SubscribeActuatorOutputStatusRequest& operator=(const SubscribeActuatorOutputStatusRequest& from) { CopyFrom(from); return *this; } #if LANG_CXX11 - EulerAngle(EulerAngle&& from) noexcept - : EulerAngle() { + SubscribeActuatorOutputStatusRequest(SubscribeActuatorOutputStatusRequest&& from) noexcept + : SubscribeActuatorOutputStatusRequest() { *this = ::std::move(from); } - inline EulerAngle& operator=(EulerAngle&& from) noexcept { + inline SubscribeActuatorOutputStatusRequest& operator=(SubscribeActuatorOutputStatusRequest&& from) noexcept { if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { if (this != &from) InternalSwap(&from); } else { @@ -3884,34 +4094,34 @@ class EulerAngle : static const ::google::protobuf::Descriptor* descriptor() { return default_instance().GetDescriptor(); } - static const EulerAngle& default_instance(); + static const SubscribeActuatorOutputStatusRequest& default_instance(); static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY - static inline const EulerAngle* internal_default_instance() { - return reinterpret_cast( - &_EulerAngle_default_instance_); + static inline const SubscribeActuatorOutputStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeActuatorOutputStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 32; + 34; - void Swap(EulerAngle* other); - friend void swap(EulerAngle& a, EulerAngle& b) { + void Swap(SubscribeActuatorOutputStatusRequest* other); + friend void swap(SubscribeActuatorOutputStatusRequest& a, SubscribeActuatorOutputStatusRequest& b) { a.Swap(&b); } // implements Message ---------------------------------------------- - inline EulerAngle* New() const final { - return CreateMaybeMessage(nullptr); + inline SubscribeActuatorOutputStatusRequest* New() const final { + return CreateMaybeMessage(nullptr); } - EulerAngle* New(::google::protobuf::Arena* arena) const final { - return CreateMaybeMessage(arena); + SubscribeActuatorOutputStatusRequest* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); } void CopyFrom(const ::google::protobuf::Message& from) final; void MergeFrom(const ::google::protobuf::Message& from) final; - void CopyFrom(const EulerAngle& from); - void MergeFrom(const EulerAngle& from); + void CopyFrom(const SubscribeActuatorOutputStatusRequest& from); + void MergeFrom(const SubscribeActuatorOutputStatusRequest& from); PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; bool IsInitialized() const final; @@ -3933,7 +4143,7 @@ class EulerAngle : void SharedCtor(); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(EulerAngle* other); + void InternalSwap(SubscribeActuatorOutputStatusRequest* other); private: inline ::google::protobuf::Arena* GetArenaNoVirtual() const { return nullptr; @@ -3949,56 +4159,35 @@ class EulerAngle : // accessors ------------------------------------------------------- - // float roll_deg = 1; - void clear_roll_deg(); - static const int kRollDegFieldNumber = 1; - float roll_deg() const; - void set_roll_deg(float value); - - // float pitch_deg = 2; - void clear_pitch_deg(); - static const int kPitchDegFieldNumber = 2; - float pitch_deg() const; - void set_pitch_deg(float value); - - // float yaw_deg = 3; - void clear_yaw_deg(); - static const int kYawDegFieldNumber = 3; - float yaw_deg() const; - void set_yaw_deg(float value); - - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.EulerAngle) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SubscribeActuatorOutputStatusRequest) private: class HasBitSetters; ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; - float roll_deg_; - float pitch_deg_; - float yaw_deg_; mutable ::google::protobuf::internal::CachedSize _cached_size_; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; }; // ------------------------------------------------------------------- -class SpeedNed : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SpeedNed) */ { +class ActuatorOutputStatusResponse : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) */ { public: - SpeedNed(); - virtual ~SpeedNed(); + ActuatorOutputStatusResponse(); + virtual ~ActuatorOutputStatusResponse(); - SpeedNed(const SpeedNed& from); + ActuatorOutputStatusResponse(const ActuatorOutputStatusResponse& from); - inline SpeedNed& operator=(const SpeedNed& from) { + inline ActuatorOutputStatusResponse& operator=(const ActuatorOutputStatusResponse& from) { CopyFrom(from); return *this; } #if LANG_CXX11 - SpeedNed(SpeedNed&& from) noexcept - : SpeedNed() { + ActuatorOutputStatusResponse(ActuatorOutputStatusResponse&& from) noexcept + : ActuatorOutputStatusResponse() { *this = ::std::move(from); } - inline SpeedNed& operator=(SpeedNed&& from) noexcept { + inline ActuatorOutputStatusResponse& operator=(ActuatorOutputStatusResponse&& from) noexcept { if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { if (this != &from) InternalSwap(&from); } else { @@ -4010,34 +4199,34 @@ class SpeedNed : static const ::google::protobuf::Descriptor* descriptor() { return default_instance().GetDescriptor(); } - static const SpeedNed& default_instance(); + static const ActuatorOutputStatusResponse& default_instance(); static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY - static inline const SpeedNed* internal_default_instance() { - return reinterpret_cast( - &_SpeedNed_default_instance_); + static inline const ActuatorOutputStatusResponse* internal_default_instance() { + return reinterpret_cast( + &_ActuatorOutputStatusResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 33; + 35; - void Swap(SpeedNed* other); - friend void swap(SpeedNed& a, SpeedNed& b) { + void Swap(ActuatorOutputStatusResponse* other); + friend void swap(ActuatorOutputStatusResponse& a, ActuatorOutputStatusResponse& b) { a.Swap(&b); } // implements Message ---------------------------------------------- - inline SpeedNed* New() const final { - return CreateMaybeMessage(nullptr); + inline ActuatorOutputStatusResponse* New() const final { + return CreateMaybeMessage(nullptr); } - SpeedNed* New(::google::protobuf::Arena* arena) const final { - return CreateMaybeMessage(arena); + ActuatorOutputStatusResponse* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); } void CopyFrom(const ::google::protobuf::Message& from) final; void MergeFrom(const ::google::protobuf::Message& from) final; - void CopyFrom(const SpeedNed& from); - void MergeFrom(const SpeedNed& from); + void CopyFrom(const ActuatorOutputStatusResponse& from); + void MergeFrom(const ActuatorOutputStatusResponse& from); PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; bool IsInitialized() const final; @@ -4059,7 +4248,7 @@ class SpeedNed : void SharedCtor(); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(SpeedNed* other); + void InternalSwap(ActuatorOutputStatusResponse* other); private: inline ::google::protobuf::Arena* GetArenaNoVirtual() const { return nullptr; @@ -4075,56 +4264,45 @@ class SpeedNed : // accessors ------------------------------------------------------- - // float velocity_north_m_s = 1; - void clear_velocity_north_m_s(); - static const int kVelocityNorthMSFieldNumber = 1; - float velocity_north_m_s() const; - void set_velocity_north_m_s(float value); - - // float velocity_east_m_s = 2; - void clear_velocity_east_m_s(); - static const int kVelocityEastMSFieldNumber = 2; - float velocity_east_m_s() const; - void set_velocity_east_m_s(float value); - - // float velocity_down_m_s = 3; - void clear_velocity_down_m_s(); - static const int kVelocityDownMSFieldNumber = 3; - float velocity_down_m_s() const; - void set_velocity_down_m_s(float value); + // .mavsdk.rpc.telemetry.ActuatorOutputStatus actuator_output_status = 1; + bool has_actuator_output_status() const; + void clear_actuator_output_status(); + static const int kActuatorOutputStatusFieldNumber = 1; + const ::mavsdk::rpc::telemetry::ActuatorOutputStatus& actuator_output_status() const; + ::mavsdk::rpc::telemetry::ActuatorOutputStatus* release_actuator_output_status(); + ::mavsdk::rpc::telemetry::ActuatorOutputStatus* mutable_actuator_output_status(); + void set_allocated_actuator_output_status(::mavsdk::rpc::telemetry::ActuatorOutputStatus* actuator_output_status); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SpeedNed) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse) private: class HasBitSetters; ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; - float velocity_north_m_s_; - float velocity_east_m_s_; - float velocity_down_m_s_; + ::mavsdk::rpc::telemetry::ActuatorOutputStatus* actuator_output_status_; mutable ::google::protobuf::internal::CachedSize _cached_size_; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; }; // ------------------------------------------------------------------- -class GpsInfo : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GpsInfo) */ { +class Position : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Position) */ { public: - GpsInfo(); - virtual ~GpsInfo(); + Position(); + virtual ~Position(); - GpsInfo(const GpsInfo& from); + Position(const Position& from); - inline GpsInfo& operator=(const GpsInfo& from) { + inline Position& operator=(const Position& from) { CopyFrom(from); return *this; } #if LANG_CXX11 - GpsInfo(GpsInfo&& from) noexcept - : GpsInfo() { + Position(Position&& from) noexcept + : Position() { *this = ::std::move(from); } - inline GpsInfo& operator=(GpsInfo&& from) noexcept { + inline Position& operator=(Position&& from) noexcept { if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { if (this != &from) InternalSwap(&from); } else { @@ -4136,34 +4314,34 @@ class GpsInfo : static const ::google::protobuf::Descriptor* descriptor() { return default_instance().GetDescriptor(); } - static const GpsInfo& default_instance(); + static const Position& default_instance(); static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY - static inline const GpsInfo* internal_default_instance() { - return reinterpret_cast( - &_GpsInfo_default_instance_); + static inline const Position* internal_default_instance() { + return reinterpret_cast( + &_Position_default_instance_); } static constexpr int kIndexInFileMessages = - 34; + 36; - void Swap(GpsInfo* other); - friend void swap(GpsInfo& a, GpsInfo& b) { + void Swap(Position* other); + friend void swap(Position& a, Position& b) { a.Swap(&b); } // implements Message ---------------------------------------------- - inline GpsInfo* New() const final { - return CreateMaybeMessage(nullptr); + inline Position* New() const final { + return CreateMaybeMessage(nullptr); } - GpsInfo* New(::google::protobuf::Arena* arena) const final { - return CreateMaybeMessage(arena); + Position* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); } void CopyFrom(const ::google::protobuf::Message& from) final; void MergeFrom(const ::google::protobuf::Message& from) final; - void CopyFrom(const GpsInfo& from); - void MergeFrom(const GpsInfo& from); + void CopyFrom(const Position& from); + void MergeFrom(const Position& from); PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; bool IsInitialized() const final; @@ -4185,7 +4363,7 @@ class GpsInfo : void SharedCtor(); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(GpsInfo* other); + void InternalSwap(Position* other); private: inline ::google::protobuf::Arena* GetArenaNoVirtual() const { return nullptr; @@ -4201,49 +4379,63 @@ class GpsInfo : // accessors ------------------------------------------------------- - // int32 num_satellites = 1; - void clear_num_satellites(); - static const int kNumSatellitesFieldNumber = 1; - ::google::protobuf::int32 num_satellites() const; - void set_num_satellites(::google::protobuf::int32 value); + // double latitude_deg = 1; + void clear_latitude_deg(); + static const int kLatitudeDegFieldNumber = 1; + double latitude_deg() const; + void set_latitude_deg(double value); - // .mavsdk.rpc.telemetry.FixType fix_type = 2; - void clear_fix_type(); - static const int kFixTypeFieldNumber = 2; - ::mavsdk::rpc::telemetry::FixType fix_type() const; - void set_fix_type(::mavsdk::rpc::telemetry::FixType value); + // double longitude_deg = 2; + void clear_longitude_deg(); + static const int kLongitudeDegFieldNumber = 2; + double longitude_deg() const; + void set_longitude_deg(double value); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GpsInfo) + // float absolute_altitude_m = 3; + void clear_absolute_altitude_m(); + static const int kAbsoluteAltitudeMFieldNumber = 3; + float absolute_altitude_m() const; + void set_absolute_altitude_m(float value); + + // float relative_altitude_m = 4; + void clear_relative_altitude_m(); + static const int kRelativeAltitudeMFieldNumber = 4; + float relative_altitude_m() const; + void set_relative_altitude_m(float value); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Position) private: class HasBitSetters; ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; - ::google::protobuf::int32 num_satellites_; - int fix_type_; + double latitude_deg_; + double longitude_deg_; + float absolute_altitude_m_; + float relative_altitude_m_; mutable ::google::protobuf::internal::CachedSize _cached_size_; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; }; // ------------------------------------------------------------------- -class Battery : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Battery) */ { +class Quaternion : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Quaternion) */ { public: - Battery(); - virtual ~Battery(); + Quaternion(); + virtual ~Quaternion(); - Battery(const Battery& from); + Quaternion(const Quaternion& from); - inline Battery& operator=(const Battery& from) { + inline Quaternion& operator=(const Quaternion& from) { CopyFrom(from); return *this; } #if LANG_CXX11 - Battery(Battery&& from) noexcept - : Battery() { + Quaternion(Quaternion&& from) noexcept + : Quaternion() { *this = ::std::move(from); } - inline Battery& operator=(Battery&& from) noexcept { + inline Quaternion& operator=(Quaternion&& from) noexcept { if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { if (this != &from) InternalSwap(&from); } else { @@ -4255,34 +4447,34 @@ class Battery : static const ::google::protobuf::Descriptor* descriptor() { return default_instance().GetDescriptor(); } - static const Battery& default_instance(); + static const Quaternion& default_instance(); static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY - static inline const Battery* internal_default_instance() { - return reinterpret_cast( - &_Battery_default_instance_); + static inline const Quaternion* internal_default_instance() { + return reinterpret_cast( + &_Quaternion_default_instance_); } static constexpr int kIndexInFileMessages = - 35; + 37; - void Swap(Battery* other); - friend void swap(Battery& a, Battery& b) { + void Swap(Quaternion* other); + friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); } // implements Message ---------------------------------------------- - inline Battery* New() const final { - return CreateMaybeMessage(nullptr); + inline Quaternion* New() const final { + return CreateMaybeMessage(nullptr); } - Battery* New(::google::protobuf::Arena* arena) const final { - return CreateMaybeMessage(arena); + Quaternion* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); } void CopyFrom(const ::google::protobuf::Message& from) final; void MergeFrom(const ::google::protobuf::Message& from) final; - void CopyFrom(const Battery& from); - void MergeFrom(const Battery& from); + void CopyFrom(const Quaternion& from); + void MergeFrom(const Quaternion& from); PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; bool IsInitialized() const final; @@ -4304,7 +4496,7 @@ class Battery : void SharedCtor(); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(Battery* other); + void InternalSwap(Quaternion* other); private: inline ::google::protobuf::Arena* GetArenaNoVirtual() const { return nullptr; @@ -4320,49 +4512,63 @@ class Battery : // accessors ------------------------------------------------------- - // float voltage_v = 1; - void clear_voltage_v(); - static const int kVoltageVFieldNumber = 1; - float voltage_v() const; - void set_voltage_v(float value); + // float w = 1; + void clear_w(); + static const int kWFieldNumber = 1; + float w() const; + void set_w(float value); - // float remaining_percent = 2; - void clear_remaining_percent(); - static const int kRemainingPercentFieldNumber = 2; - float remaining_percent() const; - void set_remaining_percent(float value); + // float x = 2; + void clear_x(); + static const int kXFieldNumber = 2; + float x() const; + void set_x(float value); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Battery) + // float y = 3; + void clear_y(); + static const int kYFieldNumber = 3; + float y() const; + void set_y(float value); + + // float z = 4; + void clear_z(); + static const int kZFieldNumber = 4; + float z() const; + void set_z(float value); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Quaternion) private: class HasBitSetters; ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; - float voltage_v_; - float remaining_percent_; + float w_; + float x_; + float y_; + float z_; mutable ::google::protobuf::internal::CachedSize _cached_size_; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; }; // ------------------------------------------------------------------- -class Health : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Health) */ { +class EulerAngle : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.EulerAngle) */ { public: - Health(); - virtual ~Health(); + EulerAngle(); + virtual ~EulerAngle(); - Health(const Health& from); + EulerAngle(const EulerAngle& from); - inline Health& operator=(const Health& from) { + inline EulerAngle& operator=(const EulerAngle& from) { CopyFrom(from); return *this; } #if LANG_CXX11 - Health(Health&& from) noexcept - : Health() { + EulerAngle(EulerAngle&& from) noexcept + : EulerAngle() { *this = ::std::move(from); } - inline Health& operator=(Health&& from) noexcept { + inline EulerAngle& operator=(EulerAngle&& from) noexcept { if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { if (this != &from) InternalSwap(&from); } else { @@ -4374,34 +4580,34 @@ class Health : static const ::google::protobuf::Descriptor* descriptor() { return default_instance().GetDescriptor(); } - static const Health& default_instance(); + static const EulerAngle& default_instance(); static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY - static inline const Health* internal_default_instance() { - return reinterpret_cast( - &_Health_default_instance_); + static inline const EulerAngle* internal_default_instance() { + return reinterpret_cast( + &_EulerAngle_default_instance_); } static constexpr int kIndexInFileMessages = - 36; + 38; - void Swap(Health* other); - friend void swap(Health& a, Health& b) { + void Swap(EulerAngle* other); + friend void swap(EulerAngle& a, EulerAngle& b) { a.Swap(&b); } // implements Message ---------------------------------------------- - inline Health* New() const final { - return CreateMaybeMessage(nullptr); + inline EulerAngle* New() const final { + return CreateMaybeMessage(nullptr); } - Health* New(::google::protobuf::Arena* arena) const final { - return CreateMaybeMessage(arena); + EulerAngle* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); } void CopyFrom(const ::google::protobuf::Message& from) final; void MergeFrom(const ::google::protobuf::Message& from) final; - void CopyFrom(const Health& from); - void MergeFrom(const Health& from); + void CopyFrom(const EulerAngle& from); + void MergeFrom(const EulerAngle& from); PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; bool IsInitialized() const final; @@ -4423,7 +4629,7 @@ class Health : void SharedCtor(); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(Health* other); + void InternalSwap(EulerAngle* other); private: inline ::google::protobuf::Arena* GetArenaNoVirtual() const { return nullptr; @@ -4439,84 +4645,56 @@ class Health : // accessors ------------------------------------------------------- - // bool is_gyrometer_calibration_ok = 1; - void clear_is_gyrometer_calibration_ok(); - static const int kIsGyrometerCalibrationOkFieldNumber = 1; - bool is_gyrometer_calibration_ok() const; - void set_is_gyrometer_calibration_ok(bool value); - - // bool is_accelerometer_calibration_ok = 2; - void clear_is_accelerometer_calibration_ok(); - static const int kIsAccelerometerCalibrationOkFieldNumber = 2; - bool is_accelerometer_calibration_ok() const; - void set_is_accelerometer_calibration_ok(bool value); - - // bool is_magnetometer_calibration_ok = 3; - void clear_is_magnetometer_calibration_ok(); - static const int kIsMagnetometerCalibrationOkFieldNumber = 3; - bool is_magnetometer_calibration_ok() const; - void set_is_magnetometer_calibration_ok(bool value); - - // bool is_level_calibration_ok = 4; - void clear_is_level_calibration_ok(); - static const int kIsLevelCalibrationOkFieldNumber = 4; - bool is_level_calibration_ok() const; - void set_is_level_calibration_ok(bool value); - - // bool is_local_position_ok = 5; - void clear_is_local_position_ok(); - static const int kIsLocalPositionOkFieldNumber = 5; - bool is_local_position_ok() const; - void set_is_local_position_ok(bool value); + // float roll_deg = 1; + void clear_roll_deg(); + static const int kRollDegFieldNumber = 1; + float roll_deg() const; + void set_roll_deg(float value); - // bool is_global_position_ok = 6; - void clear_is_global_position_ok(); - static const int kIsGlobalPositionOkFieldNumber = 6; - bool is_global_position_ok() const; - void set_is_global_position_ok(bool value); + // float pitch_deg = 2; + void clear_pitch_deg(); + static const int kPitchDegFieldNumber = 2; + float pitch_deg() const; + void set_pitch_deg(float value); - // bool is_home_position_ok = 7; - void clear_is_home_position_ok(); - static const int kIsHomePositionOkFieldNumber = 7; - bool is_home_position_ok() const; - void set_is_home_position_ok(bool value); + // float yaw_deg = 3; + void clear_yaw_deg(); + static const int kYawDegFieldNumber = 3; + float yaw_deg() const; + void set_yaw_deg(float value); - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Health) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.EulerAngle) private: class HasBitSetters; ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; - bool is_gyrometer_calibration_ok_; - bool is_accelerometer_calibration_ok_; - bool is_magnetometer_calibration_ok_; - bool is_level_calibration_ok_; - bool is_local_position_ok_; - bool is_global_position_ok_; - bool is_home_position_ok_; + float roll_deg_; + float pitch_deg_; + float yaw_deg_; mutable ::google::protobuf::internal::CachedSize _cached_size_; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; }; // ------------------------------------------------------------------- -class RcStatus : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.RcStatus) */ { +class AngularVelocityBody : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.AngularVelocityBody) */ { public: - RcStatus(); - virtual ~RcStatus(); + AngularVelocityBody(); + virtual ~AngularVelocityBody(); - RcStatus(const RcStatus& from); + AngularVelocityBody(const AngularVelocityBody& from); - inline RcStatus& operator=(const RcStatus& from) { + inline AngularVelocityBody& operator=(const AngularVelocityBody& from) { CopyFrom(from); return *this; } #if LANG_CXX11 - RcStatus(RcStatus&& from) noexcept - : RcStatus() { + AngularVelocityBody(AngularVelocityBody&& from) noexcept + : AngularVelocityBody() { *this = ::std::move(from); } - inline RcStatus& operator=(RcStatus&& from) noexcept { + inline AngularVelocityBody& operator=(AngularVelocityBody&& from) noexcept { if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { if (this != &from) InternalSwap(&from); } else { @@ -4528,34 +4706,959 @@ class RcStatus : static const ::google::protobuf::Descriptor* descriptor() { return default_instance().GetDescriptor(); } - static const RcStatus& default_instance(); + static const AngularVelocityBody& default_instance(); static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY - static inline const RcStatus* internal_default_instance() { - return reinterpret_cast( - &_RcStatus_default_instance_); + static inline const AngularVelocityBody* internal_default_instance() { + return reinterpret_cast( + &_AngularVelocityBody_default_instance_); } static constexpr int kIndexInFileMessages = - 37; + 39; - void Swap(RcStatus* other); - friend void swap(RcStatus& a, RcStatus& b) { + void Swap(AngularVelocityBody* other); + friend void swap(AngularVelocityBody& a, AngularVelocityBody& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline AngularVelocityBody* New() const final { + return CreateMaybeMessage(nullptr); + } + + AngularVelocityBody* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const AngularVelocityBody& from); + void MergeFrom(const AngularVelocityBody& from); + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + static const char* _InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx); + ::google::protobuf::internal::ParseFunc _ParseFunc() const final { return _InternalParse; } + #else + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(AngularVelocityBody* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return nullptr; + } + inline void* MaybeArenaPtr() const { + return nullptr; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // float roll_rad_s = 1; + void clear_roll_rad_s(); + static const int kRollRadSFieldNumber = 1; + float roll_rad_s() const; + void set_roll_rad_s(float value); + + // float pitch_rad_s = 2; + void clear_pitch_rad_s(); + static const int kPitchRadSFieldNumber = 2; + float pitch_rad_s() const; + void set_pitch_rad_s(float value); + + // float yaw_rad_s = 3; + void clear_yaw_rad_s(); + static const int kYawRadSFieldNumber = 3; + float yaw_rad_s() const; + void set_yaw_rad_s(float value); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.AngularVelocityBody) + private: + class HasBitSetters; + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + float roll_rad_s_; + float pitch_rad_s_; + float yaw_rad_s_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; +}; +// ------------------------------------------------------------------- + +class SpeedNed : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.SpeedNed) */ { + public: + SpeedNed(); + virtual ~SpeedNed(); + + SpeedNed(const SpeedNed& from); + + inline SpeedNed& operator=(const SpeedNed& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + SpeedNed(SpeedNed&& from) noexcept + : SpeedNed() { + *this = ::std::move(from); + } + + inline SpeedNed& operator=(SpeedNed&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor() { + return default_instance().GetDescriptor(); + } + static const SpeedNed& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const SpeedNed* internal_default_instance() { + return reinterpret_cast( + &_SpeedNed_default_instance_); + } + static constexpr int kIndexInFileMessages = + 40; + + void Swap(SpeedNed* other); + friend void swap(SpeedNed& a, SpeedNed& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline SpeedNed* New() const final { + return CreateMaybeMessage(nullptr); + } + + SpeedNed* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const SpeedNed& from); + void MergeFrom(const SpeedNed& from); + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + static const char* _InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx); + ::google::protobuf::internal::ParseFunc _ParseFunc() const final { return _InternalParse; } + #else + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(SpeedNed* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return nullptr; + } + inline void* MaybeArenaPtr() const { + return nullptr; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // float velocity_north_m_s = 1; + void clear_velocity_north_m_s(); + static const int kVelocityNorthMSFieldNumber = 1; + float velocity_north_m_s() const; + void set_velocity_north_m_s(float value); + + // float velocity_east_m_s = 2; + void clear_velocity_east_m_s(); + static const int kVelocityEastMSFieldNumber = 2; + float velocity_east_m_s() const; + void set_velocity_east_m_s(float value); + + // float velocity_down_m_s = 3; + void clear_velocity_down_m_s(); + static const int kVelocityDownMSFieldNumber = 3; + float velocity_down_m_s() const; + void set_velocity_down_m_s(float value); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.SpeedNed) + private: + class HasBitSetters; + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + float velocity_north_m_s_; + float velocity_east_m_s_; + float velocity_down_m_s_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; +}; +// ------------------------------------------------------------------- + +class GpsInfo : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.GpsInfo) */ { + public: + GpsInfo(); + virtual ~GpsInfo(); + + GpsInfo(const GpsInfo& from); + + inline GpsInfo& operator=(const GpsInfo& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + GpsInfo(GpsInfo&& from) noexcept + : GpsInfo() { + *this = ::std::move(from); + } + + inline GpsInfo& operator=(GpsInfo&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor() { + return default_instance().GetDescriptor(); + } + static const GpsInfo& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const GpsInfo* internal_default_instance() { + return reinterpret_cast( + &_GpsInfo_default_instance_); + } + static constexpr int kIndexInFileMessages = + 41; + + void Swap(GpsInfo* other); + friend void swap(GpsInfo& a, GpsInfo& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline GpsInfo* New() const final { + return CreateMaybeMessage(nullptr); + } + + GpsInfo* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const GpsInfo& from); + void MergeFrom(const GpsInfo& from); + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + static const char* _InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx); + ::google::protobuf::internal::ParseFunc _ParseFunc() const final { return _InternalParse; } + #else + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(GpsInfo* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return nullptr; + } + inline void* MaybeArenaPtr() const { + return nullptr; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // int32 num_satellites = 1; + void clear_num_satellites(); + static const int kNumSatellitesFieldNumber = 1; + ::google::protobuf::int32 num_satellites() const; + void set_num_satellites(::google::protobuf::int32 value); + + // .mavsdk.rpc.telemetry.FixType fix_type = 2; + void clear_fix_type(); + static const int kFixTypeFieldNumber = 2; + ::mavsdk::rpc::telemetry::FixType fix_type() const; + void set_fix_type(::mavsdk::rpc::telemetry::FixType value); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.GpsInfo) + private: + class HasBitSetters; + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::int32 num_satellites_; + int fix_type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; +}; +// ------------------------------------------------------------------- + +class Battery : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Battery) */ { + public: + Battery(); + virtual ~Battery(); + + Battery(const Battery& from); + + inline Battery& operator=(const Battery& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Battery(Battery&& from) noexcept + : Battery() { + *this = ::std::move(from); + } + + inline Battery& operator=(Battery&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor() { + return default_instance().GetDescriptor(); + } + static const Battery& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Battery* internal_default_instance() { + return reinterpret_cast( + &_Battery_default_instance_); + } + static constexpr int kIndexInFileMessages = + 42; + + void Swap(Battery* other); + friend void swap(Battery& a, Battery& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Battery* New() const final { + return CreateMaybeMessage(nullptr); + } + + Battery* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Battery& from); + void MergeFrom(const Battery& from); + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + static const char* _InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx); + ::google::protobuf::internal::ParseFunc _ParseFunc() const final { return _InternalParse; } + #else + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Battery* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return nullptr; + } + inline void* MaybeArenaPtr() const { + return nullptr; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // float voltage_v = 1; + void clear_voltage_v(); + static const int kVoltageVFieldNumber = 1; + float voltage_v() const; + void set_voltage_v(float value); + + // float remaining_percent = 2; + void clear_remaining_percent(); + static const int kRemainingPercentFieldNumber = 2; + float remaining_percent() const; + void set_remaining_percent(float value); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Battery) + private: + class HasBitSetters; + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + float voltage_v_; + float remaining_percent_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; +}; +// ------------------------------------------------------------------- + +class Health : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.Health) */ { + public: + Health(); + virtual ~Health(); + + Health(const Health& from); + + inline Health& operator=(const Health& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + Health(Health&& from) noexcept + : Health() { + *this = ::std::move(from); + } + + inline Health& operator=(Health&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor() { + return default_instance().GetDescriptor(); + } + static const Health& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const Health* internal_default_instance() { + return reinterpret_cast( + &_Health_default_instance_); + } + static constexpr int kIndexInFileMessages = + 43; + + void Swap(Health* other); + friend void swap(Health& a, Health& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline Health* New() const final { + return CreateMaybeMessage(nullptr); + } + + Health* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const Health& from); + void MergeFrom(const Health& from); + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + static const char* _InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx); + ::google::protobuf::internal::ParseFunc _ParseFunc() const final { return _InternalParse; } + #else + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(Health* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return nullptr; + } + inline void* MaybeArenaPtr() const { + return nullptr; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // bool is_gyrometer_calibration_ok = 1; + void clear_is_gyrometer_calibration_ok(); + static const int kIsGyrometerCalibrationOkFieldNumber = 1; + bool is_gyrometer_calibration_ok() const; + void set_is_gyrometer_calibration_ok(bool value); + + // bool is_accelerometer_calibration_ok = 2; + void clear_is_accelerometer_calibration_ok(); + static const int kIsAccelerometerCalibrationOkFieldNumber = 2; + bool is_accelerometer_calibration_ok() const; + void set_is_accelerometer_calibration_ok(bool value); + + // bool is_magnetometer_calibration_ok = 3; + void clear_is_magnetometer_calibration_ok(); + static const int kIsMagnetometerCalibrationOkFieldNumber = 3; + bool is_magnetometer_calibration_ok() const; + void set_is_magnetometer_calibration_ok(bool value); + + // bool is_level_calibration_ok = 4; + void clear_is_level_calibration_ok(); + static const int kIsLevelCalibrationOkFieldNumber = 4; + bool is_level_calibration_ok() const; + void set_is_level_calibration_ok(bool value); + + // bool is_local_position_ok = 5; + void clear_is_local_position_ok(); + static const int kIsLocalPositionOkFieldNumber = 5; + bool is_local_position_ok() const; + void set_is_local_position_ok(bool value); + + // bool is_global_position_ok = 6; + void clear_is_global_position_ok(); + static const int kIsGlobalPositionOkFieldNumber = 6; + bool is_global_position_ok() const; + void set_is_global_position_ok(bool value); + + // bool is_home_position_ok = 7; + void clear_is_home_position_ok(); + static const int kIsHomePositionOkFieldNumber = 7; + bool is_home_position_ok() const; + void set_is_home_position_ok(bool value); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.Health) + private: + class HasBitSetters; + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + bool is_gyrometer_calibration_ok_; + bool is_accelerometer_calibration_ok_; + bool is_magnetometer_calibration_ok_; + bool is_level_calibration_ok_; + bool is_local_position_ok_; + bool is_global_position_ok_; + bool is_home_position_ok_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; +}; +// ------------------------------------------------------------------- + +class RcStatus : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.RcStatus) */ { + public: + RcStatus(); + virtual ~RcStatus(); + + RcStatus(const RcStatus& from); + + inline RcStatus& operator=(const RcStatus& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + RcStatus(RcStatus&& from) noexcept + : RcStatus() { + *this = ::std::move(from); + } + + inline RcStatus& operator=(RcStatus&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor() { + return default_instance().GetDescriptor(); + } + static const RcStatus& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const RcStatus* internal_default_instance() { + return reinterpret_cast( + &_RcStatus_default_instance_); + } + static constexpr int kIndexInFileMessages = + 44; + + void Swap(RcStatus* other); + friend void swap(RcStatus& a, RcStatus& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline RcStatus* New() const final { + return CreateMaybeMessage(nullptr); + } + + RcStatus* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const RcStatus& from); + void MergeFrom(const RcStatus& from); + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + static const char* _InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx); + ::google::protobuf::internal::ParseFunc _ParseFunc() const final { return _InternalParse; } + #else + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(RcStatus* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return nullptr; + } + inline void* MaybeArenaPtr() const { + return nullptr; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // bool was_available_once = 1; + void clear_was_available_once(); + static const int kWasAvailableOnceFieldNumber = 1; + bool was_available_once() const; + void set_was_available_once(bool value); + + // bool is_available = 2; + void clear_is_available(); + static const int kIsAvailableFieldNumber = 2; + bool is_available() const; + void set_is_available(bool value); + + // float signal_strength_percent = 3; + void clear_signal_strength_percent(); + static const int kSignalStrengthPercentFieldNumber = 3; + float signal_strength_percent() const; + void set_signal_strength_percent(float value); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.RcStatus) + private: + class HasBitSetters; + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + bool was_available_once_; + bool is_available_; + float signal_strength_percent_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; +}; +// ------------------------------------------------------------------- + +class StatusText : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.StatusText) */ { + public: + StatusText(); + virtual ~StatusText(); + + StatusText(const StatusText& from); + + inline StatusText& operator=(const StatusText& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + StatusText(StatusText&& from) noexcept + : StatusText() { + *this = ::std::move(from); + } + + inline StatusText& operator=(StatusText&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor() { + return default_instance().GetDescriptor(); + } + static const StatusText& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const StatusText* internal_default_instance() { + return reinterpret_cast( + &_StatusText_default_instance_); + } + static constexpr int kIndexInFileMessages = + 45; + + void Swap(StatusText* other); + friend void swap(StatusText& a, StatusText& b) { + a.Swap(&b); + } + + // implements Message ---------------------------------------------- + + inline StatusText* New() const final { + return CreateMaybeMessage(nullptr); + } + + StatusText* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); + } + void CopyFrom(const ::google::protobuf::Message& from) final; + void MergeFrom(const ::google::protobuf::Message& from) final; + void CopyFrom(const StatusText& from); + void MergeFrom(const StatusText& from); + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + size_t ByteSizeLong() const final; + #if GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + static const char* _InternalParse(const char* begin, const char* end, void* object, ::google::protobuf::internal::ParseContext* ctx); + ::google::protobuf::internal::ParseFunc _ParseFunc() const final { return _InternalParse; } + #else + bool MergePartialFromCodedStream( + ::google::protobuf::io::CodedInputStream* input) final; + #endif // GOOGLE_PROTOBUF_ENABLE_EXPERIMENTAL_PARSER + void SerializeWithCachedSizes( + ::google::protobuf::io::CodedOutputStream* output) const final; + ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray( + ::google::protobuf::uint8* target) const final; + int GetCachedSize() const final { return _cached_size_.Get(); } + + private: + void SharedCtor(); + void SharedDtor(); + void SetCachedSize(int size) const final; + void InternalSwap(StatusText* other); + private: + inline ::google::protobuf::Arena* GetArenaNoVirtual() const { + return nullptr; + } + inline void* MaybeArenaPtr() const { + return nullptr; + } + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + typedef StatusText_StatusType StatusType; + static const StatusType INFO = + StatusText_StatusType_INFO; + static const StatusType WARNING = + StatusText_StatusType_WARNING; + static const StatusType CRITICAL = + StatusText_StatusType_CRITICAL; + static inline bool StatusType_IsValid(int value) { + return StatusText_StatusType_IsValid(value); + } + static const StatusType StatusType_MIN = + StatusText_StatusType_StatusType_MIN; + static const StatusType StatusType_MAX = + StatusText_StatusType_StatusType_MAX; + static const int StatusType_ARRAYSIZE = + StatusText_StatusType_StatusType_ARRAYSIZE; + static inline const ::google::protobuf::EnumDescriptor* + StatusType_descriptor() { + return StatusText_StatusType_descriptor(); + } + static inline const ::std::string& StatusType_Name(StatusType value) { + return StatusText_StatusType_Name(value); + } + static inline bool StatusType_Parse(const ::std::string& name, + StatusType* value) { + return StatusText_StatusType_Parse(name, value); + } + + // accessors ------------------------------------------------------- + + // string text = 2; + void clear_text(); + static const int kTextFieldNumber = 2; + const ::std::string& text() const; + void set_text(const ::std::string& value); + #if LANG_CXX11 + void set_text(::std::string&& value); + #endif + void set_text(const char* value); + void set_text(const char* value, size_t size); + ::std::string* mutable_text(); + ::std::string* release_text(); + void set_allocated_text(::std::string* text); + + // .mavsdk.rpc.telemetry.StatusText.StatusType type = 1; + void clear_type(); + static const int kTypeFieldNumber = 1; + ::mavsdk::rpc::telemetry::StatusText_StatusType type() const; + void set_type(::mavsdk::rpc::telemetry::StatusText_StatusType value); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.StatusText) + private: + class HasBitSetters; + + ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; + ::google::protobuf::internal::ArenaStringPtr text_; + int type_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; +}; +// ------------------------------------------------------------------- + +class ActuatorControlTarget : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.ActuatorControlTarget) */ { + public: + ActuatorControlTarget(); + virtual ~ActuatorControlTarget(); + + ActuatorControlTarget(const ActuatorControlTarget& from); + + inline ActuatorControlTarget& operator=(const ActuatorControlTarget& from) { + CopyFrom(from); + return *this; + } + #if LANG_CXX11 + ActuatorControlTarget(ActuatorControlTarget&& from) noexcept + : ActuatorControlTarget() { + *this = ::std::move(from); + } + + inline ActuatorControlTarget& operator=(ActuatorControlTarget&& from) noexcept { + if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { + if (this != &from) InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + #endif + static const ::google::protobuf::Descriptor* descriptor() { + return default_instance().GetDescriptor(); + } + static const ActuatorControlTarget& default_instance(); + + static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY + static inline const ActuatorControlTarget* internal_default_instance() { + return reinterpret_cast( + &_ActuatorControlTarget_default_instance_); + } + static constexpr int kIndexInFileMessages = + 46; + + void Swap(ActuatorControlTarget* other); + friend void swap(ActuatorControlTarget& a, ActuatorControlTarget& b) { a.Swap(&b); } // implements Message ---------------------------------------------- - inline RcStatus* New() const final { - return CreateMaybeMessage(nullptr); + inline ActuatorControlTarget* New() const final { + return CreateMaybeMessage(nullptr); } - RcStatus* New(::google::protobuf::Arena* arena) const final { - return CreateMaybeMessage(arena); + ActuatorControlTarget* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); } void CopyFrom(const ::google::protobuf::Message& from) final; void MergeFrom(const ::google::protobuf::Message& from) final; - void CopyFrom(const RcStatus& from); - void MergeFrom(const RcStatus& from); + void CopyFrom(const ActuatorControlTarget& from); + void MergeFrom(const ActuatorControlTarget& from); PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; bool IsInitialized() const final; @@ -4577,7 +5680,7 @@ class RcStatus : void SharedCtor(); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(RcStatus* other); + void InternalSwap(ActuatorControlTarget* other); private: inline ::google::protobuf::Arena* GetArenaNoVirtual() const { return nullptr; @@ -4593,56 +5696,56 @@ class RcStatus : // accessors ------------------------------------------------------- - // bool was_available_once = 1; - void clear_was_available_once(); - static const int kWasAvailableOnceFieldNumber = 1; - bool was_available_once() const; - void set_was_available_once(bool value); - - // bool is_available = 2; - void clear_is_available(); - static const int kIsAvailableFieldNumber = 2; - bool is_available() const; - void set_is_available(bool value); - - // float signal_strength_percent = 3; - void clear_signal_strength_percent(); - static const int kSignalStrengthPercentFieldNumber = 3; - float signal_strength_percent() const; - void set_signal_strength_percent(float value); - - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.RcStatus) + // repeated float controls = 2; + int controls_size() const; + void clear_controls(); + static const int kControlsFieldNumber = 2; + float controls(int index) const; + void set_controls(int index, float value); + void add_controls(float value); + const ::google::protobuf::RepeatedField< float >& + controls() const; + ::google::protobuf::RepeatedField< float >* + mutable_controls(); + + // int32 group = 1; + void clear_group(); + static const int kGroupFieldNumber = 1; + ::google::protobuf::int32 group() const; + void set_group(::google::protobuf::int32 value); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.ActuatorControlTarget) private: class HasBitSetters; ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; - bool was_available_once_; - bool is_available_; - float signal_strength_percent_; + ::google::protobuf::RepeatedField< float > controls_; + mutable std::atomic _controls_cached_byte_size_; + ::google::protobuf::int32 group_; mutable ::google::protobuf::internal::CachedSize _cached_size_; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; }; // ------------------------------------------------------------------- -class StatusText : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.StatusText) */ { +class ActuatorOutputStatus : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.telemetry.ActuatorOutputStatus) */ { public: - StatusText(); - virtual ~StatusText(); + ActuatorOutputStatus(); + virtual ~ActuatorOutputStatus(); - StatusText(const StatusText& from); + ActuatorOutputStatus(const ActuatorOutputStatus& from); - inline StatusText& operator=(const StatusText& from) { + inline ActuatorOutputStatus& operator=(const ActuatorOutputStatus& from) { CopyFrom(from); return *this; } #if LANG_CXX11 - StatusText(StatusText&& from) noexcept - : StatusText() { + ActuatorOutputStatus(ActuatorOutputStatus&& from) noexcept + : ActuatorOutputStatus() { *this = ::std::move(from); } - inline StatusText& operator=(StatusText&& from) noexcept { + inline ActuatorOutputStatus& operator=(ActuatorOutputStatus&& from) noexcept { if (GetArenaNoVirtual() == from.GetArenaNoVirtual()) { if (this != &from) InternalSwap(&from); } else { @@ -4654,34 +5757,34 @@ class StatusText : static const ::google::protobuf::Descriptor* descriptor() { return default_instance().GetDescriptor(); } - static const StatusText& default_instance(); + static const ActuatorOutputStatus& default_instance(); static void InitAsDefaultInstance(); // FOR INTERNAL USE ONLY - static inline const StatusText* internal_default_instance() { - return reinterpret_cast( - &_StatusText_default_instance_); + static inline const ActuatorOutputStatus* internal_default_instance() { + return reinterpret_cast( + &_ActuatorOutputStatus_default_instance_); } static constexpr int kIndexInFileMessages = - 38; + 47; - void Swap(StatusText* other); - friend void swap(StatusText& a, StatusText& b) { + void Swap(ActuatorOutputStatus* other); + friend void swap(ActuatorOutputStatus& a, ActuatorOutputStatus& b) { a.Swap(&b); } // implements Message ---------------------------------------------- - inline StatusText* New() const final { - return CreateMaybeMessage(nullptr); + inline ActuatorOutputStatus* New() const final { + return CreateMaybeMessage(nullptr); } - StatusText* New(::google::protobuf::Arena* arena) const final { - return CreateMaybeMessage(arena); + ActuatorOutputStatus* New(::google::protobuf::Arena* arena) const final { + return CreateMaybeMessage(arena); } void CopyFrom(const ::google::protobuf::Message& from) final; void MergeFrom(const ::google::protobuf::Message& from) final; - void CopyFrom(const StatusText& from); - void MergeFrom(const StatusText& from); + void CopyFrom(const ActuatorOutputStatus& from); + void MergeFrom(const ActuatorOutputStatus& from); PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; bool IsInitialized() const final; @@ -4703,7 +5806,7 @@ class StatusText : void SharedCtor(); void SharedDtor(); void SetCachedSize(int size) const final; - void InternalSwap(StatusText* other); + void InternalSwap(ActuatorOutputStatus* other); private: inline ::google::protobuf::Arena* GetArenaNoVirtual() const { return nullptr; @@ -4717,63 +5820,34 @@ class StatusText : // nested types ---------------------------------------------------- - typedef StatusText_StatusType StatusType; - static const StatusType INFO = - StatusText_StatusType_INFO; - static const StatusType WARNING = - StatusText_StatusType_WARNING; - static const StatusType CRITICAL = - StatusText_StatusType_CRITICAL; - static inline bool StatusType_IsValid(int value) { - return StatusText_StatusType_IsValid(value); - } - static const StatusType StatusType_MIN = - StatusText_StatusType_StatusType_MIN; - static const StatusType StatusType_MAX = - StatusText_StatusType_StatusType_MAX; - static const int StatusType_ARRAYSIZE = - StatusText_StatusType_StatusType_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* - StatusType_descriptor() { - return StatusText_StatusType_descriptor(); - } - static inline const ::std::string& StatusType_Name(StatusType value) { - return StatusText_StatusType_Name(value); - } - static inline bool StatusType_Parse(const ::std::string& name, - StatusType* value) { - return StatusText_StatusType_Parse(name, value); - } - // accessors ------------------------------------------------------- - // string text = 2; - void clear_text(); - static const int kTextFieldNumber = 2; - const ::std::string& text() const; - void set_text(const ::std::string& value); - #if LANG_CXX11 - void set_text(::std::string&& value); - #endif - void set_text(const char* value); - void set_text(const char* value, size_t size); - ::std::string* mutable_text(); - ::std::string* release_text(); - void set_allocated_text(::std::string* text); - - // .mavsdk.rpc.telemetry.StatusText.StatusType type = 1; - void clear_type(); - static const int kTypeFieldNumber = 1; - ::mavsdk::rpc::telemetry::StatusText_StatusType type() const; - void set_type(::mavsdk::rpc::telemetry::StatusText_StatusType value); - - // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.StatusText) + // repeated float actuator = 2; + int actuator_size() const; + void clear_actuator(); + static const int kActuatorFieldNumber = 2; + float actuator(int index) const; + void set_actuator(int index, float value); + void add_actuator(float value); + const ::google::protobuf::RepeatedField< float >& + actuator() const; + ::google::protobuf::RepeatedField< float >* + mutable_actuator(); + + // uint32 active = 1; + void clear_active(); + static const int kActiveFieldNumber = 1; + ::google::protobuf::uint32 active() const; + void set_active(::google::protobuf::uint32 value); + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.telemetry.ActuatorOutputStatus) private: class HasBitSetters; ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_; - ::google::protobuf::internal::ArenaStringPtr text_; - int type_; + ::google::protobuf::RepeatedField< float > actuator_; + mutable std::atomic _actuator_cached_byte_size_; + ::google::protobuf::uint32 active_; mutable ::google::protobuf::internal::CachedSize _cached_size_; friend struct ::TableStruct_telemetry_2ftelemetry_2eproto; }; @@ -5066,6 +6140,65 @@ inline void AttitudeEulerResponse::set_allocated_attitude_euler(::mavsdk::rpc::t // ------------------------------------------------------------------- +// SubscribeAttitudeAngularVelocityBodyRequest + +// ------------------------------------------------------------------- + +// AttitudeAngularVelocityBodyResponse + +// .mavsdk.rpc.telemetry.AngularVelocityBody attitude_angular_velocity_body = 1; +inline bool AttitudeAngularVelocityBodyResponse::has_attitude_angular_velocity_body() const { + return this != internal_default_instance() && attitude_angular_velocity_body_ != nullptr; +} +inline void AttitudeAngularVelocityBodyResponse::clear_attitude_angular_velocity_body() { + if (GetArenaNoVirtual() == nullptr && attitude_angular_velocity_body_ != nullptr) { + delete attitude_angular_velocity_body_; + } + attitude_angular_velocity_body_ = nullptr; +} +inline const ::mavsdk::rpc::telemetry::AngularVelocityBody& AttitudeAngularVelocityBodyResponse::attitude_angular_velocity_body() const { + const ::mavsdk::rpc::telemetry::AngularVelocityBody* p = attitude_angular_velocity_body_; + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse.attitude_angular_velocity_body) + return p != nullptr ? *p : *reinterpret_cast( + &::mavsdk::rpc::telemetry::_AngularVelocityBody_default_instance_); +} +inline ::mavsdk::rpc::telemetry::AngularVelocityBody* AttitudeAngularVelocityBodyResponse::release_attitude_angular_velocity_body() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse.attitude_angular_velocity_body) + + ::mavsdk::rpc::telemetry::AngularVelocityBody* temp = attitude_angular_velocity_body_; + attitude_angular_velocity_body_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::telemetry::AngularVelocityBody* AttitudeAngularVelocityBodyResponse::mutable_attitude_angular_velocity_body() { + + if (attitude_angular_velocity_body_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::telemetry::AngularVelocityBody>(GetArenaNoVirtual()); + attitude_angular_velocity_body_ = p; + } + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse.attitude_angular_velocity_body) + return attitude_angular_velocity_body_; +} +inline void AttitudeAngularVelocityBodyResponse::set_allocated_attitude_angular_velocity_body(::mavsdk::rpc::telemetry::AngularVelocityBody* attitude_angular_velocity_body) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == nullptr) { + delete attitude_angular_velocity_body_; + } + if (attitude_angular_velocity_body) { + ::google::protobuf::Arena* submessage_arena = nullptr; + if (message_arena != submessage_arena) { + attitude_angular_velocity_body = ::google::protobuf::internal::GetOwnedMessage( + message_arena, attitude_angular_velocity_body, submessage_arena); + } + + } else { + + } + attitude_angular_velocity_body_ = attitude_angular_velocity_body; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry.AttitudeAngularVelocityBodyResponse.attitude_angular_velocity_body) +} + +// ------------------------------------------------------------------- + // SubscribeCameraAttitudeQuaternionRequest // ------------------------------------------------------------------- @@ -5560,6 +6693,124 @@ inline void StatusTextResponse::set_allocated_status_text(::mavsdk::rpc::telemet // ------------------------------------------------------------------- +// SubscribeActuatorControlTargetRequest + +// ------------------------------------------------------------------- + +// ActuatorControlTargetResponse + +// .mavsdk.rpc.telemetry.ActuatorControlTarget actuator_control_target = 1; +inline bool ActuatorControlTargetResponse::has_actuator_control_target() const { + return this != internal_default_instance() && actuator_control_target_ != nullptr; +} +inline void ActuatorControlTargetResponse::clear_actuator_control_target() { + if (GetArenaNoVirtual() == nullptr && actuator_control_target_ != nullptr) { + delete actuator_control_target_; + } + actuator_control_target_ = nullptr; +} +inline const ::mavsdk::rpc::telemetry::ActuatorControlTarget& ActuatorControlTargetResponse::actuator_control_target() const { + const ::mavsdk::rpc::telemetry::ActuatorControlTarget* p = actuator_control_target_; + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.ActuatorControlTargetResponse.actuator_control_target) + return p != nullptr ? *p : *reinterpret_cast( + &::mavsdk::rpc::telemetry::_ActuatorControlTarget_default_instance_); +} +inline ::mavsdk::rpc::telemetry::ActuatorControlTarget* ActuatorControlTargetResponse::release_actuator_control_target() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry.ActuatorControlTargetResponse.actuator_control_target) + + ::mavsdk::rpc::telemetry::ActuatorControlTarget* temp = actuator_control_target_; + actuator_control_target_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::telemetry::ActuatorControlTarget* ActuatorControlTargetResponse::mutable_actuator_control_target() { + + if (actuator_control_target_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::telemetry::ActuatorControlTarget>(GetArenaNoVirtual()); + actuator_control_target_ = p; + } + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry.ActuatorControlTargetResponse.actuator_control_target) + return actuator_control_target_; +} +inline void ActuatorControlTargetResponse::set_allocated_actuator_control_target(::mavsdk::rpc::telemetry::ActuatorControlTarget* actuator_control_target) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == nullptr) { + delete actuator_control_target_; + } + if (actuator_control_target) { + ::google::protobuf::Arena* submessage_arena = nullptr; + if (message_arena != submessage_arena) { + actuator_control_target = ::google::protobuf::internal::GetOwnedMessage( + message_arena, actuator_control_target, submessage_arena); + } + + } else { + + } + actuator_control_target_ = actuator_control_target; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry.ActuatorControlTargetResponse.actuator_control_target) +} + +// ------------------------------------------------------------------- + +// SubscribeActuatorOutputStatusRequest + +// ------------------------------------------------------------------- + +// ActuatorOutputStatusResponse + +// .mavsdk.rpc.telemetry.ActuatorOutputStatus actuator_output_status = 1; +inline bool ActuatorOutputStatusResponse::has_actuator_output_status() const { + return this != internal_default_instance() && actuator_output_status_ != nullptr; +} +inline void ActuatorOutputStatusResponse::clear_actuator_output_status() { + if (GetArenaNoVirtual() == nullptr && actuator_output_status_ != nullptr) { + delete actuator_output_status_; + } + actuator_output_status_ = nullptr; +} +inline const ::mavsdk::rpc::telemetry::ActuatorOutputStatus& ActuatorOutputStatusResponse::actuator_output_status() const { + const ::mavsdk::rpc::telemetry::ActuatorOutputStatus* p = actuator_output_status_; + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse.actuator_output_status) + return p != nullptr ? *p : *reinterpret_cast( + &::mavsdk::rpc::telemetry::_ActuatorOutputStatus_default_instance_); +} +inline ::mavsdk::rpc::telemetry::ActuatorOutputStatus* ActuatorOutputStatusResponse::release_actuator_output_status() { + // @@protoc_insertion_point(field_release:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse.actuator_output_status) + + ::mavsdk::rpc::telemetry::ActuatorOutputStatus* temp = actuator_output_status_; + actuator_output_status_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::telemetry::ActuatorOutputStatus* ActuatorOutputStatusResponse::mutable_actuator_output_status() { + + if (actuator_output_status_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::telemetry::ActuatorOutputStatus>(GetArenaNoVirtual()); + actuator_output_status_ = p; + } + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse.actuator_output_status) + return actuator_output_status_; +} +inline void ActuatorOutputStatusResponse::set_allocated_actuator_output_status(::mavsdk::rpc::telemetry::ActuatorOutputStatus* actuator_output_status) { + ::google::protobuf::Arena* message_arena = GetArenaNoVirtual(); + if (message_arena == nullptr) { + delete actuator_output_status_; + } + if (actuator_output_status) { + ::google::protobuf::Arena* submessage_arena = nullptr; + if (message_arena != submessage_arena) { + actuator_output_status = ::google::protobuf::internal::GetOwnedMessage( + message_arena, actuator_output_status, submessage_arena); + } + + } else { + + } + actuator_output_status_ = actuator_output_status; + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry.ActuatorOutputStatusResponse.actuator_output_status) +} + +// ------------------------------------------------------------------- + // Position // double latitude_deg = 1; @@ -5726,6 +6977,52 @@ inline void EulerAngle::set_yaw_deg(float value) { // ------------------------------------------------------------------- +// AngularVelocityBody + +// float roll_rad_s = 1; +inline void AngularVelocityBody::clear_roll_rad_s() { + roll_rad_s_ = 0; +} +inline float AngularVelocityBody::roll_rad_s() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.AngularVelocityBody.roll_rad_s) + return roll_rad_s_; +} +inline void AngularVelocityBody::set_roll_rad_s(float value) { + + roll_rad_s_ = value; + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.AngularVelocityBody.roll_rad_s) +} + +// float pitch_rad_s = 2; +inline void AngularVelocityBody::clear_pitch_rad_s() { + pitch_rad_s_ = 0; +} +inline float AngularVelocityBody::pitch_rad_s() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.AngularVelocityBody.pitch_rad_s) + return pitch_rad_s_; +} +inline void AngularVelocityBody::set_pitch_rad_s(float value) { + + pitch_rad_s_ = value; + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.AngularVelocityBody.pitch_rad_s) +} + +// float yaw_rad_s = 3; +inline void AngularVelocityBody::clear_yaw_rad_s() { + yaw_rad_s_ = 0; +} +inline float AngularVelocityBody::yaw_rad_s() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.AngularVelocityBody.yaw_rad_s) + return yaw_rad_s_; +} +inline void AngularVelocityBody::set_yaw_rad_s(float value) { + + yaw_rad_s_ = value; + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.AngularVelocityBody.yaw_rad_s) +} + +// ------------------------------------------------------------------- + // SpeedNed // float velocity_north_m_s = 1; @@ -6053,6 +7350,102 @@ inline void StatusText::set_allocated_text(::std::string* text) { // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.telemetry.StatusText.text) } +// ------------------------------------------------------------------- + +// ActuatorControlTarget + +// int32 group = 1; +inline void ActuatorControlTarget::clear_group() { + group_ = 0; +} +inline ::google::protobuf::int32 ActuatorControlTarget::group() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.ActuatorControlTarget.group) + return group_; +} +inline void ActuatorControlTarget::set_group(::google::protobuf::int32 value) { + + group_ = value; + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.ActuatorControlTarget.group) +} + +// repeated float controls = 2; +inline int ActuatorControlTarget::controls_size() const { + return controls_.size(); +} +inline void ActuatorControlTarget::clear_controls() { + controls_.Clear(); +} +inline float ActuatorControlTarget::controls(int index) const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.ActuatorControlTarget.controls) + return controls_.Get(index); +} +inline void ActuatorControlTarget::set_controls(int index, float value) { + controls_.Set(index, value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.ActuatorControlTarget.controls) +} +inline void ActuatorControlTarget::add_controls(float value) { + controls_.Add(value); + // @@protoc_insertion_point(field_add:mavsdk.rpc.telemetry.ActuatorControlTarget.controls) +} +inline const ::google::protobuf::RepeatedField< float >& +ActuatorControlTarget::controls() const { + // @@protoc_insertion_point(field_list:mavsdk.rpc.telemetry.ActuatorControlTarget.controls) + return controls_; +} +inline ::google::protobuf::RepeatedField< float >* +ActuatorControlTarget::mutable_controls() { + // @@protoc_insertion_point(field_mutable_list:mavsdk.rpc.telemetry.ActuatorControlTarget.controls) + return &controls_; +} + +// ------------------------------------------------------------------- + +// ActuatorOutputStatus + +// uint32 active = 1; +inline void ActuatorOutputStatus::clear_active() { + active_ = 0u; +} +inline ::google::protobuf::uint32 ActuatorOutputStatus::active() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.ActuatorOutputStatus.active) + return active_; +} +inline void ActuatorOutputStatus::set_active(::google::protobuf::uint32 value) { + + active_ = value; + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.ActuatorOutputStatus.active) +} + +// repeated float actuator = 2; +inline int ActuatorOutputStatus::actuator_size() const { + return actuator_.size(); +} +inline void ActuatorOutputStatus::clear_actuator() { + actuator_.Clear(); +} +inline float ActuatorOutputStatus::actuator(int index) const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.telemetry.ActuatorOutputStatus.actuator) + return actuator_.Get(index); +} +inline void ActuatorOutputStatus::set_actuator(int index, float value) { + actuator_.Set(index, value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.telemetry.ActuatorOutputStatus.actuator) +} +inline void ActuatorOutputStatus::add_actuator(float value) { + actuator_.Add(value); + // @@protoc_insertion_point(field_add:mavsdk.rpc.telemetry.ActuatorOutputStatus.actuator) +} +inline const ::google::protobuf::RepeatedField< float >& +ActuatorOutputStatus::actuator() const { + // @@protoc_insertion_point(field_list:mavsdk.rpc.telemetry.ActuatorOutputStatus.actuator) + return actuator_; +} +inline ::google::protobuf::RepeatedField< float >* +ActuatorOutputStatus::mutable_actuator() { + // @@protoc_insertion_point(field_mutable_list:mavsdk.rpc.telemetry.ActuatorOutputStatus.actuator) + return &actuator_; +} + #ifdef __GNUC__ #pragma GCC diagnostic pop #endif // __GNUC__ @@ -6132,6 +7525,24 @@ inline void StatusText::set_allocated_text(::std::string* text) { // ------------------------------------------------------------------- +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + +// ------------------------------------------------------------------- + // @@protoc_insertion_point(namespace_scope) diff --git a/tools/generate_from_protos.sh b/tools/generate_from_protos.sh index c20d4a2b73..a62d73b7b3 100755 --- a/tools/generate_from_protos.sh +++ b/tools/generate_from_protos.sh @@ -4,7 +4,7 @@ set -e script_dir="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" -proto_dir="${script_dir}/../proto/protos" +proto_dir="${script_dir}/../src/backend/proto/protos" backend_generated_dir="${script_dir}/../src/backend/src/generated" third_party_dir="${script_dir}/../build/default/third_party" protoc_binary="${third_party_dir}/install/bin/protoc" From dd7f64c0bc1c030f4f9a899e010105d1c1181b7c Mon Sep 17 00:00:00 2001 From: Ildar Sadykov Date: Wed, 14 Aug 2019 20:01:45 +0300 Subject: [PATCH 5/5] C-style array -> std::array And doc fix. --- .../include/plugins/telemetry/telemetry.h | 4 +-- src/plugins/telemetry/telemetry_impl.cpp | 29 ++++++++++++------- src/plugins/telemetry/telemetry_impl.h | 4 +-- 3 files changed, 22 insertions(+), 15 deletions(-) diff --git a/src/plugins/telemetry/include/plugins/telemetry/telemetry.h b/src/plugins/telemetry/include/plugins/telemetry/telemetry.h index 42cdf5b750..e2aedde080 100644 --- a/src/plugins/telemetry/include/plugins/telemetry/telemetry.h +++ b/src/plugins/telemetry/include/plugins/telemetry/telemetry.h @@ -563,7 +563,7 @@ class Telemetry : public PluginBase { * @note To stop sending it completely, use a rate_hz of -1, for default rate use 0. * * @param rate_hz Rate in Hz. - * @return callback Callback to receive request result. + * @param callback Callback to receive request result. */ void set_rate_actuator_control_target_async(double rate_hz, result_callback_t callback); @@ -573,7 +573,7 @@ class Telemetry : public PluginBase { * @note To stop sending it completely, use a rate_hz of -1, for default rate use 0. * * @param rate_hz Rate in Hz. - * @return callback Callback to receive request result. + * @param callback Callback to receive request result. */ void set_rate_actuator_output_status_async(double rate_hz, result_callback_t callback); diff --git a/src/plugins/telemetry/telemetry_impl.cpp b/src/plugins/telemetry/telemetry_impl.cpp index 575bbce172..13df56e84d 100644 --- a/src/plugins/telemetry/telemetry_impl.cpp +++ b/src/plugins/telemetry/telemetry_impl.cpp @@ -6,6 +6,7 @@ #include #include #include +#include namespace mavsdk { @@ -725,11 +726,13 @@ void TelemetryImpl::process_unix_epoch_time(const mavlink_message_t& message) void TelemetryImpl::process_actuator_control_target(const mavlink_message_t& message) { - mavlink_actuator_control_target_t actuator_control_target; - mavlink_msg_actuator_control_target_decode(&message, &actuator_control_target); + uint32_t group; + std::array controls; - set_actuator_control_target( - actuator_control_target.group_mlx, actuator_control_target.controls); + group = mavlink_msg_actuator_control_target_get_group_mlx(&message); + mavlink_msg_actuator_control_target_get_controls(&message, controls.data()); + + set_actuator_control_target(group, controls); if (_actuator_control_target_subscription) { auto callback = _actuator_control_target_subscription; @@ -740,10 +743,13 @@ void TelemetryImpl::process_actuator_control_target(const mavlink_message_t& mes void TelemetryImpl::process_actuator_output_status(const mavlink_message_t& message) { - mavlink_actuator_output_status_t actuator_output_status; - mavlink_msg_actuator_output_status_decode(&message, &actuator_output_status); + uint32_t active; + std::array actuators; + + active = mavlink_msg_actuator_output_status_get_active(&message); + mavlink_msg_actuator_output_status_get_actuator(&message, actuators.data()); - set_actuator_output_status(actuator_output_status.active, actuator_output_status.actuator); + set_actuator_output_status(active, actuators); if (_actuator_output_status_subscription) { auto callback = _actuator_output_status_subscription; @@ -1155,18 +1161,19 @@ void TelemetryImpl::set_unix_epoch_time_us(uint64_t time_us) _unix_epoch_time_us = time_us; } -void TelemetryImpl::set_actuator_control_target(uint8_t group, const float* controls) +void TelemetryImpl::set_actuator_control_target(uint8_t group, const std::array& controls) { std::lock_guard lock(_actuator_control_target_mutex); _actuator_control_target.group = group; - std::copy(controls, controls + 8, _actuator_control_target.controls); + std::copy(controls.begin(), controls.end(), _actuator_control_target.controls); } -void TelemetryImpl::set_actuator_output_status(uint32_t active, const float* actuators) +void TelemetryImpl::set_actuator_output_status( + uint32_t active, const std::array& actuators) { std::lock_guard lock(_actuator_output_status_mutex); _actuator_output_status.active = active; - std::copy(actuators, actuators + active, _actuator_output_status.actuator); + std::copy(actuators.begin(), actuators.end(), _actuator_output_status.actuator); } void TelemetryImpl::position_velocity_ned_async( diff --git a/src/plugins/telemetry/telemetry_impl.h b/src/plugins/telemetry/telemetry_impl.h index 1140b23882..daefe4be84 100644 --- a/src/plugins/telemetry/telemetry_impl.h +++ b/src/plugins/telemetry/telemetry_impl.h @@ -133,8 +133,8 @@ class TelemetryImpl : public PluginImplBase { void set_health_level_calibration(bool ok); void set_rc_status(bool available, float signal_strength_percent); void set_unix_epoch_time_us(uint64_t time_us); - void set_actuator_control_target(uint8_t group, const float* controls); - void set_actuator_output_status(uint32_t active, const float* actuators); + void set_actuator_control_target(uint8_t group, const std::array& controls); + void set_actuator_output_status(uint32_t active, const std::array& actuators); void process_position_velocity_ned(const mavlink_message_t& message); void process_global_position_int(const mavlink_message_t& message);