From 875c7e9c4f90d6d06d8b6d4b57351652f0c04d0c Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 31 Jul 2024 14:12:32 +1200 Subject: [PATCH] Gimbal: support for multiple gimbals (almost done) --- examples/gimbal/gimbal.cpp | 72 +- proto | 2 +- src/integration_tests/CMakeLists.txt | 1 - src/integration_tests/gimbal.cpp | 357 -- src/mavsdk/core/mavlink_command_sender.cpp | 41 +- src/mavsdk/core/mavlink_command_sender.h | 7 +- src/mavsdk/plugins/gimbal/gimbal.cpp | 130 +- src/mavsdk/plugins/gimbal/gimbal_impl.cpp | 669 ++- src/mavsdk/plugins/gimbal/gimbal_impl.h | 90 +- .../gimbal/include/plugins/gimbal/gimbal.h | 132 +- .../src/generated/gimbal/gimbal.grpc.pb.cc | 151 +- .../src/generated/gimbal/gimbal.grpc.pb.h | 639 ++- .../src/generated/gimbal/gimbal.pb.cc | 4721 ++++++++++++----- .../src/generated/gimbal/gimbal.pb.h | 4704 ++++++++++++---- .../src/plugins/gimbal/gimbal_service_impl.h | 230 +- 15 files changed, 8965 insertions(+), 2981 deletions(-) delete mode 100644 src/integration_tests/gimbal.cpp diff --git a/examples/gimbal/gimbal.cpp b/examples/gimbal/gimbal.cpp index dc9f68decc..e8bbd753f6 100644 --- a/examples/gimbal/gimbal.cpp +++ b/examples/gimbal/gimbal.cpp @@ -11,6 +11,8 @@ #include #include #include +#include +#include #include using namespace mavsdk; @@ -51,6 +53,26 @@ int main(int argc, char** argv) // Instantiate plugins. auto gimbal = Gimbal{system.value()}; + auto prom = std::promise(); + auto fut = prom.get_future(); + std::once_flag once_flag; + // Wait for a gimbal. + gimbal.subscribe_gimbal_list([&prom, &once_flag](const Gimbal::GimbalList& gimbal_list) { + std::cout << "Found a gimbal: " << gimbal_list.gimbals.back().model_name << " by " + << gimbal_list.gimbals.back().vendor_name << '\n'; + std::call_once(once_flag, [&prom, &gimbal_list]() { + prom.set_value(gimbal_list.gimbals.back().gimbal_id); + }); + }); + + if (fut.wait_for(std::chrono::seconds(3)) == std::future_status::timeout) { + std::cerr << "Could not find a gimbal, exiting..."; + return 1; + } + + const int32_t gimbal_id = fut.get(); + std::cout << "Use gimbal ID: " << gimbal_id << '\n'; + // Set up callback to monitor camera/gimbal angle gimbal.subscribe_attitude([](Gimbal::Attitude attitude) { std::cout << "Gimbal angle pitch: " << attitude.euler_angle_forward.pitch_deg @@ -62,88 +84,80 @@ int main(int argc, char** argv) }); std::cout << "Start controlling gimbal...\n"; - Gimbal::Result gimbal_result = gimbal.take_control(Gimbal::ControlMode::Primary); + Gimbal::Result gimbal_result = gimbal.take_control(gimbal_id, Gimbal::ControlMode::Primary); if (gimbal_result != Gimbal::Result::Success) { std::cerr << "Could not take gimbal control: " << gimbal_result << '\n'; return 1; } - std::cout << "Set yaw mode to lock to a specific direction...\n"; - gimbal_result = gimbal.set_mode(Gimbal::GimbalMode::YawLock); - if (gimbal_result != Gimbal::Result::Success) { - std::cerr << "Could not set to lock mode: " << gimbal_result << '\n'; - return 1; - } + std::cout << "Use yaw mode to lock to a specific direction...\n"; std::cout << "Look North...\n"; - gimbal.set_pitch_and_yaw(0.0f, 0.0f); + gimbal.set_angles(0, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawLock, Gimbal::SendMode::Once); sleep_for(seconds(2)); std::cout << "Look East...\n"; - gimbal.set_pitch_and_yaw(0.0f, 90.0f); + gimbal.set_angles(0, 0.0f, 0.0f, 90.0f, Gimbal::GimbalMode::YawLock, Gimbal::SendMode::Once); sleep_for(seconds(2)); std::cout << "Look South...\n"; - gimbal.set_pitch_and_yaw(0.0f, 180.0f); + gimbal.set_angles(0, 0.0f, 0.0f, 180.0f, Gimbal::GimbalMode::YawLock, Gimbal::SendMode::Once); sleep_for(seconds(2)); std::cout << "Look West...\n"; - gimbal.set_pitch_and_yaw(0.0f, -90.0f); + gimbal.set_angles(0, 0.0f, 0.0f, -90.0f, Gimbal::GimbalMode::YawLock, Gimbal::SendMode::Once); sleep_for(seconds(2)); - std::cout << "Set yaw mode to follow...\n"; - gimbal_result = gimbal.set_mode(Gimbal::GimbalMode::YawFollow); - if (gimbal_result != Gimbal::Result::Success) { - std::cerr << "Could not set to follow mode: " << gimbal_result << '\n'; - return 1; - } + std::cout << "Now use follow mode...\n"; std::cout << "And center first...\n"; - gimbal.set_pitch_and_yaw(0.0f, 0.0f); + gimbal.set_angles(0, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once); sleep_for(seconds(2)); std::cout << "Tilt gimbal down...\n"; - gimbal.set_pitch_and_yaw(-90.0f, 0.0f); + gimbal.set_angles(0, 0.0f, -90.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once); sleep_for(seconds(2)); std::cout << "Tilt gimbal back up...\n"; - gimbal.set_pitch_and_yaw(0.0f, 0.0f); + gimbal.set_angles(0, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once); sleep_for(seconds(2)); std::cout << "Slowly tilt up ...\n"; - gimbal.set_pitch_rate_and_yaw_rate(10.0f, 0.0f); + gimbal.set_angular_rates( + 0, 0.0f, 10.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once); sleep_for(seconds(4)); std::cout << "Back to horizontal...\n"; - gimbal.set_pitch_and_yaw(0.0f, 0.0f); + gimbal.set_angles(0, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once); sleep_for(seconds(2)); std::cout << "Pan to the right...\n"; - gimbal.set_pitch_and_yaw(0.0f, 90.0f); + gimbal.set_angles(0, 0.0f, 0.0f, 90.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once); sleep_for(seconds(2)); std::cout << "Back to the center...\n"; - gimbal.set_pitch_and_yaw(0.0f, 0.0f); + gimbal.set_angles(0, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once); sleep_for(seconds(2)); std::cout << "Pan slowly to the left...\n"; - gimbal.set_pitch_rate_and_yaw_rate(0.0f, -10.0f); + gimbal.set_angular_rates( + 0, 0.0f, 0.0f, -10.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once); sleep_for(seconds(4)); std::cout << "Back to the center...\n"; - gimbal.set_pitch_and_yaw(0.0f, 0.0f); + gimbal.set_angles(0, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once); sleep_for(seconds(2)); std::cout << "Set ROI (region of interested) location...\n"; - gimbal.set_roi_location(47.39743832, 8.5463316, 488.0f); + gimbal.set_roi_location(0, 47.39743832, 8.5463316, 488.0f); sleep_for(seconds(3)); std::cout << "Back to the center...\n"; - gimbal.set_pitch_and_yaw(0.0f, 0.0f); + gimbal.set_angles(0, 0.0f, 0.0f, 0.0f, Gimbal::GimbalMode::YawFollow, Gimbal::SendMode::Once); sleep_for(seconds(2)); std::cout << "Stop controlling gimbal...\n"; - gimbal_result = gimbal.release_control(); + gimbal_result = gimbal.release_control(0); if (gimbal_result != Gimbal::Result::Success) { std::cerr << "Could not take gimbal control: " << gimbal_result << '\n'; return 1; diff --git a/proto b/proto index 36e3e0ab43..2d06b8cfd4 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 36e3e0ab43e3db039a0f721e66b368e6f51f909c +Subproject commit 2d06b8cfd466f3548c1769f92ba3b227ed97d519 diff --git a/src/integration_tests/CMakeLists.txt b/src/integration_tests/CMakeLists.txt index 6ed809ce0f..169afb9835 100644 --- a/src/integration_tests/CMakeLists.txt +++ b/src/integration_tests/CMakeLists.txt @@ -23,7 +23,6 @@ add_executable(integration_tests_runner connection.cpp follow_me.cpp geofence.cpp - gimbal.cpp info.cpp offboard_attitude.cpp #logging.cpp # Not fully implemented diff --git a/src/integration_tests/gimbal.cpp b/src/integration_tests/gimbal.cpp deleted file mode 100644 index 44e60a362a..0000000000 --- a/src/integration_tests/gimbal.cpp +++ /dev/null @@ -1,357 +0,0 @@ -#include -#include -#include -#include -#include - -#include "mavsdk.h" -#include "mavsdk_math.h" -#include "unused.h" -#include "integration_test_helper.h" -#include "plugins/action/action.h" -#include "plugins/gimbal/gimbal.h" -#include "plugins/offboard/offboard.h" -#include "plugins/telemetry/telemetry.h" - -using namespace mavsdk; - -void gimbal_pattern(std::shared_ptr gimbal); -void send_gimbal_roi_location( - std::shared_ptr gimbal, double latitude_deg, double longitude_deg, float altitude_m); -void receive_gimbal_result(Gimbal::Result result); -void receive_gimbal_attitude(Gimbal::Attitude attitude); - -TEST(SitlTestGimbal, GimbalMove) -{ - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; - - ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); - ASSERT_EQ(ret, ConnectionResult::Success); - - // Wait for system to connect via heartbeat. - std::this_thread::sleep_for(std::chrono::seconds(2)); - ASSERT_EQ(mavsdk.systems().size(), 1); - auto system = mavsdk.systems().at(0); - - // FIXME: This is what it should be, for now though with the typhoon_h480 - // SITL simulation, the gimbal is hooked up to the autopilot. - // ASSERT_TRUE(system.has_gimbal()); - ASSERT_TRUE(system->has_autopilot()); - - auto gimbal = std::make_shared(system); - - gimbal->subscribe_attitude(&receive_gimbal_attitude); - - EXPECT_EQ(gimbal->take_control(Gimbal::ControlMode::Primary), Gimbal::Result::Success); - - EXPECT_EQ(gimbal->set_mode(Gimbal::GimbalMode::YawFollow), Gimbal::Result::Success); - - LogInfo() << "Pitch down for a bit"; - EXPECT_EQ(gimbal->set_pitch_rate_and_yaw_rate(-10.0f, 0.0f), Gimbal::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(2)); - - LogInfo() << "Pitch up for a bit"; - EXPECT_EQ(gimbal->set_pitch_rate_and_yaw_rate(10.0f, 0.0f), Gimbal::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(2)); - - LogInfo() << "Yaw right for a bit"; - EXPECT_EQ(gimbal->set_pitch_rate_and_yaw_rate(0.0f, 10.0f), Gimbal::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(2)); - - LogInfo() << "Yaw left for a bit"; - EXPECT_EQ(gimbal->set_pitch_rate_and_yaw_rate(0.0f, -10.0f), Gimbal::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(2)); - - LogInfo() << "Reset back to 0,0"; - EXPECT_EQ(gimbal->set_pitch_and_yaw(0.0f, 0.0f), Gimbal::Result::Success); - - std::this_thread::sleep_for(std::chrono::seconds(1)); - - EXPECT_EQ(gimbal->take_control(Gimbal::ControlMode::None), Gimbal::Result::Success); -} - -TEST(SitlTestGimbal, GimbalAngles) -{ - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; - - ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); - ASSERT_EQ(ret, ConnectionResult::Success); - - // Wait for system to connect via heartbeat. - std::this_thread::sleep_for(std::chrono::seconds(2)); - ASSERT_EQ(mavsdk.systems().size(), 1); - auto system = mavsdk.systems().at(0); - - // FIXME: This is what it should be, for now though with the typhoon_h480 - // SITL simulation, the gimbal is hooked up to the autopilot. - // ASSERT_TRUE(system.has_gimbal()); - ASSERT_TRUE(system->has_autopilot()); - - auto gimbal = std::make_shared(system); - - EXPECT_EQ(gimbal->take_control(Gimbal::ControlMode::Primary), Gimbal::Result::Success); - - EXPECT_EQ(gimbal->set_mode(Gimbal::GimbalMode::YawFollow), Gimbal::Result::Success); - - LogInfo() << "Pitch 45 degrees down"; - EXPECT_EQ(gimbal->set_pitch_and_yaw(-45.0f, 0.0f), Gimbal::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(1)); - LogInfo() << "Pitch back up"; - EXPECT_EQ(gimbal->set_pitch_and_yaw(0.0f, 0.0f), Gimbal::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(1)); - LogInfo() << "Pitch 45 degrees up"; - EXPECT_EQ(gimbal->set_pitch_and_yaw(45.0f, 0.0f), Gimbal::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(1)); - LogInfo() << "Pitch back down"; - EXPECT_EQ(gimbal->set_pitch_and_yaw(0.0f, 0.0f), Gimbal::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(1)); - - LogInfo() << "Yaw 45 degrees to the right"; - EXPECT_EQ(gimbal->set_pitch_and_yaw(0.0f, 45.0f), Gimbal::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(1)); - LogInfo() << "Yaw forward"; - EXPECT_EQ(gimbal->set_pitch_and_yaw(0.0f, 0.0f), Gimbal::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(1)); - LogInfo() << "Yaw 45 degrees to the left"; - EXPECT_EQ(gimbal->set_pitch_and_yaw(0.0f, -45.0f), Gimbal::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(1)); - LogInfo() << "Yaw forward"; - EXPECT_EQ(gimbal->set_pitch_and_yaw(0.0f, 0.0f), Gimbal::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(1)); - - EXPECT_EQ(gimbal->take_control(Gimbal::ControlMode::None), Gimbal::Result::Success); -} - -TEST(SitlTestGimbal, GimbalTakeoffAndMove) -{ - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; - - ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); - ASSERT_EQ(ret, ConnectionResult::Success); - - // Wait for system to connect via heartbeat. - std::this_thread::sleep_for(std::chrono::seconds(2)); - ASSERT_EQ(mavsdk.systems().size(), 1); - auto system = mavsdk.systems().at(0); - // ASSERT_TRUE(system.has_gimbal()); - ASSERT_TRUE(system->has_autopilot()); - - auto telemetry = std::make_shared(system); - auto gimbal = std::make_shared(system); - auto action = std::make_shared(system); - auto offboard = std::make_shared(system); - - LogInfo() << "Waiting for system to be ready"; - ASSERT_TRUE(poll_condition_with_timeout( - [telemetry]() { - LogInfo() << "Waiting for system to be ready"; - return telemetry->health_all_ok(); - }, - std::chrono::seconds(10))); - - Action::Result action_result = action->arm(); - EXPECT_EQ(action_result, Action::Result::Success); - - action_result = action->takeoff(); - EXPECT_EQ(action_result, Action::Result::Success); - - gimbal->subscribe_attitude(&receive_gimbal_attitude); - - std::this_thread::sleep_for(std::chrono::seconds(3)); - - // Slowly fly circle. - Offboard::VelocityBodyYawspeed circle; - circle.forward_m_s = 0.5f; - circle.right_m_s = 0.0f; - circle.down_m_s = 0.0f; - circle.yawspeed_deg_s = 10.0f; - - EXPECT_EQ(offboard->set_velocity_body(circle), Offboard::Result::Success); - EXPECT_EQ(offboard->start(), Offboard::Result::Success); - - std::this_thread::sleep_for(std::chrono::seconds(1)); - - EXPECT_EQ(gimbal->take_control(Gimbal::ControlMode::Primary), Gimbal::Result::Success); - - // First use gimbal in yaw follow mode. - EXPECT_EQ(gimbal->set_mode(Gimbal::GimbalMode::YawFollow), Gimbal::Result::Success); - - gimbal_pattern(gimbal); - std::this_thread::sleep_for(std::chrono::seconds(1)); - - // Now set to lock mode - EXPECT_EQ(gimbal->set_mode(Gimbal::GimbalMode::YawLock), Gimbal::Result::Success); - - gimbal_pattern(gimbal); - std::this_thread::sleep_for(std::chrono::seconds(1)); - - EXPECT_EQ(gimbal->take_control(Gimbal::ControlMode::None), Gimbal::Result::Success); - - action->land(); - std::this_thread::sleep_for(std::chrono::seconds(3)); -} - -void gimbal_pattern(std::shared_ptr gimbal) -{ - // Look forward - gimbal->set_pitch_and_yaw_async(0.0f, 0.0f, &receive_gimbal_result); - std::this_thread::sleep_for(std::chrono::seconds(1)); - - // Look right - for (int i = 0; i < 60; ++i) { - gimbal->set_pitch_and_yaw_async(0.0f, static_cast(i), &receive_gimbal_result); - std::this_thread::sleep_for(std::chrono::milliseconds(50)); - } - std::this_thread::sleep_for(std::chrono::seconds(1)); - - // Look left - for (int i = 60; i >= -60; --i) { - gimbal->set_pitch_and_yaw_async(0.0f, static_cast(i), &receive_gimbal_result); - std::this_thread::sleep_for(std::chrono::milliseconds(50)); - } - std::this_thread::sleep_for(std::chrono::seconds(1)); - - // Look up - for (int i = -60; i <= 0; ++i) { - gimbal->set_pitch_and_yaw_async(0.0f, static_cast(i), &receive_gimbal_result); - std::this_thread::sleep_for(std::chrono::milliseconds(50)); - } - std::this_thread::sleep_for(std::chrono::seconds(1)); - - // Tilt down - for (int i = 0; i > -60; --i) { - gimbal->set_pitch_and_yaw_async(static_cast(i), 0.0f, &receive_gimbal_result); - std::this_thread::sleep_for(std::chrono::milliseconds(50)); - } - std::this_thread::sleep_for(std::chrono::seconds(1)); - - // And back up - for (int i = -60; i <= 0; ++i) { - gimbal->set_pitch_and_yaw_async(static_cast(i), 0.0f, &receive_gimbal_result); - std::this_thread::sleep_for(std::chrono::milliseconds(50)); - } - - // Look forward - gimbal->set_pitch_and_yaw_async(0.0f, 0.0f, &receive_gimbal_result); - std::this_thread::sleep_for(std::chrono::seconds(1)); -} - -TEST(SitlTestGimbal, GimbalROIOffboard) -{ - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; - - ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); - ASSERT_EQ(ret, ConnectionResult::Success); - - // Wait for system to connect via heartbeat. - std::this_thread::sleep_for(std::chrono::seconds(2)); - ASSERT_EQ(mavsdk.systems().size(), 1); - auto system = mavsdk.systems().at(0); - // ASSERT_TRUE(system.has_gimbal()); - ASSERT_TRUE(system->has_autopilot()); - - auto telemetry = std::make_shared(system); - auto gimbal = std::make_shared(system); - auto action = std::make_shared(system); - auto offboard = std::make_shared(system); - - LogInfo() << "Waiting for system to be ready"; - ASSERT_TRUE(poll_condition_with_timeout( - [telemetry]() { - LogInfo() << "Waiting for system to be ready"; - return telemetry->health_all_ok(); - }, - std::chrono::seconds(10))); - - const Telemetry::Position& position = telemetry->position(); - - // set the ROI location: a bit to the north of the vehicle's location - const double latitude_offset_deg = 3. / 111111.; // this is about 3 m - send_gimbal_roi_location( - gimbal, - position.latitude_deg + latitude_offset_deg, - position.longitude_deg, - position.absolute_altitude_m + 1.f); - - Action::Result action_result = action->arm(); - EXPECT_EQ(action_result, Action::Result::Success); - - action_result = action->takeoff(); - EXPECT_EQ(action_result, Action::Result::Success); - - std::this_thread::sleep_for(std::chrono::seconds(5)); - - gimbal->subscribe_attitude(&receive_gimbal_attitude); - - // Send it once before starting offboard, otherwise it will be rejected. - Offboard::VelocityNedYaw still; - still.north_m_s = 0.0f; - still.east_m_s = 0.0f; - still.down_m_s = 0.0f; - still.yaw_deg = 0.0f; - offboard->set_velocity_ned(still); - Offboard::Result offboard_result = offboard->start(); - EXPECT_EQ(offboard_result, Offboard::Result::Success); - - auto fly_straight = [&offboard](int step_count, float max_speed) { - for (int i = 0; i < step_count; ++i) { - int k = (i <= step_count / 2) ? i : step_count - i; - float vy = static_cast(k) / (step_count / 2) * max_speed; - - Offboard::VelocityNedYaw move_east; - move_east.north_m_s = 0.0f; - move_east.east_m_s = vy; - move_east.down_m_s = 0.0f; - move_east.yaw_deg = 90.0f; - offboard->set_velocity_ned(move_east); - std::this_thread::sleep_for(std::chrono::milliseconds(10)); - } - }; - - // fly east for a bit - fly_straight(300, 2.f); - - // fly in north-south direction (back & forth a few times) - const float step_size = 0.01f; - const float one_cycle = 2.0f * static_cast(PI); - const unsigned steps = static_cast(2.5f * one_cycle / step_size); - - for (unsigned i = 0; i < steps; ++i) { - float vx = 5.0f * sinf(i * step_size); - - Offboard::VelocityNedYaw move_north; - move_north.north_m_s = vx; - move_north.east_m_s = 0.0f; - move_north.down_m_s = 0.0f; - move_north.yaw_deg = 90.0f; - offboard->set_velocity_ned(move_north); - std::this_thread::sleep_for(std::chrono::milliseconds(10)); - } - - // fly west for a bit - fly_straight(600, -4.f); - - action->land(); - std::this_thread::sleep_for(std::chrono::seconds(3)); -} - -void send_gimbal_roi_location( - std::shared_ptr gimbal, double latitude_deg, double longitude_deg, float altitude_m) -{ - gimbal->set_roi_location_async(latitude_deg, longitude_deg, altitude_m, &receive_gimbal_result); -} - -void receive_gimbal_result(Gimbal::Result result) -{ - EXPECT_EQ(result, Gimbal::Result::Success); -} - -void receive_gimbal_attitude(Gimbal::Attitude attitude) -{ - std::cout << "Gimbal angle pitch: " << attitude.euler_angle_forward.pitch_deg - << " deg, yaw: " << attitude.euler_angle_forward.yaw_deg - << " yaw (relative to forward)\n"; - std::cout << "Gimbal angle pitch: " << attitude.euler_angle_north.pitch_deg - << " deg, yaw: " << attitude.euler_angle_north.yaw_deg - << " yaw (relative to North)\n"; -} diff --git a/src/mavsdk/core/mavlink_command_sender.cpp b/src/mavsdk/core/mavlink_command_sender.cpp index f65b8a9fc0..672a62a655 100644 --- a/src/mavsdk/core/mavlink_command_sender.cpp +++ b/src/mavsdk/core/mavlink_command_sender.cpp @@ -81,8 +81,9 @@ void MavlinkCommandSender::queue_command_async( const CommandInt& command, const CommandResultCallback& callback) { if (_command_debugging) { - LogDebug() << "COMMAND_INT " << (int)(command.command) << " to send to " - << (int)(command.target_system_id) << ", " << (int)(command.target_component_id); + LogDebug() << "COMMAND_INT " << static_cast(command.command) << " to send to " + << static_cast(command.target_system_id) << ", " + << static_cast(command.target_component_id); } CommandIdentification identification = identification_from_command(command); @@ -109,8 +110,9 @@ void MavlinkCommandSender::queue_command_async( const CommandLong& command, const CommandResultCallback& callback) { if (_command_debugging) { - LogDebug() << "COMMAND_LONG " << (int)(command.command) << " to send to " - << (int)(command.target_system_id) << ", " << (int)(command.target_component_id); + LogDebug() << "COMMAND_LONG " << static_cast(command.command) << " to send to " + << static_cast(command.target_system_id) << ", " + << static_cast(command.target_component_id); } CommandIdentification identification = identification_from_command(command); @@ -134,7 +136,7 @@ void MavlinkCommandSender::queue_command_async( _work_queue.push_back(new_work); } -void MavlinkCommandSender::receive_command_ack(mavlink_message_t message) +void MavlinkCommandSender::receive_command_ack(const mavlink_message_t& message) { mavlink_command_ack_t command_ack; mavlink_msg_command_ack_decode(&message, &command_ack); @@ -156,7 +158,7 @@ void MavlinkCommandSender::receive_command_ack(mavlink_message_t message) LockedQueue::Guard work_queue_guard(_work_queue); for (auto it = _work_queue.begin(); it != _work_queue.end(); ++it) { - auto work = *it; + const auto& work = *it; if (!work) { LogErr() << "No work available! (should not happen #1)"; @@ -302,7 +304,7 @@ void MavlinkCommandSender::receive_timeout(const CommandIdentification& identifi LockedQueue::Guard work_queue_guard(_work_queue); for (auto it = _work_queue.begin(); it != _work_queue.end(); ++it) { - auto work = *it; + const auto& work = *it; if (!work) { LogErr() << "No work available! (should not happen #2)"; @@ -343,7 +345,26 @@ void MavlinkCommandSender::receive_timeout(const CommandIdentification& identifi } } else { // We have tried retransmitting, giving up now. - LogErr() << "Retrying failed (" << work->identification.command << ")"; + if (work->identification.command == 512) { + uint8_t target_sysid; + uint8_t target_compid; + if (auto command_int = std::get_if(&work->command)) { + target_sysid = command_int->target_system_id; + target_compid = command_int->target_component_id; + } else if (auto command_long = std::get_if(&work->command)) { + target_sysid = command_long->target_system_id; + target_compid = command_long->target_component_id; + } else { + LogErr() << "No command, that's awkward"; + continue; + } + LogErr() << "Retrying failed for REQUEST_MESSAGE command for message: " + << work->identification.maybe_param1 << ", to (" + << std::to_string(target_sysid) << "/" << std::to_string(target_compid) + << ")"; + } else { + LogErr() << "Retrying failed for command: " << work->identification.command << ")"; + } temp_callback = work->callback; temp_result = {Result::Timeout, NAN}; @@ -418,7 +439,7 @@ void MavlinkCommandSender::do_work() } void MavlinkCommandSender::call_callback( - const CommandResultCallback& callback, Result result, float progress) + const CommandResultCallback& callback, Result result, float progress) const { if (!callback) { return; @@ -431,7 +452,7 @@ void MavlinkCommandSender::call_callback( [temp_callback, result, progress]() { temp_callback(result, progress); }); } -bool MavlinkCommandSender::send_mavlink_message(const Command& command) +bool MavlinkCommandSender::send_mavlink_message(const Command& command) const { if (auto command_int = std::get_if(&command)) { return _system_impl.queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { diff --git a/src/mavsdk/core/mavlink_command_sender.h b/src/mavsdk/core/mavlink_command_sender.h index c8d02774b8..143c39975e 100644 --- a/src/mavsdk/core/mavlink_command_sender.h +++ b/src/mavsdk/core/mavlink_command_sender.h @@ -10,7 +10,6 @@ #include #include #include -#include #include namespace mavsdk { @@ -147,12 +146,12 @@ class MavlinkCommandSender { return identification; } - void receive_command_ack(mavlink_message_t message); + void receive_command_ack(const mavlink_message_t& message); void receive_timeout(const CommandIdentification& identification); - void call_callback(const CommandResultCallback& callback, Result result, float progress); + void call_callback(const CommandResultCallback& callback, Result result, float progress) const; - bool send_mavlink_message(const Command& command); + bool send_mavlink_message(const Command& command) const; float maybe_reserved(const std::optional& maybe_param) const; diff --git a/src/mavsdk/plugins/gimbal/gimbal.cpp b/src/mavsdk/plugins/gimbal/gimbal.cpp index 628e01094f..ad2bc3ee7c 100644 --- a/src/mavsdk/plugins/gimbal/gimbal.cpp +++ b/src/mavsdk/plugins/gimbal/gimbal.cpp @@ -13,6 +13,8 @@ using Quaternion = Gimbal::Quaternion; using EulerAngle = Gimbal::EulerAngle; using AngularVelocityBody = Gimbal::AngularVelocityBody; using Attitude = Gimbal::Attitude; +using GimbalItem = Gimbal::GimbalItem; +using GimbalList = Gimbal::GimbalList; using ControlStatus = Gimbal::ControlStatus; Gimbal::Gimbal(System& system) : PluginBase(), _impl{std::make_unique(system)} {} @@ -25,6 +27,7 @@ Gimbal::Gimbal(std::shared_ptr system) : Gimbal::~Gimbal() {} void Gimbal::set_angles_async( + int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, @@ -32,20 +35,23 @@ void Gimbal::set_angles_async( SendMode send_mode, const ResultCallback callback) { - _impl->set_angles_async(roll_deg, pitch_deg, yaw_deg, gimbal_mode, send_mode, callback); + _impl->set_angles_async( + gimbal_id, roll_deg, pitch_deg, yaw_deg, gimbal_mode, send_mode, callback); } Gimbal::Result Gimbal::set_angles( + int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, GimbalMode gimbal_mode, SendMode send_mode) const { - return _impl->set_angles(roll_deg, pitch_deg, yaw_deg, gimbal_mode, send_mode); + return _impl->set_angles(gimbal_id, roll_deg, pitch_deg, yaw_deg, gimbal_mode, send_mode); } void Gimbal::set_angular_rates_async( + int32_t gimbal_id, float roll_rate_deg_s, float pitch_rate_deg_s, float yaw_rate_deg_s, @@ -54,10 +60,17 @@ void Gimbal::set_angular_rates_async( const ResultCallback callback) { _impl->set_angular_rates_async( - roll_rate_deg_s, pitch_rate_deg_s, yaw_rate_deg_s, gimbal_mode, send_mode, callback); + gimbal_id, + roll_rate_deg_s, + pitch_rate_deg_s, + yaw_rate_deg_s, + gimbal_mode, + send_mode, + callback); } Gimbal::Result Gimbal::set_angular_rates( + int32_t gimbal_id, float roll_rate_deg_s, float pitch_rate_deg_s, float yaw_rate_deg_s, @@ -65,54 +78,74 @@ Gimbal::Result Gimbal::set_angular_rates( SendMode send_mode) const { return _impl->set_angular_rates( - roll_rate_deg_s, pitch_rate_deg_s, yaw_rate_deg_s, gimbal_mode, send_mode); + gimbal_id, roll_rate_deg_s, pitch_rate_deg_s, yaw_rate_deg_s, gimbal_mode, send_mode); } void Gimbal::set_roi_location_async( - double latitude_deg, double longitude_deg, float altitude_m, const ResultCallback callback) + int32_t gimbal_id, + double latitude_deg, + double longitude_deg, + float altitude_m, + const ResultCallback callback) +{ + _impl->set_roi_location_async(gimbal_id, latitude_deg, longitude_deg, altitude_m, callback); +} + +Gimbal::Result Gimbal::set_roi_location( + int32_t gimbal_id, double latitude_deg, double longitude_deg, float altitude_m) const { - _impl->set_roi_location_async(latitude_deg, longitude_deg, altitude_m, callback); + return _impl->set_roi_location(gimbal_id, latitude_deg, longitude_deg, altitude_m); } -Gimbal::Result -Gimbal::set_roi_location(double latitude_deg, double longitude_deg, float altitude_m) const +void Gimbal::take_control_async( + int32_t gimbal_id, ControlMode control_mode, const ResultCallback callback) { - return _impl->set_roi_location(latitude_deg, longitude_deg, altitude_m); + _impl->take_control_async(gimbal_id, control_mode, callback); } -void Gimbal::take_control_async(ControlMode control_mode, const ResultCallback callback) +Gimbal::Result Gimbal::take_control(int32_t gimbal_id, ControlMode control_mode) const { - _impl->take_control_async(control_mode, callback); + return _impl->take_control(gimbal_id, control_mode); } -Gimbal::Result Gimbal::take_control(ControlMode control_mode) const +void Gimbal::release_control_async(int32_t gimbal_id, const ResultCallback callback) { - return _impl->take_control(control_mode); + _impl->release_control_async(gimbal_id, callback); } -void Gimbal::release_control_async(const ResultCallback callback) +Gimbal::Result Gimbal::release_control(int32_t gimbal_id) const { - _impl->release_control_async(callback); + return _impl->release_control(gimbal_id); } -Gimbal::Result Gimbal::release_control() const +Gimbal::GimbalListHandle Gimbal::subscribe_gimbal_list(const GimbalListCallback& callback) { - return _impl->release_control(); + return _impl->subscribe_gimbal_list(callback); } -Gimbal::ControlHandle Gimbal::subscribe_control(const ControlCallback& callback) +void Gimbal::unsubscribe_gimbal_list(GimbalListHandle handle) { - return _impl->subscribe_control(callback); + _impl->unsubscribe_gimbal_list(handle); } -void Gimbal::unsubscribe_control(ControlHandle handle) +Gimbal::GimbalList Gimbal::gimbal_list() const { - _impl->unsubscribe_control(handle); + return _impl->gimbal_list(); } -Gimbal::ControlStatus Gimbal::control() const +Gimbal::ControlStatusHandle Gimbal::subscribe_control_status(const ControlStatusCallback& callback) { - return _impl->control(); + return _impl->subscribe_control_status(callback); +} + +void Gimbal::unsubscribe_control_status(ControlStatusHandle handle) +{ + _impl->unsubscribe_control_status(handle); +} + +std::pair Gimbal::get_control_status(int32_t gimbal_id) const +{ + return _impl->get_control_status(gimbal_id); } Gimbal::AttitudeHandle Gimbal::subscribe_attitude(const AttitudeCallback& callback) @@ -125,9 +158,9 @@ void Gimbal::unsubscribe_attitude(AttitudeHandle handle) _impl->unsubscribe_attitude(handle); } -Gimbal::Attitude Gimbal::attitude() const +std::pair Gimbal::get_attitude(int32_t gimbal_id) const { - return _impl->attitude(); + return _impl->get_attitude(gimbal_id); } bool operator==(const Gimbal::Quaternion& lhs, const Gimbal::Quaternion& rhs) @@ -194,7 +227,8 @@ operator<<(std::ostream& str, Gimbal::AngularVelocityBody const& angular_velocit bool operator==(const Gimbal::Attitude& lhs, const Gimbal::Attitude& rhs) { - return (rhs.euler_angle_forward == lhs.euler_angle_forward) && + return (rhs.gimbal_id == lhs.gimbal_id) && + (rhs.euler_angle_forward == lhs.euler_angle_forward) && (rhs.quaternion_forward == lhs.quaternion_forward) && (rhs.euler_angle_north == lhs.euler_angle_north) && (rhs.quaternion_north == lhs.quaternion_north) && @@ -205,6 +239,7 @@ std::ostream& operator<<(std::ostream& str, Gimbal::Attitude const& attitude) { str << std::setprecision(15); str << "attitude:" << '\n' << "{\n"; + str << " gimbal_id: " << attitude.gimbal_id << '\n'; str << " euler_angle_forward: " << attitude.euler_angle_forward << '\n'; str << " quaternion_forward: " << attitude.quaternion_forward << '\n'; str << " euler_angle_north: " << attitude.euler_angle_north << '\n'; @@ -215,9 +250,49 @@ std::ostream& operator<<(std::ostream& str, Gimbal::Attitude const& attitude) return str; } +bool operator==(const Gimbal::GimbalItem& lhs, const Gimbal::GimbalItem& rhs) +{ + return (rhs.gimbal_id == lhs.gimbal_id) && (rhs.vendor_name == lhs.vendor_name) && + (rhs.model_name == lhs.model_name) && (rhs.custom_name == lhs.custom_name) && + (rhs.gimbal_manager_component_id == lhs.gimbal_manager_component_id) && + (rhs.gimbal_device_id == lhs.gimbal_device_id); +} + +std::ostream& operator<<(std::ostream& str, Gimbal::GimbalItem const& gimbal_item) +{ + str << std::setprecision(15); + str << "gimbal_item:" << '\n' << "{\n"; + str << " gimbal_id: " << gimbal_item.gimbal_id << '\n'; + str << " vendor_name: " << gimbal_item.vendor_name << '\n'; + str << " model_name: " << gimbal_item.model_name << '\n'; + str << " custom_name: " << gimbal_item.custom_name << '\n'; + str << " gimbal_manager_component_id: " << gimbal_item.gimbal_manager_component_id << '\n'; + str << " gimbal_device_id: " << gimbal_item.gimbal_device_id << '\n'; + str << '}'; + return str; +} + +bool operator==(const Gimbal::GimbalList& lhs, const Gimbal::GimbalList& rhs) +{ + return (rhs.gimbals == lhs.gimbals); +} + +std::ostream& operator<<(std::ostream& str, Gimbal::GimbalList const& gimbal_list) +{ + str << std::setprecision(15); + str << "gimbal_list:" << '\n' << "{\n"; + str << " gimbals: ["; + for (auto it = gimbal_list.gimbals.begin(); it != gimbal_list.gimbals.end(); ++it) { + str << *it; + str << (it + 1 != gimbal_list.gimbals.end() ? ", " : "]\n"); + } + str << '}'; + return str; +} + bool operator==(const Gimbal::ControlStatus& lhs, const Gimbal::ControlStatus& rhs) { - return (rhs.control_mode == lhs.control_mode) && + return (rhs.gimbal_id == lhs.gimbal_id) && (rhs.control_mode == lhs.control_mode) && (rhs.sysid_primary_control == lhs.sysid_primary_control) && (rhs.compid_primary_control == lhs.compid_primary_control) && (rhs.sysid_secondary_control == lhs.sysid_secondary_control) && @@ -228,6 +303,7 @@ std::ostream& operator<<(std::ostream& str, Gimbal::ControlStatus const& control { str << std::setprecision(15); str << "control_status:" << '\n' << "{\n"; + str << " gimbal_id: " << control_status.gimbal_id << '\n'; str << " control_mode: " << control_status.control_mode << '\n'; str << " sysid_primary_control: " << control_status.sysid_primary_control << '\n'; str << " compid_primary_control: " << control_status.compid_primary_control << '\n'; diff --git a/src/mavsdk/plugins/gimbal/gimbal_impl.cpp b/src/mavsdk/plugins/gimbal/gimbal_impl.cpp index 8e4eea6437..cd776a05d9 100644 --- a/src/mavsdk/plugins/gimbal/gimbal_impl.cpp +++ b/src/mavsdk/plugins/gimbal/gimbal_impl.cpp @@ -2,10 +2,11 @@ #include "callback_list.tpp" #include "mavsdk_math.h" #include "math_conversions.h" +#include +#include #include #include #include -#include namespace mavsdk { @@ -28,6 +29,18 @@ GimbalImpl::~GimbalImpl() void GimbalImpl::init() { + if (const char* env_p = std::getenv("MAVSDK_GIMBAL_DEBUGGING")) { + if (std::string(env_p) == "1") { + LogDebug() << "Gimbal debugging is on."; + _debugging = true; + } + } + + _system_impl->register_mavlink_message_handler( + MAVLINK_MSG_ID_HEARTBEAT, + [this](const mavlink_message_t& message) { process_heartbeat(message); }, + this); + _system_impl->register_mavlink_message_handler( MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION, [this](const mavlink_message_t& message) { process_gimbal_manager_information(message); }, @@ -38,6 +51,11 @@ void GimbalImpl::init() [this](const mavlink_message_t& message) { process_gimbal_manager_status(message); }, this); + _system_impl->register_mavlink_message_handler( + MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, + [this](const mavlink_message_t& message) { process_gimbal_device_information(message); }, + this); + _system_impl->register_mavlink_message_handler( MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, [this](const mavlink_message_t& message) { @@ -56,28 +74,110 @@ void GimbalImpl::deinit() _system_impl->unregister_all_mavlink_message_handlers(this); } -void GimbalImpl::enable() -{ - request_gimbal_information(); -} +void GimbalImpl::enable() {} void GimbalImpl::disable() {} -void GimbalImpl::request_gimbal_information() +void GimbalImpl::request_gimbal_manager_information(uint8_t target_component_id) const { + if (_debugging) { + LogDebug() << "Requesting GIMBAL_MANAGER_INFORMATION from: " + << std::to_string(_system_impl->get_system_id()) << "/" + << std::to_string(target_component_id); + } + MavlinkCommandSender::CommandLong command{}; command.command = MAV_CMD_REQUEST_MESSAGE; command.params.maybe_param1 = {static_cast(MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION)}; - command.target_component_id = 0; // any component + command.target_system_id = _system_impl->get_system_id(); + command.target_component_id = target_component_id; _system_impl->send_command_async(command, nullptr); } +void GimbalImpl::request_gimbal_device_information(uint8_t target_component_id) const +{ + if (_debugging) { + LogDebug() << "Requesting GIMBAL_DEVICE_INFORMATION from: " + << std::to_string(_system_impl->get_system_id()) << "/" + << std::to_string(target_component_id); + } + + MavlinkCommandSender::CommandLong command{}; + command.command = MAV_CMD_REQUEST_MESSAGE; + command.params.maybe_param1 = {static_cast(MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION)}; + command.target_system_id = _system_impl->get_system_id(); + command.target_component_id = target_component_id; + _system_impl->send_command_async(command, nullptr); +} + +void GimbalImpl::process_heartbeat(const mavlink_message_t& message) +{ + std::lock_guard lock(_mutex); + + auto maybe_gimbal = std::find_if(_gimbals.begin(), _gimbals.end(), [&](const GimbalItem& item) { + return item.gimbal_manager_compid == message.compid; + }); + + // Every component can potentially be a gimbal manager. Therefore, on any + // heartbeat arriving, we create an entry in the potential gimbal manager + // list and subsequently try to figure out whether it sends gimbal manager + // messages. + auto* gimbal = [&]() { + if (maybe_gimbal != _gimbals.end()) { + // Going from iterator to pointer is not exactly pretty. + return &(*maybe_gimbal); + } else { + GimbalItem new_item{}; + new_item.gimbal_manager_compid = message.compid; + _gimbals.emplace_back(std::move(new_item)); + + return &_gimbals.back(); + } + }(); + + check_is_gimbal_valid(gimbal); +} + void GimbalImpl::process_gimbal_manager_information(const mavlink_message_t& message) { mavlink_gimbal_manager_information_t gimbal_manager_information; mavlink_msg_gimbal_manager_information_decode(&message, &gimbal_manager_information); - // TODO: implement + if (_debugging) { + LogDebug() << "Got GIMBAL_MANAGER_INFORMATION from: " << std::to_string(message.sysid) + << "/" << std::to_string(message.compid) << " with gimbal_device_id: " + << std::to_string(gimbal_manager_information.gimbal_device_id); + } + + std::lock_guard lock(_mutex); + + auto maybe_gimbal = std::find_if(_gimbals.begin(), _gimbals.end(), [&](const GimbalItem& item) { + return item.gimbal_manager_compid == message.compid; + }); + + auto* gimbal = [&]() { + if (maybe_gimbal != _gimbals.end()) { + // Going from iterator to pointer is not exactly pretty. + return &(*maybe_gimbal); + } else { + GimbalItem new_item{}; + new_item.gimbal_manager_compid = message.compid; + new_item.gimbal_device_id = gimbal_manager_information.gimbal_device_id; + _gimbals.emplace_back(new_item); + return &_gimbals.back(); + } + }(); + + if (gimbal->gimbal_manager_information_received && + gimbal->gimbal_device_id != gimbal_manager_information.gimbal_device_id) { + LogWarn() << "gimbal_manager_information.gimbal_device_id changed from " + << gimbal->gimbal_device_id << " to " + << gimbal_manager_information.gimbal_device_id; + } + gimbal->gimbal_device_id = gimbal_manager_information.gimbal_device_id; + gimbal->gimbal_manager_information_received = true; + + check_is_gimbal_valid(gimbal); } void GimbalImpl::process_gimbal_manager_status(const mavlink_message_t& message) @@ -87,24 +187,76 @@ void GimbalImpl::process_gimbal_manager_status(const mavlink_message_t& message) std::lock_guard lock(_mutex); + auto maybe_gimbal = std::find_if(_gimbals.begin(), _gimbals.end(), [&](const GimbalItem& item) { + return item.gimbal_manager_compid == message.compid && + item.gimbal_device_id == status.gimbal_device_id; + }); + + if (maybe_gimbal == _gimbals.end()) { + // No potential entry exists yet, we just give up for now. + return; + } + + auto& gimbal = *maybe_gimbal; + + // We need to populate the MAVSDK gimbal ID, so the user knows which is which. + gimbal.control_status.gimbal_id = + static_cast(std::distance(_gimbals.begin(), maybe_gimbal)); + if (status.primary_control_sysid == static_cast(_system_impl->get_own_system_id()) && status.primary_control_compid == static_cast(_system_impl->get_own_component_id())) { - _control_status.control_mode = Gimbal::ControlMode::Primary; + gimbal.control_status.control_mode = Gimbal::ControlMode::Primary; } else if ( status.secondary_control_sysid == static_cast(_system_impl->get_own_system_id()) && status.secondary_control_compid == static_cast(_system_impl->get_own_component_id())) { - _control_status.control_mode = Gimbal::ControlMode::Secondary; + gimbal.control_status.control_mode = Gimbal::ControlMode::Secondary; } else { - _control_status.control_mode = Gimbal::ControlMode::None; + gimbal.control_status.control_mode = Gimbal::ControlMode::None; + } + + gimbal.control_status.sysid_primary_control = status.primary_control_sysid; + gimbal.control_status.compid_primary_control = status.primary_control_compid; + gimbal.control_status.sysid_secondary_control = status.secondary_control_sysid; + gimbal.control_status.compid_secondary_control = status.secondary_control_compid; + + _control_status_subscriptions.queue(gimbal.control_status, [this](const auto& func) { + _system_impl->call_user_callback(func); + }); +} + +void GimbalImpl::process_gimbal_device_information(const mavlink_message_t& message) +{ + mavlink_gimbal_device_information_t gimbal_device_information; + mavlink_msg_gimbal_device_information_decode(&message, &gimbal_device_information); + + if (_debugging) { + LogDebug() << "Got GIMBAL_DEVICE_INFORMATION from: " << std::to_string(message.sysid) << "/" + << std::to_string(message.compid) << " with gimbal_device_id: " + << std::to_string(gimbal_device_information.gimbal_device_id); + } + + auto maybe_gimbal = std::find_if(_gimbals.begin(), _gimbals.end(), [&](const GimbalItem& item) { + if (gimbal_device_information.gimbal_device_id == 0) { + return item.gimbal_device_id == message.compid; + } else { + return item.gimbal_manager_compid == message.compid; + } + }); + + if (maybe_gimbal == _gimbals.end()) { + if (_debugging) { + LogDebug() << "Didn't find gimbal for gimbal device"; + } + return; } + auto gimbal = &(*maybe_gimbal); - _control_status.sysid_primary_control = status.primary_control_sysid; - _control_status.compid_primary_control = status.primary_control_compid; - _control_status.sysid_secondary_control = status.secondary_control_sysid; - _control_status.compid_secondary_control = status.secondary_control_compid; + gimbal->gimbal_device_information_received = true; + gimbal->vendor_name = gimbal_device_information.vendor_name; + gimbal->model_name = gimbal_device_information.model_name; + gimbal->custom_name = gimbal_device_information.custom_name; - _control_subscriptions.queue( - _control_status, [this](const auto& func) { _system_impl->call_user_callback(func); }); + check_is_gimbal_valid(gimbal); } void GimbalImpl::process_gimbal_device_attitude_status(const mavlink_message_t& message) @@ -122,23 +274,54 @@ void GimbalImpl::process_gimbal_device_attitude_status(const mavlink_message_t& is_in_forward_frame = false; } } else { - // Neither of the flags indicating the frame are set, we fallback to previous way + // Neither of the flags indicating the frame are set, we fall back to previous way // which depends on lock flag. if (attitude_status.flags & GIMBAL_DEVICE_FLAGS_YAW_LOCK) { is_in_forward_frame = false; } } + if (attitude_status.gimbal_device_id > 6) { + LogWarn() << "Ignoring gimbal device attitude status with invalid gimbal_device_id " + << attitude_status.gimbal_device_id << " from (" << message.sysid << "/" + << ")"; + return; + } + std::lock_guard lock(_mutex); + auto maybe_gimbal = std::find_if(_gimbals.begin(), _gimbals.end(), [&](const GimbalItem& item) { + if (attitude_status.gimbal_device_id == 0) { + return item.gimbal_device_id == message.compid; + } else { + return item.gimbal_manager_compid == message.compid && + item.gimbal_device_id == attitude_status.gimbal_device_id; + } + }); + + if (maybe_gimbal == _gimbals.end()) { + // Only warn if we have found any gimbals. + if (std::any_of(_gimbals.begin(), _gimbals.end(), [](const GimbalItem& item) { + return item.is_valid; + })) { + LogWarn() << "Received gimbal manager status for unknown gimbal."; + } + // Otherwise, ignore it silently + return; + } + + auto& gimbal = *maybe_gimbal; + // Reset to defaults (e.g. NaN) first. - _attitude = {}; + gimbal.attitude = {}; + // We need to populate the MAVSDK gimbal ID, so the user knows which is which. + gimbal.attitude.gimbal_id = static_cast(std::distance(_gimbals.begin(), maybe_gimbal)); if (is_in_forward_frame) { - _attitude.quaternion_forward.w = attitude_status.q[0]; - _attitude.quaternion_forward.x = attitude_status.q[1]; - _attitude.quaternion_forward.y = attitude_status.q[2]; - _attitude.quaternion_forward.z = attitude_status.q[3]; + gimbal.attitude.quaternion_forward.w = attitude_status.q[0]; + gimbal.attitude.quaternion_forward.x = attitude_status.q[1]; + gimbal.attitude.quaternion_forward.y = attitude_status.q[2]; + gimbal.attitude.quaternion_forward.z = attitude_status.q[3]; auto quaternion_forward = Quaternion{}; quaternion_forward.w = attitude_status.q[0]; @@ -147,11 +330,11 @@ void GimbalImpl::process_gimbal_device_attitude_status(const mavlink_message_t& quaternion_forward.z = attitude_status.q[3]; const auto euler_angle_forward = to_euler_angle_from_quaternion(quaternion_forward); - _attitude.euler_angle_forward.roll_deg = euler_angle_forward.roll_deg; - _attitude.euler_angle_forward.pitch_deg = euler_angle_forward.pitch_deg; - _attitude.euler_angle_forward.yaw_deg = euler_angle_forward.yaw_deg; + gimbal.attitude.euler_angle_forward.roll_deg = euler_angle_forward.roll_deg; + gimbal.attitude.euler_angle_forward.pitch_deg = euler_angle_forward.pitch_deg; + gimbal.attitude.euler_angle_forward.yaw_deg = euler_angle_forward.yaw_deg; - _attitude.timestamp_us = attitude_status.time_boot_ms * 1000; + gimbal.attitude.timestamp_us = attitude_status.time_boot_ms * 1000; // Calculate angle relative to North as well if (!std::isnan(_vehicle_yaw_rad)) { @@ -159,22 +342,22 @@ void GimbalImpl::process_gimbal_device_attitude_status(const mavlink_message_t& to_quaternion_from_euler_angle(EulerAngle{0, 0, to_deg_from_rad(_vehicle_yaw_rad)}); auto quaternion_north = rotation * quaternion_forward; - _attitude.quaternion_north.w = quaternion_north.w; - _attitude.quaternion_north.x = quaternion_north.x; - _attitude.quaternion_north.y = quaternion_north.y; - _attitude.quaternion_north.z = quaternion_north.z; + gimbal.attitude.quaternion_north.w = quaternion_north.w; + gimbal.attitude.quaternion_north.x = quaternion_north.x; + gimbal.attitude.quaternion_north.y = quaternion_north.y; + gimbal.attitude.quaternion_north.z = quaternion_north.z; const auto euler_angle_north = to_euler_angle_from_quaternion(quaternion_north); - _attitude.euler_angle_north.roll_deg = euler_angle_north.roll_deg; - _attitude.euler_angle_north.pitch_deg = euler_angle_north.pitch_deg; - _attitude.euler_angle_north.yaw_deg = euler_angle_north.yaw_deg; + gimbal.attitude.euler_angle_north.roll_deg = euler_angle_north.roll_deg; + gimbal.attitude.euler_angle_north.pitch_deg = euler_angle_north.pitch_deg; + gimbal.attitude.euler_angle_north.yaw_deg = euler_angle_north.yaw_deg; } } else { - _attitude.quaternion_north.w = attitude_status.q[0]; - _attitude.quaternion_north.x = attitude_status.q[1]; - _attitude.quaternion_north.y = attitude_status.q[2]; - _attitude.quaternion_north.z = attitude_status.q[3]; + gimbal.attitude.quaternion_north.w = attitude_status.q[0]; + gimbal.attitude.quaternion_north.x = attitude_status.q[1]; + gimbal.attitude.quaternion_north.y = attitude_status.q[2]; + gimbal.attitude.quaternion_north.z = attitude_status.q[3]; auto quaternion_north = Quaternion{}; quaternion_north.w = attitude_status.q[0]; @@ -183,9 +366,9 @@ void GimbalImpl::process_gimbal_device_attitude_status(const mavlink_message_t& quaternion_north.z = attitude_status.q[3]; const auto euler_angle_north = to_euler_angle_from_quaternion(quaternion_north); - _attitude.euler_angle_north.roll_deg = euler_angle_north.roll_deg; - _attitude.euler_angle_north.pitch_deg = euler_angle_north.pitch_deg; - _attitude.euler_angle_north.yaw_deg = euler_angle_north.yaw_deg; + gimbal.attitude.euler_angle_north.roll_deg = euler_angle_north.roll_deg; + gimbal.attitude.euler_angle_north.pitch_deg = euler_angle_north.pitch_deg; + gimbal.attitude.euler_angle_north.yaw_deg = euler_angle_north.yaw_deg; // Calculate angle relative to forward as well if (!std::isnan(_vehicle_yaw_rad)) { @@ -193,24 +376,24 @@ void GimbalImpl::process_gimbal_device_attitude_status(const mavlink_message_t& EulerAngle{0, 0, -to_deg_from_rad(_vehicle_yaw_rad)}); auto quaternion_forward = rotation * quaternion_north; - _attitude.quaternion_forward.w = quaternion_forward.w; - _attitude.quaternion_forward.x = quaternion_forward.x; - _attitude.quaternion_forward.y = quaternion_forward.y; - _attitude.quaternion_forward.z = quaternion_forward.z; + gimbal.attitude.quaternion_forward.w = quaternion_forward.w; + gimbal.attitude.quaternion_forward.x = quaternion_forward.x; + gimbal.attitude.quaternion_forward.y = quaternion_forward.y; + gimbal.attitude.quaternion_forward.z = quaternion_forward.z; const auto euler_angle_forward = to_euler_angle_from_quaternion(quaternion_forward); - _attitude.euler_angle_forward.roll_deg = euler_angle_forward.roll_deg; - _attitude.euler_angle_forward.pitch_deg = euler_angle_forward.pitch_deg; - _attitude.euler_angle_forward.yaw_deg = euler_angle_forward.yaw_deg; + gimbal.attitude.euler_angle_forward.roll_deg = euler_angle_forward.roll_deg; + gimbal.attitude.euler_angle_forward.pitch_deg = euler_angle_forward.pitch_deg; + gimbal.attitude.euler_angle_forward.yaw_deg = euler_angle_forward.yaw_deg; } } - _attitude.angular_velocity.roll_rad_s = attitude_status.angular_velocity_x; - _attitude.angular_velocity.pitch_rad_s = attitude_status.angular_velocity_y; - _attitude.angular_velocity.yaw_rad_s = attitude_status.angular_velocity_z; + gimbal.attitude.angular_velocity.roll_rad_s = attitude_status.angular_velocity_x; + gimbal.attitude.angular_velocity.pitch_rad_s = attitude_status.angular_velocity_y; + gimbal.attitude.angular_velocity.yaw_rad_s = attitude_status.angular_velocity_z; _attitude_subscriptions.queue( - _attitude, [this](const auto& func) { _system_impl->call_user_callback(func); }); + gimbal.attitude, [this](const auto& func) { _system_impl->call_user_callback(func); }); } void GimbalImpl::process_attitude(const mavlink_message_t& message) @@ -223,7 +406,54 @@ void GimbalImpl::process_attitude(const mavlink_message_t& message) _vehicle_yaw_rad = attitude.yaw; } +void GimbalImpl::check_is_gimbal_valid(GimbalItem* gimbal) +{ + assert(gimbal != nullptr); + + // Assumes lock + + if (gimbal->is_valid) { + // We're already done. + return; + } + + // Check if we should request GIMBAL_MANAGER_INFORMATION again. + if (!gimbal->gimbal_manager_information_received && + gimbal->gimbal_manager_information_requests_left-- > 0) { + request_gimbal_manager_information(gimbal->gimbal_manager_compid); + } + + if (!gimbal->gimbal_manager_information_received) { + // Leave it at this for now, we need the gimbal_device_id for further steps + return; + } + + // Check if we should request GIMBAL_DEVICE_INFORMATION again. + if (!gimbal->gimbal_device_information_received && + gimbal->gimbal_device_information_requests_left-- > 0) { + auto component_id = (gimbal->gimbal_device_id > 0 && gimbal->gimbal_device_id <= 6) ? + gimbal->gimbal_manager_compid : + gimbal->gimbal_device_id; + if (component_id != 0) { + request_gimbal_device_information(component_id); + } + return; + } + + // If we have gimbal_manager_information but no GIMBAL_DEVICE_INFORMATION despite + // having tried multiple times, we might as well continue without. + if (!gimbal->gimbal_device_information_received) { + LogWarn() << "Continuing despite GIMBAL_DEVICE_INFORMATION missing"; + } + + gimbal->is_valid = true; + _gimbal_list_subscriptions.queue(gimbal_list_with_lock(), [this](const auto& func) { + _system_impl->call_user_callback(func); + }); +} + Gimbal::Result GimbalImpl::set_angles( + int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, @@ -234,23 +464,34 @@ Gimbal::Result GimbalImpl::set_angles( auto fut = prom.get_future(); set_angles_async_internal( - roll_deg, pitch_deg, yaw_deg, gimbal_mode, send_mode, [&prom](Gimbal::Result result) { - prom.set_value(result); - }); + gimbal_id, + roll_deg, + pitch_deg, + yaw_deg, + gimbal_mode, + send_mode, + [&prom](Gimbal::Result result) { prom.set_value(result); }); return fut.get(); } void GimbalImpl::set_angles_async( + int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, Gimbal::GimbalMode gimbal_mode, Gimbal::SendMode send_mode, - Gimbal::ResultCallback callback) + const Gimbal::ResultCallback& callback) { set_angles_async_internal( - roll_deg, pitch_deg, yaw_deg, gimbal_mode, send_mode, [this, callback](auto result) { + gimbal_id, + roll_deg, + pitch_deg, + yaw_deg, + gimbal_mode, + send_mode, + [this, callback](auto result) { if (callback) { _system_impl->call_user_callback([callback, result]() { callback(result); }); } @@ -258,13 +499,27 @@ void GimbalImpl::set_angles_async( } void GimbalImpl::set_angles_async_internal( + int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, Gimbal::GimbalMode gimbal_mode, Gimbal::SendMode send_mode, - Gimbal::ResultCallback callback) + const Gimbal::ResultCallback& callback) { + std::lock_guard lock(_mutex); + + auto maybe_address = maybe_address_for_gimbal_id(gimbal_id); + + if (!maybe_address) { + if (callback) { + callback(Gimbal::Result::InvalidArgument); + } + return; + } + + auto address = maybe_address.value(); + const float roll_rad = to_rad_from_deg(roll_deg); const float pitch_rad = to_rad_from_deg(pitch_deg); const float yaw_rad = to_rad_from_deg(yaw_deg); @@ -272,14 +527,15 @@ void GimbalImpl::set_angles_async_internal( float quaternion[4]; mavlink_euler_to_quaternion(roll_rad, pitch_rad, yaw_rad, quaternion); - std::lock_guard lock(_mutex); - const uint32_t flags = GIMBAL_MANAGER_FLAGS_ROLL_LOCK | GIMBAL_MANAGER_FLAGS_PITCH_LOCK | ((gimbal_mode == Gimbal::GimbalMode::YawLock) ? GIMBAL_MANAGER_FLAGS_YAW_LOCK : 0); switch (send_mode) { case Gimbal::SendMode::Stream: { + if (_debugging) { + LogDebug() << "Sending GIMBAL_MANAGER_SET_ATTITUDE message with angles"; + } auto result = _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { mavlink_message_t message; @@ -288,10 +544,10 @@ void GimbalImpl::set_angles_async_internal( mavlink_address.component_id, channel, &message, - _gimbal_manager_sysid, - _gimbal_manager_compid, + _system_impl->get_system_id(), + address.gimbal_manager_compid, flags, - _gimbal_device_id, + address.gimbal_device_id, quaternion, NAN, NAN, @@ -312,17 +568,20 @@ void GimbalImpl::set_angles_async_internal( } } else { - MavlinkCommandSender::CommandInt command{}; + if (_debugging) { + LogDebug() << "Sending DO_GIMBAL_MANAGER_PITCHYAW command with angles"; + } + MavlinkCommandSender::CommandLong command{}; command.command = MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW; command.params.maybe_param1 = pitch_deg; command.params.maybe_param2 = yaw_deg; command.params.maybe_param3 = NAN; command.params.maybe_param4 = NAN; - command.params.x = flags; - command.params.maybe_z = _gimbal_device_id; - command.target_system_id = _gimbal_manager_sysid; - command.target_component_id = _gimbal_manager_compid; + command.params.maybe_param5 = static_cast(flags); + command.params.maybe_param7 = address.gimbal_device_id; + command.target_system_id = _system_impl->get_system_id(); + command.target_component_id = address.gimbal_manager_compid; _system_impl->send_command_async( command, [callback](MavlinkCommandSender::Result result, float) { @@ -340,6 +599,7 @@ void GimbalImpl::set_angles_async_internal( } Gimbal::Result GimbalImpl::set_angular_rates( + int32_t gimbal_id, float roll_rate_deg_s, float pitch_rate_deg_s, float yaw_rate_deg_s, @@ -350,6 +610,7 @@ Gimbal::Result GimbalImpl::set_angular_rates( auto fut = prom.get_future(); set_angular_rates_async_internal( + gimbal_id, roll_rate_deg_s, pitch_rate_deg_s, yaw_rate_deg_s, @@ -361,14 +622,16 @@ Gimbal::Result GimbalImpl::set_angular_rates( } void GimbalImpl::set_angular_rates_async( + int32_t gimbal_id, float roll_rate_deg_s, float pitch_rate_deg_s, float yaw_rate_deg_s, Gimbal::GimbalMode gimbal_mode, Gimbal::SendMode send_mode, - Gimbal::ResultCallback callback) + const Gimbal::ResultCallback& callback) { set_angular_rates_async_internal( + gimbal_id, roll_rate_deg_s, pitch_rate_deg_s, yaw_rate_deg_s, @@ -382,23 +645,38 @@ void GimbalImpl::set_angular_rates_async( } void GimbalImpl::set_angular_rates_async_internal( + int32_t gimbal_id, float roll_rate_deg_s, float pitch_rate_deg_s, float yaw_rate_deg_s, Gimbal::GimbalMode gimbal_mode, Gimbal::SendMode send_mode, - Gimbal::ResultCallback callback) + const Gimbal::ResultCallback& callback) { std::lock_guard lock(_mutex); + auto maybe_address = maybe_address_for_gimbal_id(gimbal_id); + + if (!maybe_address) { + if (callback) { + callback(Gimbal::Result::InvalidArgument); + } + return; + } + + auto address = maybe_address.value(); + const uint32_t flags = GIMBAL_MANAGER_FLAGS_ROLL_LOCK | GIMBAL_MANAGER_FLAGS_PITCH_LOCK | ((gimbal_mode == Gimbal::GimbalMode::YawLock) ? GIMBAL_MANAGER_FLAGS_YAW_LOCK : 0); switch (send_mode) { case Gimbal::SendMode::Stream: { - const float quaternion[4] = {NAN, NAN, NAN, NAN}; + constexpr float quaternion[4] = {NAN, NAN, NAN, NAN}; + if (_debugging) { + LogDebug() << "Sending GIMBAL_MANAGER_SET_ATTITUDE message with angular rates"; + } auto result = _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) { mavlink_message_t message; @@ -407,10 +685,10 @@ void GimbalImpl::set_angular_rates_async_internal( mavlink_address.component_id, channel, &message, - _gimbal_manager_sysid, - _gimbal_manager_compid, + _system_impl->get_system_id(), + address.gimbal_manager_compid, flags, - _gimbal_device_id, + address.gimbal_device_id, quaternion, to_rad_from_deg(roll_rate_deg_s), to_rad_from_deg(pitch_rate_deg_s), @@ -432,17 +710,20 @@ void GimbalImpl::set_angular_rates_async_internal( } } else { - MavlinkCommandSender::CommandInt command{}; + if (_debugging) { + LogDebug() << "Sending DO_GIMBAL_MANAGER_PITCHYAW command with angular rates"; + } + MavlinkCommandSender::CommandInt command{}; command.command = MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW; command.params.maybe_param1 = NAN; command.params.maybe_param2 = NAN; command.params.maybe_param3 = pitch_rate_deg_s; command.params.maybe_param4 = yaw_rate_deg_s; - command.params.x = flags; - command.params.maybe_z = _gimbal_device_id; - command.target_system_id = _gimbal_manager_sysid; - command.target_component_id = _gimbal_manager_compid; + command.params.x = static_cast(flags); + command.params.maybe_z = address.gimbal_device_id; + command.target_system_id = _system_impl->get_system_id(); + command.target_component_id = address.gimbal_manager_compid; _system_impl->send_command_async( command, [callback](MavlinkCommandSender::Result result, float) { @@ -457,34 +738,50 @@ void GimbalImpl::set_angular_rates_async_internal( } } -Gimbal::Result -GimbalImpl::set_roi_location(double latitude_deg, double longitude_deg, float altitude_m) +Gimbal::Result GimbalImpl::set_roi_location( + int32_t gimbal_id, double latitude_deg, double longitude_deg, float altitude_m) { - MavlinkCommandSender::CommandInt command{}; + auto prom = std::promise(); + auto fut = prom.get_future(); - command.command = MAV_CMD_DO_SET_ROI_LOCATION; - command.params.x = static_cast(std::round(latitude_deg * 1e7)); - command.params.y = static_cast(std::round(longitude_deg * 1e7)); - command.params.maybe_z = altitude_m; - command.target_system_id = _gimbal_manager_sysid; - command.target_component_id = _gimbal_manager_compid; + set_roi_location_async( + gimbal_id, latitude_deg, longitude_deg, altitude_m, [&prom](Gimbal::Result result) { + prom.set_value(result); + }); - return gimbal_result_from_command_result(_system_impl->send_command(command)); + return fut.get(); } void GimbalImpl::set_roi_location_async( - double latitude_deg, double longitude_deg, float altitude_m, Gimbal::ResultCallback callback) + int32_t gimbal_id, + double latitude_deg, + double longitude_deg, + float altitude_m, + const Gimbal::ResultCallback& callback) { std::lock_guard lock(_mutex); + auto maybe_address = maybe_address_for_gimbal_id(gimbal_id); + + if (!maybe_address) { + if (callback) { + _system_impl->call_user_callback( + [callback]() { callback(Gimbal::Result::InvalidArgument); }); + } + return; + } + + auto address = maybe_address.value(); + MavlinkCommandSender::CommandInt command{}; command.command = MAV_CMD_DO_SET_ROI_LOCATION; + command.params.maybe_param1 = address.gimbal_device_id; command.params.x = static_cast(std::round(latitude_deg * 1e7)); command.params.y = static_cast(std::round(longitude_deg * 1e7)); command.params.maybe_z = altitude_m; - command.target_system_id = _gimbal_manager_sysid; - command.target_component_id = _gimbal_manager_compid; + command.target_system_id = _system_impl->get_system_id(); + command.target_component_id = address.gimbal_manager_compid; _system_impl->send_command_async( command, [callback](MavlinkCommandSender::Result result, float) { @@ -492,26 +789,41 @@ void GimbalImpl::set_roi_location_async( }); } -Gimbal::Result GimbalImpl::take_control(Gimbal::ControlMode control_mode) +Gimbal::Result GimbalImpl::take_control(int32_t gimbal_id, Gimbal::ControlMode control_mode) { auto prom = std::promise(); auto fut = prom.get_future(); - take_control_async(control_mode, [&prom](Gimbal::Result result) { prom.set_value(result); }); + take_control_async( + gimbal_id, control_mode, [&prom](Gimbal::Result result) { prom.set_value(result); }); return fut.get(); } void GimbalImpl::take_control_async( - Gimbal::ControlMode control_mode, Gimbal::ResultCallback callback) + int32_t gimbal_id, Gimbal::ControlMode control_mode, const Gimbal::ResultCallback& callback) { std::lock_guard lock(_mutex); + auto maybe_address = maybe_address_for_gimbal_id(gimbal_id); + + if (!maybe_address) { + if (callback) { + callback(Gimbal::Result::InvalidArgument); + } + return; + } + + auto address = maybe_address.value(); + if (control_mode == Gimbal::ControlMode::None) { - release_control_async(callback); + release_control_async(gimbal_id, callback); return; } else if (control_mode == Gimbal::ControlMode::Secondary) { - _system_impl->call_user_callback([callback]() { callback(Gimbal::Result::Unsupported); }); + if (callback) { + _system_impl->call_user_callback( + [callback]() { callback(Gimbal::Result::Unsupported); }); + } LogErr() << "Gimbal secondary control is not implemented yet!"; return; } @@ -532,9 +844,9 @@ void GimbalImpl::take_control_async( own_compid : -3.0f; // compid secondary control - command.params.maybe_param7 = _gimbal_device_id; - command.target_system_id = _gimbal_manager_sysid; - command.target_component_id = _gimbal_manager_compid; + command.params.maybe_param7 = address.gimbal_device_id; + command.target_system_id = _system_impl->get_system_id(); + command.target_component_id = address.gimbal_manager_compid; _system_impl->send_command_async( command, [callback](MavlinkCommandSender::Result result, float) { @@ -542,17 +854,17 @@ void GimbalImpl::take_control_async( }); } -Gimbal::Result GimbalImpl::release_control() +Gimbal::Result GimbalImpl::release_control(int32_t gimbal_id) { auto prom = std::promise(); auto fut = prom.get_future(); - release_control_async([&prom](Gimbal::Result result) { prom.set_value(result); }); + release_control_async(gimbal_id, [&prom](Gimbal::Result result) { prom.set_value(result); }); return fut.get(); } -void GimbalImpl::release_control_async(Gimbal::ResultCallback callback) +void GimbalImpl::release_control_async(int32_t gimbal_id, const Gimbal::ResultCallback& callback) { std::lock_guard lock(_mutex); @@ -563,9 +875,22 @@ void GimbalImpl::release_control_async(Gimbal::ResultCallback callback) command.params.maybe_param2 = -3.0f; // compid primary control command.params.maybe_param3 = -3.0f; // sysid secondary control command.params.maybe_param4 = -3.0f; // compid secondary control - command.params.maybe_param7 = _gimbal_device_id; - command.target_system_id = _gimbal_manager_sysid; - command.target_component_id = _gimbal_manager_compid; + + auto maybe_address = maybe_address_for_gimbal_id(gimbal_id); + + if (!maybe_address) { + if (callback) { + _system_impl->call_user_callback( + [callback]() { callback(Gimbal::Result::InvalidArgument); }); + } + return; + } + + auto address = maybe_address.value(); + + command.target_component_id = address.gimbal_manager_compid; + command.target_system_id = _system_impl->get_system_id(); + command.params.maybe_param7 = address.gimbal_device_id; _system_impl->send_command_async( command, [callback](MavlinkCommandSender::Result result, float) { @@ -573,22 +898,84 @@ void GimbalImpl::release_control_async(Gimbal::ResultCallback callback) }); } -Gimbal::ControlStatus GimbalImpl::control() +std::pair GimbalImpl::get_control_status(int32_t gimbal_id) { std::lock_guard lock(_mutex); - return _control_status; + + auto* maybe_gimbal = maybe_gimbal_item_for_gimbal_id(gimbal_id); + + if (!maybe_gimbal) { + return {Gimbal::Result::InvalidArgument, {}}; + } + + auto& gimbal = *maybe_gimbal; + return {Gimbal::Result::Success, gimbal.control_status}; } -Gimbal::ControlHandle GimbalImpl::subscribe_control(const Gimbal::ControlCallback& callback) +Gimbal::GimbalListHandle +GimbalImpl::subscribe_gimbal_list(const Gimbal::GimbalListCallback& callback) { std::lock_guard lock(_mutex); - return _control_subscriptions.subscribe(callback); + auto handle = _gimbal_list_subscriptions.subscribe(callback); + + if (std::any_of(_gimbals.begin(), _gimbals.end(), [](const GimbalItem& item) { + return item.is_valid; + })) { + // We already have some gimbals detected that we need to tell the subscriber. + _gimbal_list_subscriptions.queue(gimbal_list_with_lock(), [this](const auto& func) { + _system_impl->call_user_callback(func); + }); + } + + return handle; } -void GimbalImpl::unsubscribe_control(Gimbal::ControlHandle handle) +void GimbalImpl::unsubscribe_gimbal_list(Gimbal::GimbalListHandle handle) { std::lock_guard lock(_mutex); - _control_subscriptions.unsubscribe(handle); + _gimbal_list_subscriptions.unsubscribe(handle); +} + +Gimbal::GimbalList GimbalImpl::gimbal_list() +{ + std::lock_guard lock(_mutex); + + return gimbal_list_with_lock(); +} + +Gimbal::GimbalList GimbalImpl::gimbal_list_with_lock() +{ + // Obviously assume lock + + int32_t gimbal_id = 1; + Gimbal::GimbalList new_list; + for (auto& gimbal : _gimbals) { + if (!gimbal.is_valid) { + continue; + } + Gimbal::GimbalItem new_item{}; + new_item.gimbal_id = gimbal_id++; + new_item.gimbal_device_id = gimbal.gimbal_device_id; + new_item.gimbal_manager_component_id = gimbal.gimbal_manager_compid; + new_item.vendor_name = gimbal.vendor_name; + new_item.model_name = gimbal.model_name; + new_item.custom_name = gimbal.custom_name; + new_list.gimbals.emplace_back(std::move(new_item)); + } + return new_list; +} + +Gimbal::ControlStatusHandle +GimbalImpl::subscribe_control_status(const Gimbal::ControlStatusCallback& callback) +{ + std::lock_guard lock(_mutex); + return _control_status_subscriptions.subscribe(callback); +} + +void GimbalImpl::unsubscribe_control_status(Gimbal::ControlStatusHandle handle) +{ + std::lock_guard lock(_mutex); + _control_status_subscriptions.unsubscribe(handle); } Gimbal::AttitudeHandle GimbalImpl::subscribe_attitude(const Gimbal::AttitudeCallback& callback) @@ -603,10 +990,19 @@ void GimbalImpl::unsubscribe_attitude(Gimbal::AttitudeHandle handle) _attitude_subscriptions.unsubscribe(handle); } -Gimbal::Attitude GimbalImpl::attitude() +std::pair GimbalImpl::get_attitude(int32_t gimbal_id) { std::lock_guard lock(_mutex); - return _attitude; + + auto* maybe_gimbal = maybe_gimbal_item_for_gimbal_id(gimbal_id); + + if (!maybe_gimbal) { + return {Gimbal::Result::InvalidArgument, {}}; + } + + auto& gimbal = *maybe_gimbal; + + return {Gimbal::Result::Success, gimbal.attitude}; } void GimbalImpl::receive_command_result( @@ -637,4 +1033,49 @@ GimbalImpl::gimbal_result_from_command_result(MavlinkCommandSender::Result comma } } +std::optional +GimbalImpl::maybe_address_for_gimbal_id(int32_t gimbal_id) const +{ + // Assumes lock + + if (gimbal_id < 0) { + LogWarn() << "Invalid negative gimbal ID: " << gimbal_id; + return {}; + } + + if (gimbal_id > _gimbals.size()) { + LogWarn() << "Invalid positive gimbal ID: " << gimbal_id; + return {}; + } + + if (gimbal_id == 0) { + return GimbalAddress{0, 0}; + } + + return GimbalAddress{ + _gimbals[gimbal_id - 1].gimbal_manager_compid, _gimbals[gimbal_id - 1].gimbal_device_id}; +} + +GimbalImpl::GimbalItem* GimbalImpl::maybe_gimbal_item_for_gimbal_id(int32_t gimbal_id) +{ + // Assumes lock + + if (gimbal_id == 0) { + LogWarn() << "Invalid gimbal ID: " << gimbal_id; + return nullptr; + } + + if (gimbal_id < 0) { + LogWarn() << "Invalid negative gimbal ID: " << gimbal_id; + return nullptr; + } + + if (gimbal_id > _gimbals.size()) { + LogWarn() << "Invalid positive gimbal ID: " << gimbal_id; + return nullptr; + } + + return &_gimbals[gimbal_id - 1]; +} + } // namespace mavsdk diff --git a/src/mavsdk/plugins/gimbal/gimbal_impl.h b/src/mavsdk/plugins/gimbal/gimbal_impl.h index f63249bb0b..54c7ba7f65 100644 --- a/src/mavsdk/plugins/gimbal/gimbal_impl.h +++ b/src/mavsdk/plugins/gimbal/gimbal_impl.h @@ -1,5 +1,6 @@ #pragma once +#include #include "plugins/gimbal/gimbal.h" #include "plugin_impl_base.h" #include "system.h" @@ -20,53 +21,67 @@ class GimbalImpl : public PluginImplBase { void disable() override; Gimbal::Result set_angles( + int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, Gimbal::GimbalMode gimbal_mode, Gimbal::SendMode send_mode); void set_angles_async( + int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, Gimbal::GimbalMode gimbal_mode, Gimbal::SendMode send_mode, - Gimbal::ResultCallback callback); + const Gimbal::ResultCallback& callback); Gimbal::Result set_angular_rates( + int32_t gimbal_id, float roll_rate_deg, float pitch_rate_deg, float yaw_rate_deg, Gimbal::GimbalMode gimbal_mode, Gimbal::SendMode send_mode); void set_angular_rates_async( + int32_t gimbal_id, float roll_rate_deg, float pitch_rate_deg, float yaw_rate_deg, Gimbal::GimbalMode gimbal_mode, Gimbal::SendMode send_mode, - Gimbal::ResultCallback callback); + const Gimbal::ResultCallback& callback); - Gimbal::Result set_roi_location(double latitude_deg, double longitude_deg, float altitude_m); + Gimbal::Result set_roi_location( + int32_t gimbal_id, double latitude_deg, double longitude_deg, float altitude_m); void set_roi_location_async( + int32_t gimbal_id, double latitude_deg, double longitude_deg, float altitude_m, - Gimbal::ResultCallback callback); + const Gimbal::ResultCallback& callback); - Gimbal::Result take_control(Gimbal::ControlMode control_mode); - void take_control_async(Gimbal::ControlMode control_mode, Gimbal::ResultCallback callback); + Gimbal::Result take_control(int32_t gimbal_id, Gimbal::ControlMode control_mode); + void take_control_async( + int32_t gimbal_id, + Gimbal::ControlMode control_mode, + const Gimbal::ResultCallback& callback); - Gimbal::Result release_control(); - void release_control_async(Gimbal::ResultCallback callback); + Gimbal::Result release_control(int32_t gimbal_id); + void release_control_async(int32_t gimbal_id, const Gimbal::ResultCallback& callback); - Gimbal::ControlStatus control(); - Gimbal::ControlHandle subscribe_control(const Gimbal::ControlCallback& callback); - void unsubscribe_control(Gimbal::ControlHandle handle); + Gimbal::GimbalListHandle subscribe_gimbal_list(const Gimbal::GimbalListCallback& callback); + void unsubscribe_gimbal_list(Gimbal::GimbalListHandle handle); + Gimbal::GimbalList gimbal_list(); + + Gimbal::ControlStatusHandle + subscribe_control_status(const Gimbal::ControlStatusCallback& callback); + void unsubscribe_control_status(Gimbal::ControlStatusHandle handle); + std::pair get_control_status(int32_t gimbal_id); Gimbal::AttitudeHandle subscribe_attitude(const Gimbal::AttitudeCallback& callback); void unsubscribe_attitude(Gimbal::AttitudeHandle handle); - Gimbal::Attitude attitude(); + std::pair get_attitude(int32_t gimbal_id); static Gimbal::Result gimbal_result_from_command_result(MavlinkCommandSender::Result command_result); @@ -79,40 +94,69 @@ class GimbalImpl : public PluginImplBase { const GimbalImpl& operator=(const GimbalImpl&) = delete; private: - void request_gimbal_information(); - + struct GimbalItem { + Gimbal::ControlStatus control_status{0, Gimbal::ControlMode::None, 0, 0, 0, 0}; + Gimbal::Attitude attitude{}; + std::string vendor_name; + std::string model_name; + std::string custom_name; + unsigned gimbal_manager_information_requests_left{5}; + unsigned gimbal_device_information_requests_left{5}; + bool gimbal_manager_information_received{false}; + bool gimbal_device_information_received{false}; + uint8_t gimbal_manager_compid{0}; + uint8_t gimbal_device_id{0}; + bool is_valid{false}; + }; + + struct GimbalAddress { + uint8_t gimbal_manager_compid{0}; + uint8_t gimbal_device_id{0}; + }; + + void request_gimbal_manager_information(uint8_t target_component_id) const; + void request_gimbal_device_information(uint8_t target_component_id) const; + + void process_heartbeat(const mavlink_message_t& message); void process_gimbal_manager_information(const mavlink_message_t& message); void process_gimbal_manager_status(const mavlink_message_t& message); + void process_gimbal_device_information(const mavlink_message_t& message); void process_gimbal_device_attitude_status(const mavlink_message_t& message); void process_attitude(const mavlink_message_t& message); + void check_is_gimbal_valid(GimbalItem* gimbal_item); + void set_angles_async_internal( + int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, Gimbal::GimbalMode gimbal_mode, Gimbal::SendMode send_mode, - Gimbal::ResultCallback callback); + const Gimbal::ResultCallback& callback); void set_angular_rates_async_internal( + int32_t gimbal_id, float roll_rate_deg, float pitch_rate_deg, float yaw_rate_deg, Gimbal::GimbalMode gimbal_mode, Gimbal::SendMode send_mode, - Gimbal::ResultCallback callback); + const Gimbal::ResultCallback& callback); + + Gimbal::GimbalList gimbal_list_with_lock(); + std::optional maybe_address_for_gimbal_id(int32_t gimbal_id) const; + GimbalItem* maybe_gimbal_item_for_gimbal_id(int32_t gimbal_id); std::mutex _mutex{}; - CallbackList _control_subscriptions{}; + CallbackList _gimbal_list_subscriptions{}; + CallbackList _control_status_subscriptions{}; CallbackList _attitude_subscriptions{}; - uint8_t _gimbal_device_id{0}; - uint8_t _gimbal_manager_sysid{0}; - uint8_t _gimbal_manager_compid{0}; - - Gimbal::ControlStatus _control_status{Gimbal::ControlMode::None, 0, 0, 0, 0}; - Gimbal::Attitude _attitude{}; + std::vector _gimbals; float _vehicle_yaw_rad{NAN}; + + bool _debugging{false}; }; } // namespace mavsdk diff --git a/src/mavsdk/plugins/gimbal/include/plugins/gimbal/gimbal.h b/src/mavsdk/plugins/gimbal/include/plugins/gimbal/gimbal.h index c521ee0fe8..8283074d36 100644 --- a/src/mavsdk/plugins/gimbal/include/plugins/gimbal/gimbal.h +++ b/src/mavsdk/plugins/gimbal/include/plugins/gimbal/gimbal.h @@ -198,6 +198,7 @@ class Gimbal : public PluginBase { * @brief Gimbal attitude type */ struct Attitude { + int32_t gimbal_id{}; /**< @brief Gimbal ID */ EulerAngle euler_angle_forward{}; /**< @brief Euler angle relative to forward */ Quaternion quaternion_forward{}; /**< @brief Quaternion relative to forward */ EulerAngle euler_angle_north{}; /**< @brief Euler angle relative to North */ @@ -220,10 +221,59 @@ class Gimbal : public PluginBase { */ friend std::ostream& operator<<(std::ostream& str, Gimbal::Attitude const& attitude); + /** + * @brief Gimbal list item + */ + struct GimbalItem { + int32_t gimbal_id{}; /**< @brief ID to address it, starting at 1 (0 means all gimbals) */ + std::string vendor_name{}; /**< @brief Vendor name */ + std::string model_name{}; /**< @brief Model name */ + std::string custom_name{}; /**< @brief Custom name name */ + int32_t gimbal_manager_component_id{}; /**< @brief MAVLink component of gimbal manager, for + debugging purposes */ + int32_t gimbal_device_id{}; /**< @brief MAVLink component of gimbal device */ + }; + + /** + * @brief Equal operator to compare two `Gimbal::GimbalItem` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==(const Gimbal::GimbalItem& lhs, const Gimbal::GimbalItem& rhs); + + /** + * @brief Stream operator to print information about a `Gimbal::GimbalItem`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, Gimbal::GimbalItem const& gimbal_item); + + /** + * @brief Gimbal list + */ + struct GimbalList { + std::vector gimbals{}; /**< @brief Gimbal item. */ + }; + + /** + * @brief Equal operator to compare two `Gimbal::GimbalList` objects. + * + * @return `true` if items are equal. + */ + friend bool operator==(const Gimbal::GimbalList& lhs, const Gimbal::GimbalList& rhs); + + /** + * @brief Stream operator to print information about a `Gimbal::GimbalList`. + * + * @return A reference to the stream. + */ + friend std::ostream& operator<<(std::ostream& str, Gimbal::GimbalList const& gimbal_list); + /** * @brief Control status */ struct ControlStatus { + int32_t gimbal_id{}; /**< @brief Gimbal ID */ ControlMode control_mode{}; /**< @brief Control mode (none, primary or secondary) */ int32_t sysid_primary_control{}; /**< @brief Sysid of the component that has primary control over the gimbal (0 if no one is in control) */ @@ -287,6 +337,7 @@ class Gimbal : public PluginBase { * This function is non-blocking. See 'set_angles' for the blocking counterpart. */ void set_angles_async( + int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, @@ -308,6 +359,7 @@ class Gimbal : public PluginBase { * @return Result of request. */ Result set_angles( + int32_t gimbal_id, float roll_deg, float pitch_deg, float yaw_deg, @@ -326,6 +378,7 @@ class Gimbal : public PluginBase { * This function is non-blocking. See 'set_angular_rates' for the blocking counterpart. */ void set_angular_rates_async( + int32_t gimbal_id, float roll_rate_deg_s, float pitch_rate_deg_s, float yaw_rate_deg_s, @@ -347,6 +400,7 @@ class Gimbal : public PluginBase { * @return Result of request. */ Result set_angular_rates( + int32_t gimbal_id, float roll_rate_deg_s, float pitch_rate_deg_s, float yaw_rate_deg_s, @@ -365,7 +419,11 @@ class Gimbal : public PluginBase { * This function is non-blocking. See 'set_roi_location' for the blocking counterpart. */ void set_roi_location_async( - double latitude_deg, double longitude_deg, float altitude_m, const ResultCallback callback); + int32_t gimbal_id, + double latitude_deg, + double longitude_deg, + float altitude_m, + const ResultCallback callback); /** * @brief Set gimbal region of interest (ROI). @@ -380,7 +438,8 @@ class Gimbal : public PluginBase { * * @return Result of request. */ - Result set_roi_location(double latitude_deg, double longitude_deg, float altitude_m) const; + Result set_roi_location( + int32_t gimbal_id, double latitude_deg, double longitude_deg, float altitude_m) const; /** * @brief Take control. @@ -395,7 +454,8 @@ class Gimbal : public PluginBase { * * This function is non-blocking. See 'take_control' for the blocking counterpart. */ - void take_control_async(ControlMode control_mode, const ResultCallback callback); + void + take_control_async(int32_t gimbal_id, ControlMode control_mode, const ResultCallback callback); /** * @brief Take control. @@ -412,7 +472,7 @@ class Gimbal : public PluginBase { * * @return Result of request. */ - Result take_control(ControlMode control_mode) const; + Result take_control(int32_t gimbal_id, ControlMode control_mode) const; /** * @brief Release control. @@ -421,7 +481,7 @@ class Gimbal : public PluginBase { * * This function is non-blocking. See 'release_control' for the blocking counterpart. */ - void release_control_async(const ResultCallback callback); + void release_control_async(int32_t gimbal_id, const ResultCallback callback); /** * @brief Release control. @@ -432,17 +492,47 @@ class Gimbal : public PluginBase { * * @return Result of request. */ - Result release_control() const; + Result release_control(int32_t gimbal_id) const; /** - * @brief Callback type for subscribe_control. + * @brief Callback type for subscribe_gimbal_list. */ - using ControlCallback = std::function; + using GimbalListCallback = std::function; /** - * @brief Handle type for subscribe_control. + * @brief Handle type for subscribe_gimbal_list. */ - using ControlHandle = Handle; + using GimbalListHandle = Handle; + + /** + * @brief Subscribe to list of gimbals. + * + * This allows to find out what gimbals are connected to the system. + * Based on the gimbal ID, we can then address a specific gimbal. + */ + GimbalListHandle subscribe_gimbal_list(const GimbalListCallback& callback); + + /** + * @brief Unsubscribe from subscribe_gimbal_list + */ + void unsubscribe_gimbal_list(GimbalListHandle handle); + + /** + * @brief Poll for 'GimbalList' (blocking). + * + * @return One GimbalList update. + */ + GimbalList gimbal_list() const; + + /** + * @brief Callback type for subscribe_control_status. + */ + using ControlStatusCallback = std::function; + + /** + * @brief Handle type for subscribe_control_status. + */ + using ControlStatusHandle = Handle; /** * @brief Subscribe to control status updates. @@ -451,19 +541,21 @@ class Gimbal : public PluginBase { * no control over the gimbal. Also, it gives the system and component ids * of the other components in control (if any). */ - ControlHandle subscribe_control(const ControlCallback& callback); + ControlStatusHandle subscribe_control_status(const ControlStatusCallback& callback); /** - * @brief Unsubscribe from subscribe_control + * @brief Unsubscribe from subscribe_control_status */ - void unsubscribe_control(ControlHandle handle); + void unsubscribe_control_status(ControlStatusHandle handle); /** - * @brief Poll for 'ControlStatus' (blocking). + * @brief Get control status for specific gimbal. + * + * This function is blocking. * - * @return One ControlStatus update. + * @return Result of request. */ - ControlStatus control() const; + std::pair get_control_status(int32_t gimbal_id) const; /** * @brief Callback type for subscribe_attitude. @@ -488,11 +580,13 @@ class Gimbal : public PluginBase { void unsubscribe_attitude(AttitudeHandle handle); /** - * @brief Poll for 'Attitude' (blocking). + * @brief Get attitude for specific gimbal. + * + * This function is blocking. * - * @return One Attitude update. + * @return Result of request. */ - Attitude attitude() const; + std::pair get_attitude(int32_t gimbal_id) const; /** * @brief Copy constructor. diff --git a/src/mavsdk_server/src/generated/gimbal/gimbal.grpc.pb.cc b/src/mavsdk_server/src/generated/gimbal/gimbal.grpc.pb.cc index 9b0087767b..f60067a4ae 100644 --- a/src/mavsdk_server/src/generated/gimbal/gimbal.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/gimbal/gimbal.grpc.pb.cc @@ -29,8 +29,11 @@ static const char* GimbalService_method_names[] = { "/mavsdk.rpc.gimbal.GimbalService/SetRoiLocation", "/mavsdk.rpc.gimbal.GimbalService/TakeControl", "/mavsdk.rpc.gimbal.GimbalService/ReleaseControl", - "/mavsdk.rpc.gimbal.GimbalService/SubscribeControl", + "/mavsdk.rpc.gimbal.GimbalService/SubscribeGimbalList", + "/mavsdk.rpc.gimbal.GimbalService/SubscribeControlStatus", + "/mavsdk.rpc.gimbal.GimbalService/GetControlStatus", "/mavsdk.rpc.gimbal.GimbalService/SubscribeAttitude", + "/mavsdk.rpc.gimbal.GimbalService/GetAttitude", }; std::unique_ptr< GimbalService::Stub> GimbalService::NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) { @@ -45,8 +48,11 @@ GimbalService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& chan , rpcmethod_SetRoiLocation_(GimbalService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_TakeControl_(GimbalService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) , rpcmethod_ReleaseControl_(GimbalService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeControl_(GimbalService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeAttitude_(GimbalService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeGimbalList_(GimbalService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeControlStatus_(GimbalService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_GetControlStatus_(GimbalService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeAttitude_(GimbalService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_GetAttitude_(GimbalService_method_names[9], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) {} ::grpc::Status GimbalService::Stub::SetAngles(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SetAnglesRequest& request, ::mavsdk::rpc::gimbal::SetAnglesResponse* response) { @@ -164,20 +170,59 @@ ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::ReleaseControlResponse return result; } -::grpc::ClientReader< ::mavsdk::rpc::gimbal::ControlResponse>* GimbalService::Stub::SubscribeControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request) { - return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::gimbal::ControlResponse>::Create(channel_.get(), rpcmethod_SubscribeControl_, context, request); +::grpc::ClientReader< ::mavsdk::rpc::gimbal::GimbalListResponse>* GimbalService::Stub::SubscribeGimbalListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::gimbal::GimbalListResponse>::Create(channel_.get(), rpcmethod_SubscribeGimbalList_, context, request); } -void GimbalService::Stub::async::SubscribeControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::gimbal::ControlResponse>* reactor) { - ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::gimbal::ControlResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeControl_, context, request, reactor); +void GimbalService::Stub::async::SubscribeGimbalList(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::gimbal::GimbalListResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::gimbal::GimbalListResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeGimbalList_, context, request, reactor); } -::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlResponse>* GimbalService::Stub::AsyncSubscribeControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::gimbal::ControlResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeControl_, context, request, true, tag); +::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::GimbalListResponse>* GimbalService::Stub::AsyncSubscribeGimbalListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::gimbal::GimbalListResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeGimbalList_, context, request, true, tag); } -::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlResponse>* GimbalService::Stub::PrepareAsyncSubscribeControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request, ::grpc::CompletionQueue* cq) { - return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::gimbal::ControlResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeControl_, context, request, false, nullptr); +::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::GimbalListResponse>* GimbalService::Stub::PrepareAsyncSubscribeGimbalListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::gimbal::GimbalListResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeGimbalList_, context, request, false, nullptr); +} + +::grpc::ClientReader< ::mavsdk::rpc::gimbal::ControlStatusResponse>* GimbalService::Stub::SubscribeControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request) { + return ::grpc::internal::ClientReaderFactory< ::mavsdk::rpc::gimbal::ControlStatusResponse>::Create(channel_.get(), rpcmethod_SubscribeControlStatus_, context, request); +} + +void GimbalService::Stub::async::SubscribeControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::gimbal::ControlStatusResponse>* reactor) { + ::grpc::internal::ClientCallbackReaderFactory< ::mavsdk::rpc::gimbal::ControlStatusResponse>::Create(stub_->channel_.get(), stub_->rpcmethod_SubscribeControlStatus_, context, request, reactor); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlStatusResponse>* GimbalService::Stub::AsyncSubscribeControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::gimbal::ControlStatusResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeControlStatus_, context, request, true, tag); +} + +::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlStatusResponse>* GimbalService::Stub::PrepareAsyncSubscribeControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::gimbal::ControlStatusResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeControlStatus_, context, request, false, nullptr); +} + +::grpc::Status GimbalService::Stub::GetControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest& request, ::mavsdk::rpc::gimbal::GetControlStatusResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::gimbal::GetControlStatusRequest, ::mavsdk::rpc::gimbal::GetControlStatusResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_GetControlStatus_, context, request, response); +} + +void GimbalService::Stub::async::GetControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* request, ::mavsdk::rpc::gimbal::GetControlStatusResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::gimbal::GetControlStatusRequest, ::mavsdk::rpc::gimbal::GetControlStatusResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetControlStatus_, context, request, response, std::move(f)); +} + +void GimbalService::Stub::async::GetControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* request, ::mavsdk::rpc::gimbal::GetControlStatusResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetControlStatus_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetControlStatusResponse>* GimbalService::Stub::PrepareAsyncGetControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::gimbal::GetControlStatusResponse, ::mavsdk::rpc::gimbal::GetControlStatusRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_GetControlStatus_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetControlStatusResponse>* GimbalService::Stub::AsyncGetControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncGetControlStatusRaw(context, request, cq); + result->StartCall(); + return result; } ::grpc::ClientReader< ::mavsdk::rpc::gimbal::AttitudeResponse>* GimbalService::Stub::SubscribeAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest& request) { @@ -196,6 +241,29 @@ ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::AttitudeResponse>* GimbalServi return ::grpc::internal::ClientAsyncReaderFactory< ::mavsdk::rpc::gimbal::AttitudeResponse>::Create(channel_.get(), cq, rpcmethod_SubscribeAttitude_, context, request, false, nullptr); } +::grpc::Status GimbalService::Stub::GetAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest& request, ::mavsdk::rpc::gimbal::GetAttitudeResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::gimbal::GetAttitudeRequest, ::mavsdk::rpc::gimbal::GetAttitudeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_GetAttitude_, context, request, response); +} + +void GimbalService::Stub::async::GetAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* request, ::mavsdk::rpc::gimbal::GetAttitudeResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::gimbal::GetAttitudeRequest, ::mavsdk::rpc::gimbal::GetAttitudeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetAttitude_, context, request, response, std::move(f)); +} + +void GimbalService::Stub::async::GetAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* request, ::mavsdk::rpc::gimbal::GetAttitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_GetAttitude_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetAttitudeResponse>* GimbalService::Stub::PrepareAsyncGetAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::gimbal::GetAttitudeResponse, ::mavsdk::rpc::gimbal::GetAttitudeRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_GetAttitude_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetAttitudeResponse>* GimbalService::Stub::AsyncGetAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncGetAttitudeRaw(context, request, cq); + result->StartCall(); + return result; +} + GimbalService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( GimbalService_method_names[0], @@ -250,16 +318,36 @@ GimbalService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( GimbalService_method_names[5], ::grpc::internal::RpcMethod::SERVER_STREAMING, - new ::grpc::internal::ServerStreamingHandler< GimbalService::Service, ::mavsdk::rpc::gimbal::SubscribeControlRequest, ::mavsdk::rpc::gimbal::ControlResponse>( + new ::grpc::internal::ServerStreamingHandler< GimbalService::Service, ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest, ::mavsdk::rpc::gimbal::GimbalListResponse>( [](GimbalService::Service* service, ::grpc::ServerContext* ctx, - const ::mavsdk::rpc::gimbal::SubscribeControlRequest* req, - ::grpc::ServerWriter<::mavsdk::rpc::gimbal::ControlResponse>* writer) { - return service->SubscribeControl(ctx, req, writer); + const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::gimbal::GimbalListResponse>* writer) { + return service->SubscribeGimbalList(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( GimbalService_method_names[6], ::grpc::internal::RpcMethod::SERVER_STREAMING, + new ::grpc::internal::ServerStreamingHandler< GimbalService::Service, ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest, ::mavsdk::rpc::gimbal::ControlStatusResponse>( + [](GimbalService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* req, + ::grpc::ServerWriter<::mavsdk::rpc::gimbal::ControlStatusResponse>* writer) { + return service->SubscribeControlStatus(ctx, req, writer); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + GimbalService_method_names[7], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< GimbalService::Service, ::mavsdk::rpc::gimbal::GetControlStatusRequest, ::mavsdk::rpc::gimbal::GetControlStatusResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](GimbalService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::gimbal::GetControlStatusRequest* req, + ::mavsdk::rpc::gimbal::GetControlStatusResponse* resp) { + return service->GetControlStatus(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + GimbalService_method_names[8], + ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< GimbalService::Service, ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest, ::mavsdk::rpc::gimbal::AttitudeResponse>( [](GimbalService::Service* service, ::grpc::ServerContext* ctx, @@ -267,6 +355,16 @@ GimbalService::Service::Service() { ::grpc::ServerWriter<::mavsdk::rpc::gimbal::AttitudeResponse>* writer) { return service->SubscribeAttitude(ctx, req, writer); }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + GimbalService_method_names[9], + ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< GimbalService::Service, ::mavsdk::rpc::gimbal::GetAttitudeRequest, ::mavsdk::rpc::gimbal::GetAttitudeResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](GimbalService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::gimbal::GetAttitudeRequest* req, + ::mavsdk::rpc::gimbal::GetAttitudeResponse* resp) { + return service->GetAttitude(ctx, req, resp); + }, this))); } GimbalService::Service::~Service() { @@ -307,13 +405,27 @@ ::grpc::Status GimbalService::Service::ReleaseControl(::grpc::ServerContext* con return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } -::grpc::Status GimbalService::Service::SubscribeControl(::grpc::ServerContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlResponse>* writer) { +::grpc::Status GimbalService::Service::SubscribeGimbalList(::grpc::ServerContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::GimbalListResponse>* writer) { (void) context; (void) request; (void) writer; return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status GimbalService::Service::SubscribeControlStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlStatusResponse>* writer) { + (void) context; + (void) request; + (void) writer; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + +::grpc::Status GimbalService::Service::GetControlStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* request, ::mavsdk::rpc::gimbal::GetControlStatusResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status GimbalService::Service::SubscribeAttitude(::grpc::ServerContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::AttitudeResponse>* writer) { (void) context; (void) request; @@ -321,6 +433,13 @@ ::grpc::Status GimbalService::Service::SubscribeAttitude(::grpc::ServerContext* return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } +::grpc::Status GimbalService::Service::GetAttitude(::grpc::ServerContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* request, ::mavsdk::rpc::gimbal::GetAttitudeResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + } // namespace mavsdk } // namespace rpc diff --git a/src/mavsdk_server/src/generated/gimbal/gimbal.grpc.pb.h b/src/mavsdk_server/src/generated/gimbal/gimbal.grpc.pb.h index 2c611b8ac0..cb573c3ffe 100644 --- a/src/mavsdk_server/src/generated/gimbal/gimbal.grpc.pb.h +++ b/src/mavsdk_server/src/generated/gimbal/gimbal.grpc.pb.h @@ -112,19 +112,42 @@ class GimbalService final { return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::ReleaseControlResponse>>(PrepareAsyncReleaseControlRaw(context, request, cq)); } // + // Subscribe to list of gimbals. + // + // This allows to find out what gimbals are connected to the system. + // Based on the gimbal ID, we can then address a specific gimbal. + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::gimbal::GimbalListResponse>> SubscribeGimbalList(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::gimbal::GimbalListResponse>>(SubscribeGimbalListRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::GimbalListResponse>> AsyncSubscribeGimbalList(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::GimbalListResponse>>(AsyncSubscribeGimbalListRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::GimbalListResponse>> PrepareAsyncSubscribeGimbalList(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::GimbalListResponse>>(PrepareAsyncSubscribeGimbalListRaw(context, request, cq)); + } + // // Subscribe to control status updates. // // This allows a component to know if it has primary, secondary or // no control over the gimbal. Also, it gives the system and component ids // of the other components in control (if any). - std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::gimbal::ControlResponse>> SubscribeControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request) { - return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::gimbal::ControlResponse>>(SubscribeControlRaw(context, request)); + std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::gimbal::ControlStatusResponse>> SubscribeControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request) { + return std::unique_ptr< ::grpc::ClientReaderInterface< ::mavsdk::rpc::gimbal::ControlStatusResponse>>(SubscribeControlStatusRaw(context, request)); } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::ControlResponse>> AsyncSubscribeControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::ControlResponse>>(AsyncSubscribeControlRaw(context, request, cq, tag)); + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::ControlStatusResponse>> AsyncSubscribeControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::ControlStatusResponse>>(AsyncSubscribeControlStatusRaw(context, request, cq, tag)); } - std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::ControlResponse>> PrepareAsyncSubscribeControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::ControlResponse>>(PrepareAsyncSubscribeControlRaw(context, request, cq)); + std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::ControlStatusResponse>> PrepareAsyncSubscribeControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::ControlStatusResponse>>(PrepareAsyncSubscribeControlStatusRaw(context, request, cq)); + } + // + // Get control status for specific gimbal. + virtual ::grpc::Status GetControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest& request, ::mavsdk::rpc::gimbal::GetControlStatusResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::GetControlStatusResponse>> AsyncGetControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::GetControlStatusResponse>>(AsyncGetControlStatusRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::GetControlStatusResponse>> PrepareAsyncGetControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::GetControlStatusResponse>>(PrepareAsyncGetControlStatusRaw(context, request, cq)); } // // Subscribe to attitude updates. @@ -139,6 +162,15 @@ class GimbalService final { std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::AttitudeResponse>> PrepareAsyncSubscribeAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::AttitudeResponse>>(PrepareAsyncSubscribeAttitudeRaw(context, request, cq)); } + // + // Get attitude for specific gimbal. + virtual ::grpc::Status GetAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest& request, ::mavsdk::rpc::gimbal::GetAttitudeResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::GetAttitudeResponse>> AsyncGetAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::GetAttitudeResponse>>(AsyncGetAttitudeRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::GetAttitudeResponse>> PrepareAsyncGetAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::GetAttitudeResponse>>(PrepareAsyncGetAttitudeRaw(context, request, cq)); + } class async_interface { public: virtual ~async_interface() {} @@ -191,17 +223,31 @@ class GimbalService final { virtual void ReleaseControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::ReleaseControlRequest* request, ::mavsdk::rpc::gimbal::ReleaseControlResponse* response, std::function) = 0; virtual void ReleaseControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::ReleaseControlRequest* request, ::mavsdk::rpc::gimbal::ReleaseControlResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; // + // Subscribe to list of gimbals. + // + // This allows to find out what gimbals are connected to the system. + // Based on the gimbal ID, we can then address a specific gimbal. + virtual void SubscribeGimbalList(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::gimbal::GimbalListResponse>* reactor) = 0; + // // Subscribe to control status updates. // // This allows a component to know if it has primary, secondary or // no control over the gimbal. Also, it gives the system and component ids // of the other components in control (if any). - virtual void SubscribeControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::gimbal::ControlResponse>* reactor) = 0; + virtual void SubscribeControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::gimbal::ControlStatusResponse>* reactor) = 0; + // + // Get control status for specific gimbal. + virtual void GetControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* request, ::mavsdk::rpc::gimbal::GetControlStatusResponse* response, std::function) = 0; + virtual void GetControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* request, ::mavsdk::rpc::gimbal::GetControlStatusResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; // // Subscribe to attitude updates. // // This gets you the gimbal's attitude and angular rate. virtual void SubscribeAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::gimbal::AttitudeResponse>* reactor) = 0; + // + // Get attitude for specific gimbal. + virtual void GetAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* request, ::mavsdk::rpc::gimbal::GetAttitudeResponse* response, std::function) = 0; + virtual void GetAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* request, ::mavsdk::rpc::gimbal::GetAttitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; }; typedef class async_interface experimental_async_interface; virtual class async_interface* async() { return nullptr; } @@ -217,12 +263,19 @@ class GimbalService final { virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::TakeControlResponse>* PrepareAsyncTakeControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::TakeControlRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::ReleaseControlResponse>* AsyncReleaseControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::ReleaseControlRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::ReleaseControlResponse>* PrepareAsyncReleaseControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::ReleaseControlRequest& request, ::grpc::CompletionQueue* cq) = 0; - virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::gimbal::ControlResponse>* SubscribeControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::ControlResponse>* AsyncSubscribeControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; - virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::ControlResponse>* PrepareAsyncSubscribeControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::gimbal::GimbalListResponse>* SubscribeGimbalListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::GimbalListResponse>* AsyncSubscribeGimbalListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::GimbalListResponse>* PrepareAsyncSubscribeGimbalListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::gimbal::ControlStatusResponse>* SubscribeControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::ControlStatusResponse>* AsyncSubscribeControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; + virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::ControlStatusResponse>* PrepareAsyncSubscribeControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::GetControlStatusResponse>* AsyncGetControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::GetControlStatusResponse>* PrepareAsyncGetControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientReaderInterface< ::mavsdk::rpc::gimbal::AttitudeResponse>* SubscribeAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest& request) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::AttitudeResponse>* AsyncSubscribeAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest& request, ::grpc::CompletionQueue* cq, void* tag) = 0; virtual ::grpc::ClientAsyncReaderInterface< ::mavsdk::rpc::gimbal::AttitudeResponse>* PrepareAsyncSubscribeAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::GetAttitudeResponse>* AsyncGetAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::gimbal::GetAttitudeResponse>* PrepareAsyncGetAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest& request, ::grpc::CompletionQueue* cq) = 0; }; class Stub final : public StubInterface { public: @@ -262,14 +315,30 @@ class GimbalService final { std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::ReleaseControlResponse>> PrepareAsyncReleaseControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::ReleaseControlRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::ReleaseControlResponse>>(PrepareAsyncReleaseControlRaw(context, request, cq)); } - std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::gimbal::ControlResponse>> SubscribeControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request) { - return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::gimbal::ControlResponse>>(SubscribeControlRaw(context, request)); + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::gimbal::GimbalListResponse>> SubscribeGimbalList(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::gimbal::GimbalListResponse>>(SubscribeGimbalListRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::GimbalListResponse>> AsyncSubscribeGimbalList(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::GimbalListResponse>>(AsyncSubscribeGimbalListRaw(context, request, cq, tag)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::GimbalListResponse>> PrepareAsyncSubscribeGimbalList(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::GimbalListResponse>>(PrepareAsyncSubscribeGimbalListRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::gimbal::ControlStatusResponse>> SubscribeControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request) { + return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::gimbal::ControlStatusResponse>>(SubscribeControlStatusRaw(context, request)); + } + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlStatusResponse>> AsyncSubscribeControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlStatusResponse>>(AsyncSubscribeControlStatusRaw(context, request, cq, tag)); } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlResponse>> AsyncSubscribeControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request, ::grpc::CompletionQueue* cq, void* tag) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlResponse>>(AsyncSubscribeControlRaw(context, request, cq, tag)); + std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlStatusResponse>> PrepareAsyncSubscribeControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlStatusResponse>>(PrepareAsyncSubscribeControlStatusRaw(context, request, cq)); } - std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlResponse>> PrepareAsyncSubscribeControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request, ::grpc::CompletionQueue* cq) { - return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlResponse>>(PrepareAsyncSubscribeControlRaw(context, request, cq)); + ::grpc::Status GetControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest& request, ::mavsdk::rpc::gimbal::GetControlStatusResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetControlStatusResponse>> AsyncGetControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetControlStatusResponse>>(AsyncGetControlStatusRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetControlStatusResponse>> PrepareAsyncGetControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetControlStatusResponse>>(PrepareAsyncGetControlStatusRaw(context, request, cq)); } std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::gimbal::AttitudeResponse>> SubscribeAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest& request) { return std::unique_ptr< ::grpc::ClientReader< ::mavsdk::rpc::gimbal::AttitudeResponse>>(SubscribeAttitudeRaw(context, request)); @@ -280,6 +349,13 @@ class GimbalService final { std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::AttitudeResponse>> PrepareAsyncSubscribeAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::AttitudeResponse>>(PrepareAsyncSubscribeAttitudeRaw(context, request, cq)); } + ::grpc::Status GetAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest& request, ::mavsdk::rpc::gimbal::GetAttitudeResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetAttitudeResponse>> AsyncGetAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetAttitudeResponse>>(AsyncGetAttitudeRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetAttitudeResponse>> PrepareAsyncGetAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetAttitudeResponse>>(PrepareAsyncGetAttitudeRaw(context, request, cq)); + } class async final : public StubInterface::async_interface { public: @@ -293,8 +369,13 @@ class GimbalService final { void TakeControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::TakeControlRequest* request, ::mavsdk::rpc::gimbal::TakeControlResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void ReleaseControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::ReleaseControlRequest* request, ::mavsdk::rpc::gimbal::ReleaseControlResponse* response, std::function) override; void ReleaseControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::ReleaseControlRequest* request, ::mavsdk::rpc::gimbal::ReleaseControlResponse* response, ::grpc::ClientUnaryReactor* reactor) override; - void SubscribeControl(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::gimbal::ControlResponse>* reactor) override; + void SubscribeGimbalList(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::gimbal::GimbalListResponse>* reactor) override; + void SubscribeControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::gimbal::ControlStatusResponse>* reactor) override; + void GetControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* request, ::mavsdk::rpc::gimbal::GetControlStatusResponse* response, std::function) override; + void GetControlStatus(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* request, ::mavsdk::rpc::gimbal::GetControlStatusResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void SubscribeAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest* request, ::grpc::ClientReadReactor< ::mavsdk::rpc::gimbal::AttitudeResponse>* reactor) override; + void GetAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* request, ::mavsdk::rpc::gimbal::GetAttitudeResponse* response, std::function) override; + void GetAttitude(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* request, ::mavsdk::rpc::gimbal::GetAttitudeResponse* response, ::grpc::ClientUnaryReactor* reactor) override; private: friend class Stub; explicit async(Stub* stub): stub_(stub) { } @@ -316,19 +397,29 @@ class GimbalService final { ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::TakeControlResponse>* PrepareAsyncTakeControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::TakeControlRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::ReleaseControlResponse>* AsyncReleaseControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::ReleaseControlRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::ReleaseControlResponse>* PrepareAsyncReleaseControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::ReleaseControlRequest& request, ::grpc::CompletionQueue* cq) override; - ::grpc::ClientReader< ::mavsdk::rpc::gimbal::ControlResponse>* SubscribeControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlResponse>* AsyncSubscribeControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; - ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlResponse>* PrepareAsyncSubscribeControlRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::gimbal::GimbalListResponse>* SubscribeGimbalListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::GimbalListResponse>* AsyncSubscribeGimbalListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::GimbalListResponse>* PrepareAsyncSubscribeGimbalListRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientReader< ::mavsdk::rpc::gimbal::ControlStatusResponse>* SubscribeControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlStatusResponse>* AsyncSubscribeControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; + ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::ControlStatusResponse>* PrepareAsyncSubscribeControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetControlStatusResponse>* AsyncGetControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetControlStatusResponse>* PrepareAsyncGetControlStatusRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientReader< ::mavsdk::rpc::gimbal::AttitudeResponse>* SubscribeAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::AttitudeResponse>* AsyncSubscribeAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::gimbal::AttitudeResponse>* PrepareAsyncSubscribeAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetAttitudeResponse>* AsyncGetAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::gimbal::GetAttitudeResponse>* PrepareAsyncGetAttitudeRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest& request, ::grpc::CompletionQueue* cq) override; const ::grpc::internal::RpcMethod rpcmethod_SetAngles_; const ::grpc::internal::RpcMethod rpcmethod_SetAngularRates_; const ::grpc::internal::RpcMethod rpcmethod_SetRoiLocation_; const ::grpc::internal::RpcMethod rpcmethod_TakeControl_; const ::grpc::internal::RpcMethod rpcmethod_ReleaseControl_; - const ::grpc::internal::RpcMethod rpcmethod_SubscribeControl_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeGimbalList_; + const ::grpc::internal::RpcMethod rpcmethod_SubscribeControlStatus_; + const ::grpc::internal::RpcMethod rpcmethod_GetControlStatus_; const ::grpc::internal::RpcMethod rpcmethod_SubscribeAttitude_; + const ::grpc::internal::RpcMethod rpcmethod_GetAttitude_; }; static std::unique_ptr NewStub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); @@ -380,17 +471,29 @@ class GimbalService final { // Release control, such that other components can control the gimbal. virtual ::grpc::Status ReleaseControl(::grpc::ServerContext* context, const ::mavsdk::rpc::gimbal::ReleaseControlRequest* request, ::mavsdk::rpc::gimbal::ReleaseControlResponse* response); // + // Subscribe to list of gimbals. + // + // This allows to find out what gimbals are connected to the system. + // Based on the gimbal ID, we can then address a specific gimbal. + virtual ::grpc::Status SubscribeGimbalList(::grpc::ServerContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::GimbalListResponse>* writer); + // // Subscribe to control status updates. // // This allows a component to know if it has primary, secondary or // no control over the gimbal. Also, it gives the system and component ids // of the other components in control (if any). - virtual ::grpc::Status SubscribeControl(::grpc::ServerContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlResponse>* writer); + virtual ::grpc::Status SubscribeControlStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlStatusResponse>* writer); + // + // Get control status for specific gimbal. + virtual ::grpc::Status GetControlStatus(::grpc::ServerContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* request, ::mavsdk::rpc::gimbal::GetControlStatusResponse* response); // // Subscribe to attitude updates. // // This gets you the gimbal's attitude and angular rate. virtual ::grpc::Status SubscribeAttitude(::grpc::ServerContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::AttitudeResponse>* writer); + // + // Get attitude for specific gimbal. + virtual ::grpc::Status GetAttitude(::grpc::ServerContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* request, ::mavsdk::rpc::gimbal::GetAttitudeResponse* response); }; template class WithAsyncMethod_SetAngles : public BaseClass { @@ -493,32 +596,72 @@ class GimbalService final { } }; template - class WithAsyncMethod_SubscribeControl : public BaseClass { + class WithAsyncMethod_SubscribeGimbalList : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithAsyncMethod_SubscribeControl() { + WithAsyncMethod_SubscribeGimbalList() { ::grpc::Service::MarkMethodAsync(5); } - ~WithAsyncMethod_SubscribeControl() override { + ~WithAsyncMethod_SubscribeGimbalList() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribeControl(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeControlRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlResponse>* /*writer*/) override { + ::grpc::Status SubscribeGimbalList(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::GimbalListResponse>* /*writer*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - void RequestSubscribeControl(::grpc::ServerContext* context, ::mavsdk::rpc::gimbal::SubscribeControlRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::gimbal::ControlResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + void RequestSubscribeGimbalList(::grpc::ServerContext* context, ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::gimbal::GimbalListResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { ::grpc::Service::RequestAsyncServerStreaming(5, context, request, writer, new_call_cq, notification_cq, tag); } }; template + class WithAsyncMethod_SubscribeControlStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SubscribeControlStatus() { + ::grpc::Service::MarkMethodAsync(6); + } + ~WithAsyncMethod_SubscribeControlStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeControlStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlStatusResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeControlStatus(::grpc::ServerContext* context, ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::gimbal::ControlStatusResponse>* 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_GetControlStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_GetControlStatus() { + ::grpc::Service::MarkMethodAsync(7); + } + ~WithAsyncMethod_GetControlStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetControlStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* /*request*/, ::mavsdk::rpc::gimbal::GetControlStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetControlStatus(::grpc::ServerContext* context, ::mavsdk::rpc::gimbal::GetControlStatusRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::gimbal::GetControlStatusResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(7, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithAsyncMethod_SubscribeAttitude : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeAttitude() { - ::grpc::Service::MarkMethodAsync(6); + ::grpc::Service::MarkMethodAsync(8); } ~WithAsyncMethod_SubscribeAttitude() override { BaseClassMustBeDerivedFromService(this); @@ -529,10 +672,30 @@ class GimbalService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeAttitude(::grpc::ServerContext* context, ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::gimbal::AttitudeResponse>* 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(8, context, request, writer, new_call_cq, notification_cq, tag); } }; - typedef WithAsyncMethod_SetAngles > > > > > > AsyncService; + template + class WithAsyncMethod_GetAttitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_GetAttitude() { + ::grpc::Service::MarkMethodAsync(9); + } + ~WithAsyncMethod_GetAttitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* /*request*/, ::mavsdk::rpc::gimbal::GetAttitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetAttitude(::grpc::ServerContext* context, ::mavsdk::rpc::gimbal::GetAttitudeRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::gimbal::GetAttitudeResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(9, context, request, response, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_SetAngles > > > > > > > > > AsyncService; template class WithCallbackMethod_SetAngles : public BaseClass { private: @@ -669,26 +832,75 @@ class GimbalService final { ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::gimbal::ReleaseControlRequest* /*request*/, ::mavsdk::rpc::gimbal::ReleaseControlResponse* /*response*/) { return nullptr; } }; template - class WithCallbackMethod_SubscribeControl : public BaseClass { + class WithCallbackMethod_SubscribeGimbalList : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithCallbackMethod_SubscribeControl() { + WithCallbackMethod_SubscribeGimbalList() { ::grpc::Service::MarkMethodCallback(5, - new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::gimbal::SubscribeControlRequest, ::mavsdk::rpc::gimbal::ControlResponse>( + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest, ::mavsdk::rpc::gimbal::GimbalListResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* request) { return this->SubscribeGimbalList(context, request); })); + } + ~WithCallbackMethod_SubscribeGimbalList() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeGimbalList(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::GimbalListResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::gimbal::GimbalListResponse>* SubscribeGimbalList( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_SubscribeControlStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SubscribeControlStatus() { + ::grpc::Service::MarkMethodCallback(6, + new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest, ::mavsdk::rpc::gimbal::ControlStatusResponse>( [this]( - ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlRequest* request) { return this->SubscribeControl(context, request); })); + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* request) { return this->SubscribeControlStatus(context, request); })); } - ~WithCallbackMethod_SubscribeControl() override { + ~WithCallbackMethod_SubscribeControlStatus() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribeControl(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeControlRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlResponse>* /*writer*/) override { + ::grpc::Status SubscribeControlStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlStatusResponse>* /*writer*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::gimbal::ControlResponse>* SubscribeControl( - ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeControlRequest* /*request*/) { return nullptr; } + virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::gimbal::ControlStatusResponse>* SubscribeControlStatus( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* /*request*/) { return nullptr; } + }; + template + class WithCallbackMethod_GetControlStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_GetControlStatus() { + ::grpc::Service::MarkMethodCallback(7, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::gimbal::GetControlStatusRequest, ::mavsdk::rpc::gimbal::GetControlStatusResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* request, ::mavsdk::rpc::gimbal::GetControlStatusResponse* response) { return this->GetControlStatus(context, request, response); }));} + void SetMessageAllocatorFor_GetControlStatus( + ::grpc::MessageAllocator< ::mavsdk::rpc::gimbal::GetControlStatusRequest, ::mavsdk::rpc::gimbal::GetControlStatusResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(7); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::gimbal::GetControlStatusRequest, ::mavsdk::rpc::gimbal::GetControlStatusResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_GetControlStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetControlStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* /*request*/, ::mavsdk::rpc::gimbal::GetControlStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetControlStatus( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* /*request*/, ::mavsdk::rpc::gimbal::GetControlStatusResponse* /*response*/) { return nullptr; } }; template class WithCallbackMethod_SubscribeAttitude : public BaseClass { @@ -696,7 +908,7 @@ class GimbalService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeAttitude() { - ::grpc::Service::MarkMethodCallback(6, + ::grpc::Service::MarkMethodCallback(8, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest, ::mavsdk::rpc::gimbal::AttitudeResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest* request) { return this->SubscribeAttitude(context, request); })); @@ -712,7 +924,34 @@ class GimbalService final { virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::gimbal::AttitudeResponse>* SubscribeAttitude( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest* /*request*/) { return nullptr; } }; - typedef WithCallbackMethod_SetAngles > > > > > > CallbackService; + template + class WithCallbackMethod_GetAttitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_GetAttitude() { + ::grpc::Service::MarkMethodCallback(9, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::gimbal::GetAttitudeRequest, ::mavsdk::rpc::gimbal::GetAttitudeResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* request, ::mavsdk::rpc::gimbal::GetAttitudeResponse* response) { return this->GetAttitude(context, request, response); }));} + void SetMessageAllocatorFor_GetAttitude( + ::grpc::MessageAllocator< ::mavsdk::rpc::gimbal::GetAttitudeRequest, ::mavsdk::rpc::gimbal::GetAttitudeResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(9); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::gimbal::GetAttitudeRequest, ::mavsdk::rpc::gimbal::GetAttitudeResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_GetAttitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* /*request*/, ::mavsdk::rpc::gimbal::GetAttitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetAttitude( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* /*request*/, ::mavsdk::rpc::gimbal::GetAttitudeResponse* /*response*/) { return nullptr; } + }; + typedef WithCallbackMethod_SetAngles > > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template class WithGenericMethod_SetAngles : public BaseClass { @@ -800,18 +1039,52 @@ class GimbalService final { } }; template - class WithGenericMethod_SubscribeControl : public BaseClass { + class WithGenericMethod_SubscribeGimbalList : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithGenericMethod_SubscribeControl() { + WithGenericMethod_SubscribeGimbalList() { ::grpc::Service::MarkMethodGeneric(5); } - ~WithGenericMethod_SubscribeControl() override { + ~WithGenericMethod_SubscribeGimbalList() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribeControl(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeControlRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlResponse>* /*writer*/) override { + ::grpc::Status SubscribeGimbalList(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::GimbalListResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_SubscribeControlStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SubscribeControlStatus() { + ::grpc::Service::MarkMethodGeneric(6); + } + ~WithGenericMethod_SubscribeControlStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeControlStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlStatusResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template + class WithGenericMethod_GetControlStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_GetControlStatus() { + ::grpc::Service::MarkMethodGeneric(7); + } + ~WithGenericMethod_GetControlStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetControlStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* /*request*/, ::mavsdk::rpc::gimbal::GetControlStatusResponse* /*response*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } @@ -822,7 +1095,7 @@ class GimbalService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeAttitude() { - ::grpc::Service::MarkMethodGeneric(6); + ::grpc::Service::MarkMethodGeneric(8); } ~WithGenericMethod_SubscribeAttitude() override { BaseClassMustBeDerivedFromService(this); @@ -834,6 +1107,23 @@ class GimbalService final { } }; template + class WithGenericMethod_GetAttitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_GetAttitude() { + ::grpc::Service::MarkMethodGeneric(9); + } + ~WithGenericMethod_GetAttitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* /*request*/, ::mavsdk::rpc::gimbal::GetAttitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithRawMethod_SetAngles : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -934,32 +1224,72 @@ class GimbalService final { } }; template - class WithRawMethod_SubscribeControl : public BaseClass { + class WithRawMethod_SubscribeGimbalList : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawMethod_SubscribeControl() { + WithRawMethod_SubscribeGimbalList() { ::grpc::Service::MarkMethodRaw(5); } - ~WithRawMethod_SubscribeControl() override { + ~WithRawMethod_SubscribeGimbalList() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribeControl(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeControlRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlResponse>* /*writer*/) override { + ::grpc::Status SubscribeGimbalList(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::GimbalListResponse>* /*writer*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - void RequestSubscribeControl(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + void RequestSubscribeGimbalList(::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(5, context, request, writer, new_call_cq, notification_cq, tag); } }; template + class WithRawMethod_SubscribeControlStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SubscribeControlStatus() { + ::grpc::Service::MarkMethodRaw(6); + } + ~WithRawMethod_SubscribeControlStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeControlStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlStatusResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSubscribeControlStatus(::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_GetControlStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_GetControlStatus() { + ::grpc::Service::MarkMethodRaw(7); + } + ~WithRawMethod_GetControlStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetControlStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* /*request*/, ::mavsdk::rpc::gimbal::GetControlStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetControlStatus(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(7, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithRawMethod_SubscribeAttitude : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeAttitude() { - ::grpc::Service::MarkMethodRaw(6); + ::grpc::Service::MarkMethodRaw(8); } ~WithRawMethod_SubscribeAttitude() override { BaseClassMustBeDerivedFromService(this); @@ -970,7 +1300,27 @@ class GimbalService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeAttitude(::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(8, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawMethod_GetAttitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_GetAttitude() { + ::grpc::Service::MarkMethodRaw(9); + } + ~WithRawMethod_GetAttitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* /*request*/, ::mavsdk::rpc::gimbal::GetAttitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestGetAttitude(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncResponseWriter< ::grpc::ByteBuffer>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(9, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1084,34 +1434,78 @@ class GimbalService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template - class WithRawCallbackMethod_SubscribeControl : public BaseClass { + class WithRawCallbackMethod_SubscribeGimbalList : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithRawCallbackMethod_SubscribeControl() { + WithRawCallbackMethod_SubscribeGimbalList() { ::grpc::Service::MarkMethodRawCallback(5, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( - ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeControl(context, request); })); + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeGimbalList(context, request); })); } - ~WithRawCallbackMethod_SubscribeControl() override { + ~WithRawCallbackMethod_SubscribeGimbalList() override { BaseClassMustBeDerivedFromService(this); } // disable synchronous version of this method - ::grpc::Status SubscribeControl(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeControlRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlResponse>* /*writer*/) override { + ::grpc::Status SubscribeGimbalList(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::GimbalListResponse>* /*writer*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } - virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeControl( + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeGimbalList( ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_SubscribeControlStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SubscribeControlStatus() { + ::grpc::Service::MarkMethodRawCallback(6, + new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeControlStatus(context, request); })); + } + ~WithRawCallbackMethod_SubscribeControlStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SubscribeControlStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlStatusResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerWriteReactor< ::grpc::ByteBuffer>* SubscribeControlStatus( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } + }; + template + class WithRawCallbackMethod_GetControlStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_GetControlStatus() { + ::grpc::Service::MarkMethodRawCallback(7, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->GetControlStatus(context, request, response); })); + } + ~WithRawCallbackMethod_GetControlStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetControlStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* /*request*/, ::mavsdk::rpc::gimbal::GetControlStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetControlStatus( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithRawCallbackMethod_SubscribeAttitude : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeAttitude() { - ::grpc::Service::MarkMethodRawCallback(6, + ::grpc::Service::MarkMethodRawCallback(8, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeAttitude(context, request); })); @@ -1128,6 +1522,28 @@ class GimbalService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithRawCallbackMethod_GetAttitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_GetAttitude() { + ::grpc::Service::MarkMethodRawCallback(9, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->GetAttitude(context, request, response); })); + } + ~WithRawCallbackMethod_GetAttitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status GetAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* /*request*/, ::mavsdk::rpc::gimbal::GetAttitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* GetAttitude( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } + }; + template class WithStreamedUnaryMethod_SetAngles : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} @@ -1262,33 +1678,114 @@ class GimbalService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedReleaseControl(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::gimbal::ReleaseControlRequest,::mavsdk::rpc::gimbal::ReleaseControlResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_SetAngles > > > > StreamedUnaryService; template - class WithSplitStreamingMethod_SubscribeControl : public BaseClass { + class WithStreamedUnaryMethod_GetControlStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_GetControlStatus() { + ::grpc::Service::MarkMethodStreamed(7, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::gimbal::GetControlStatusRequest, ::mavsdk::rpc::gimbal::GetControlStatusResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::gimbal::GetControlStatusRequest, ::mavsdk::rpc::gimbal::GetControlStatusResponse>* streamer) { + return this->StreamedGetControlStatus(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_GetControlStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status GetControlStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::GetControlStatusRequest* /*request*/, ::mavsdk::rpc::gimbal::GetControlStatusResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedGetControlStatus(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::gimbal::GetControlStatusRequest,::mavsdk::rpc::gimbal::GetControlStatusResponse>* server_unary_streamer) = 0; + }; + template + class WithStreamedUnaryMethod_GetAttitude : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_GetAttitude() { + ::grpc::Service::MarkMethodStreamed(9, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::gimbal::GetAttitudeRequest, ::mavsdk::rpc::gimbal::GetAttitudeResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::gimbal::GetAttitudeRequest, ::mavsdk::rpc::gimbal::GetAttitudeResponse>* streamer) { + return this->StreamedGetAttitude(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_GetAttitude() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status GetAttitude(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::GetAttitudeRequest* /*request*/, ::mavsdk::rpc::gimbal::GetAttitudeResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedGetAttitude(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::gimbal::GetAttitudeRequest,::mavsdk::rpc::gimbal::GetAttitudeResponse>* server_unary_streamer) = 0; + }; + typedef WithStreamedUnaryMethod_SetAngles > > > > > > StreamedUnaryService; + template + class WithSplitStreamingMethod_SubscribeGimbalList : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: - WithSplitStreamingMethod_SubscribeControl() { + WithSplitStreamingMethod_SubscribeGimbalList() { ::grpc::Service::MarkMethodStreamed(5, new ::grpc::internal::SplitServerStreamingHandler< - ::mavsdk::rpc::gimbal::SubscribeControlRequest, ::mavsdk::rpc::gimbal::ControlResponse>( + ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest, ::mavsdk::rpc::gimbal::GimbalListResponse>( [this](::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< - ::mavsdk::rpc::gimbal::SubscribeControlRequest, ::mavsdk::rpc::gimbal::ControlResponse>* streamer) { - return this->StreamedSubscribeControl(context, + ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest, ::mavsdk::rpc::gimbal::GimbalListResponse>* streamer) { + return this->StreamedSubscribeGimbalList(context, streamer); })); } - ~WithSplitStreamingMethod_SubscribeControl() override { + ~WithSplitStreamingMethod_SubscribeGimbalList() override { BaseClassMustBeDerivedFromService(this); } // disable regular version of this method - ::grpc::Status SubscribeControl(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeControlRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlResponse>* /*writer*/) override { + ::grpc::Status SubscribeGimbalList(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::GimbalListResponse>* /*writer*/) override { abort(); return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } // replace default version of method with split streamed - virtual ::grpc::Status StreamedSubscribeControl(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::gimbal::SubscribeControlRequest,::mavsdk::rpc::gimbal::ControlResponse>* server_split_streamer) = 0; + virtual ::grpc::Status StreamedSubscribeGimbalList(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::gimbal::SubscribeGimbalListRequest,::mavsdk::rpc::gimbal::GimbalListResponse>* server_split_streamer) = 0; + }; + template + class WithSplitStreamingMethod_SubscribeControlStatus : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithSplitStreamingMethod_SubscribeControlStatus() { + ::grpc::Service::MarkMethodStreamed(6, + new ::grpc::internal::SplitServerStreamingHandler< + ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest, ::mavsdk::rpc::gimbal::ControlStatusResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerSplitStreamer< + ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest, ::mavsdk::rpc::gimbal::ControlStatusResponse>* streamer) { + return this->StreamedSubscribeControlStatus(context, + streamer); + })); + } + ~WithSplitStreamingMethod_SubscribeControlStatus() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SubscribeControlStatus(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest* /*request*/, ::grpc::ServerWriter< ::mavsdk::rpc::gimbal::ControlStatusResponse>* /*writer*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with split streamed + virtual ::grpc::Status StreamedSubscribeControlStatus(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::gimbal::SubscribeControlStatusRequest,::mavsdk::rpc::gimbal::ControlStatusResponse>* server_split_streamer) = 0; }; template class WithSplitStreamingMethod_SubscribeAttitude : public BaseClass { @@ -1296,7 +1793,7 @@ class GimbalService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeAttitude() { - ::grpc::Service::MarkMethodStreamed(6, + ::grpc::Service::MarkMethodStreamed(8, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest, ::mavsdk::rpc::gimbal::AttitudeResponse>( [this](::grpc::ServerContext* context, @@ -1317,8 +1814,8 @@ class GimbalService final { // replace default version of method with split streamed virtual ::grpc::Status StreamedSubscribeAttitude(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::gimbal::SubscribeAttitudeRequest,::mavsdk::rpc::gimbal::AttitudeResponse>* server_split_streamer) = 0; }; - typedef WithSplitStreamingMethod_SubscribeControl > SplitStreamedService; - typedef WithStreamedUnaryMethod_SetAngles > > > > > > StreamedService; + typedef WithSplitStreamingMethod_SubscribeGimbalList > > SplitStreamedService; + typedef WithStreamedUnaryMethod_SetAngles > > > > > > > > > StreamedService; }; } // namespace gimbal diff --git a/src/mavsdk_server/src/generated/gimbal/gimbal.pb.cc b/src/mavsdk_server/src/generated/gimbal/gimbal.pb.cc index 0fb7c6b56e..af49811e56 100644 --- a/src/mavsdk_server/src/generated/gimbal/gimbal.pb.cc +++ b/src/mavsdk_server/src/generated/gimbal/gimbal.pb.cc @@ -26,7 +26,8 @@ namespace gimbal { inline constexpr TakeControlRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : control_mode_{static_cast< ::mavsdk::rpc::gimbal::ControlMode >(0)}, + : gimbal_id_{0}, + control_mode_{static_cast< ::mavsdk::rpc::gimbal::ControlMode >(0)}, _cached_size_{0} {} template @@ -43,17 +44,29 @@ struct TakeControlRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 TakeControlRequestDefaultTypeInternal _TakeControlRequest_default_instance_; template -PROTOBUF_CONSTEXPR SubscribeControlRequest::SubscribeControlRequest(::_pbi::ConstantInitialized) {} -struct SubscribeControlRequestDefaultTypeInternal { - PROTOBUF_CONSTEXPR SubscribeControlRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~SubscribeControlRequestDefaultTypeInternal() {} +PROTOBUF_CONSTEXPR SubscribeGimbalListRequest::SubscribeGimbalListRequest(::_pbi::ConstantInitialized) {} +struct SubscribeGimbalListRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeGimbalListRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeGimbalListRequestDefaultTypeInternal() {} union { - SubscribeControlRequest _instance; + SubscribeGimbalListRequest _instance; }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeControlRequestDefaultTypeInternal _SubscribeControlRequest_default_instance_; + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeGimbalListRequestDefaultTypeInternal _SubscribeGimbalListRequest_default_instance_; + template +PROTOBUF_CONSTEXPR SubscribeControlStatusRequest::SubscribeControlStatusRequest(::_pbi::ConstantInitialized) {} +struct SubscribeControlStatusRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SubscribeControlStatusRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SubscribeControlStatusRequestDefaultTypeInternal() {} + union { + SubscribeControlStatusRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeControlStatusRequestDefaultTypeInternal _SubscribeControlStatusRequest_default_instance_; template PROTOBUF_CONSTEXPR SubscribeAttitudeRequest::SubscribeAttitudeRequest(::_pbi::ConstantInitialized) {} struct SubscribeAttitudeRequestDefaultTypeInternal { @@ -70,8 +83,9 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr SetRoiLocationRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : latitude_deg_{0}, - longitude_deg_{0}, + gimbal_id_{0}, altitude_m_{0}, + longitude_deg_{0}, _cached_size_{0} {} template @@ -90,7 +104,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr SetAngularRatesRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : roll_rate_deg_s_{0}, + : gimbal_id_{0}, + roll_rate_deg_s_{0}, pitch_rate_deg_s_{0}, yaw_rate_deg_s_{0}, gimbal_mode_{static_cast< ::mavsdk::rpc::gimbal::GimbalMode >(0)}, @@ -113,7 +128,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr SetAnglesRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : roll_deg_{0}, + : gimbal_id_{0}, + roll_deg_{0}, pitch_deg_{0}, yaw_deg_{0}, gimbal_mode_{static_cast< ::mavsdk::rpc::gimbal::GimbalMode >(0)}, @@ -133,8 +149,15 @@ struct SetAnglesRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetAnglesRequestDefaultTypeInternal _SetAnglesRequest_default_instance_; - template -PROTOBUF_CONSTEXPR ReleaseControlRequest::ReleaseControlRequest(::_pbi::ConstantInitialized) {} + +inline constexpr ReleaseControlRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : gimbal_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR ReleaseControlRequest::ReleaseControlRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} struct ReleaseControlRequestDefaultTypeInternal { PROTOBUF_CONSTEXPR ReleaseControlRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} ~ReleaseControlRequestDefaultTypeInternal() {} @@ -190,6 +213,74 @@ struct GimbalResultDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GimbalResultDefaultTypeInternal _GimbalResult_default_instance_; +inline constexpr GimbalItem::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : vendor_name_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + model_name_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + custom_name_( + &::google::protobuf::internal::fixed_address_empty_string, + ::_pbi::ConstantInitialized()), + gimbal_id_{0}, + gimbal_manager_component_id_{0}, + gimbal_device_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR GimbalItem::GimbalItem(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GimbalItemDefaultTypeInternal { + PROTOBUF_CONSTEXPR GimbalItemDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GimbalItemDefaultTypeInternal() {} + union { + GimbalItem _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GimbalItemDefaultTypeInternal _GimbalItem_default_instance_; + +inline constexpr GetControlStatusRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : gimbal_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR GetControlStatusRequest::GetControlStatusRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetControlStatusRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetControlStatusRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetControlStatusRequestDefaultTypeInternal() {} + union { + GetControlStatusRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetControlStatusRequestDefaultTypeInternal _GetControlStatusRequest_default_instance_; + +inline constexpr GetAttitudeRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : gimbal_id_{0}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR GetAttitudeRequest::GetAttitudeRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetAttitudeRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetAttitudeRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetAttitudeRequestDefaultTypeInternal() {} + union { + GetAttitudeRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetAttitudeRequestDefaultTypeInternal _GetAttitudeRequest_default_instance_; + inline constexpr EulerAngle::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : roll_deg_{0}, @@ -213,7 +304,8 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr ControlStatus::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept - : control_mode_{static_cast< ::mavsdk::rpc::gimbal::ControlMode >(0)}, + : gimbal_id_{0}, + control_mode_{static_cast< ::mavsdk::rpc::gimbal::ControlMode >(0)}, sysid_primary_control_{0}, compid_primary_control_{0}, sysid_secondary_control_{0}, @@ -350,24 +442,63 @@ struct ReleaseControlResponseDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ReleaseControlResponseDefaultTypeInternal _ReleaseControlResponse_default_instance_; -inline constexpr ControlResponse::Impl_::Impl_( +inline constexpr GimbalList::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : gimbals_{}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR GimbalList::GimbalList(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GimbalListDefaultTypeInternal { + PROTOBUF_CONSTEXPR GimbalListDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GimbalListDefaultTypeInternal() {} + union { + GimbalList _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GimbalListDefaultTypeInternal _GimbalList_default_instance_; + +inline constexpr GetControlStatusResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + gimbal_result_{nullptr}, + control_status_{nullptr} {} + +template +PROTOBUF_CONSTEXPR GetControlStatusResponse::GetControlStatusResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetControlStatusResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetControlStatusResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetControlStatusResponseDefaultTypeInternal() {} + union { + GetControlStatusResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetControlStatusResponseDefaultTypeInternal _GetControlStatusResponse_default_instance_; + +inline constexpr ControlStatusResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, control_status_{nullptr} {} template -PROTOBUF_CONSTEXPR ControlResponse::ControlResponse(::_pbi::ConstantInitialized) +PROTOBUF_CONSTEXPR ControlStatusResponse::ControlStatusResponse(::_pbi::ConstantInitialized) : _impl_(::_pbi::ConstantInitialized()) {} -struct ControlResponseDefaultTypeInternal { - PROTOBUF_CONSTEXPR ControlResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} - ~ControlResponseDefaultTypeInternal() {} +struct ControlStatusResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR ControlStatusResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~ControlStatusResponseDefaultTypeInternal() {} union { - ControlResponse _instance; + ControlStatusResponse _instance; }; }; PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT - PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ControlResponseDefaultTypeInternal _ControlResponse_default_instance_; + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 ControlStatusResponseDefaultTypeInternal _ControlStatusResponse_default_instance_; inline constexpr Attitude::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept @@ -377,7 +508,8 @@ inline constexpr Attitude::Impl_::Impl_( euler_angle_north_{nullptr}, quaternion_north_{nullptr}, angular_velocity_{nullptr}, - timestamp_us_{::uint64_t{0u}} {} + timestamp_us_{::uint64_t{0u}}, + gimbal_id_{0} {} template PROTOBUF_CONSTEXPR Attitude::Attitude(::_pbi::ConstantInitialized) @@ -393,6 +525,45 @@ struct AttitudeDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 AttitudeDefaultTypeInternal _Attitude_default_instance_; +inline constexpr GimbalListResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + gimbal_list_{nullptr} {} + +template +PROTOBUF_CONSTEXPR GimbalListResponse::GimbalListResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GimbalListResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR GimbalListResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GimbalListResponseDefaultTypeInternal() {} + union { + GimbalListResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GimbalListResponseDefaultTypeInternal _GimbalListResponse_default_instance_; + +inline constexpr GetAttitudeResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + gimbal_result_{nullptr}, + attitude_{nullptr} {} + +template +PROTOBUF_CONSTEXPR GetAttitudeResponse::GetAttitudeResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct GetAttitudeResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR GetAttitudeResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~GetAttitudeResponseDefaultTypeInternal() {} + union { + GetAttitudeResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 GetAttitudeResponseDefaultTypeInternal _GetAttitudeResponse_default_instance_; + inline constexpr AttitudeResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -414,7 +585,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace gimbal } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_gimbal_2fgimbal_2eproto[20]; +static ::_pb::Metadata file_level_metadata_gimbal_2fgimbal_2eproto[28]; static const ::_pb::EnumDescriptor* file_level_enum_descriptors_gimbal_2fgimbal_2eproto[4]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_gimbal_2fgimbal_2eproto = nullptr; @@ -428,6 +599,7 @@ const ::uint32_t TableStruct_gimbal_2fgimbal_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SetAnglesRequest, _impl_.gimbal_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SetAnglesRequest, _impl_.roll_deg_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SetAnglesRequest, _impl_.pitch_deg_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SetAnglesRequest, _impl_.yaw_deg_), @@ -451,6 +623,7 @@ const ::uint32_t TableStruct_gimbal_2fgimbal_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SetAngularRatesRequest, _impl_.gimbal_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SetAngularRatesRequest, _impl_.roll_rate_deg_s_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SetAngularRatesRequest, _impl_.pitch_rate_deg_s_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SetAngularRatesRequest, _impl_.yaw_rate_deg_s_), @@ -474,6 +647,7 @@ const ::uint32_t TableStruct_gimbal_2fgimbal_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SetRoiLocationRequest, _impl_.gimbal_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SetRoiLocationRequest, _impl_.latitude_deg_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SetRoiLocationRequest, _impl_.longitude_deg_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SetRoiLocationRequest, _impl_.altitude_m_), @@ -495,6 +669,7 @@ const ::uint32_t TableStruct_gimbal_2fgimbal_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::TakeControlRequest, _impl_.gimbal_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::TakeControlRequest, _impl_.control_mode_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::TakeControlResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::TakeControlResponse, _internal_metadata_), @@ -514,6 +689,7 @@ const ::uint32_t TableStruct_gimbal_2fgimbal_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ReleaseControlRequest, _impl_.gimbal_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ReleaseControlResponse, _impl_._has_bits_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ReleaseControlResponse, _internal_metadata_), ~0u, // no _extensions_ @@ -525,23 +701,44 @@ const ::uint32_t TableStruct_gimbal_2fgimbal_2eproto::offsets[] PROTOBUF_SECTION PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ReleaseControlResponse, _impl_.gimbal_result_), 0, ~0u, // no _has_bits_ - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SubscribeControlRequest, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SubscribeControlStatusRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ControlStatusResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ControlStatusResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ControlStatusResponse, _impl_.control_status_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GetControlStatusRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ ~0u, // no _weak_field_map_ ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ControlResponse, _impl_._has_bits_), - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ControlResponse, _internal_metadata_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GetControlStatusRequest, _impl_.gimbal_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GetControlStatusResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GetControlStatusResponse, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ ~0u, // no _weak_field_map_ ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ControlResponse, _impl_.control_status_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GetControlStatusResponse, _impl_.gimbal_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GetControlStatusResponse, _impl_.control_status_), 0, + 1, ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::Quaternion, _internal_metadata_), ~0u, // no _extensions_ @@ -584,12 +781,14 @@ const ::uint32_t TableStruct_gimbal_2fgimbal_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::Attitude, _impl_.gimbal_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::Attitude, _impl_.euler_angle_forward_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::Attitude, _impl_.quaternion_forward_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::Attitude, _impl_.euler_angle_north_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::Attitude, _impl_.quaternion_north_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::Attitude, _impl_.angular_velocity_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::Attitude, _impl_.timestamp_us_), + ~0u, 0, 1, 2, @@ -615,6 +814,68 @@ const ::uint32_t TableStruct_gimbal_2fgimbal_2eproto::offsets[] PROTOBUF_SECTION PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::AttitudeResponse, _impl_.attitude_), 0, ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GetAttitudeRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GetAttitudeRequest, _impl_.gimbal_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GetAttitudeResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GetAttitudeResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GetAttitudeResponse, _impl_.gimbal_result_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GetAttitudeResponse, _impl_.attitude_), + 0, + 1, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::SubscribeGimbalListRequest, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GimbalListResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GimbalListResponse, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GimbalListResponse, _impl_.gimbal_list_), + 0, + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GimbalItem, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GimbalItem, _impl_.gimbal_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GimbalItem, _impl_.vendor_name_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GimbalItem, _impl_.model_name_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GimbalItem, _impl_.custom_name_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GimbalItem, _impl_.gimbal_manager_component_id_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GimbalItem, _impl_.gimbal_device_id_), + ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GimbalList, _internal_metadata_), + ~0u, // no _extensions_ + ~0u, // no _oneof_case_ + ~0u, // no _weak_field_map_ + ~0u, // no _inlined_string_donated_ + ~0u, // no _split_ + ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::GimbalList, _impl_.gimbals_), + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ControlStatus, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -622,6 +883,7 @@ const ::uint32_t TableStruct_gimbal_2fgimbal_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ControlStatus, _impl_.gimbal_id_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ControlStatus, _impl_.control_mode_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ControlStatus, _impl_.sysid_primary_control_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::gimbal::ControlStatus, _impl_.compid_primary_control_), @@ -642,25 +904,33 @@ const ::uint32_t TableStruct_gimbal_2fgimbal_2eproto::offsets[] PROTOBUF_SECTION static const ::_pbi::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { {0, -1, -1, sizeof(::mavsdk::rpc::gimbal::SetAnglesRequest)}, - {13, 22, -1, sizeof(::mavsdk::rpc::gimbal::SetAnglesResponse)}, - {23, -1, -1, sizeof(::mavsdk::rpc::gimbal::SetAngularRatesRequest)}, - {36, 45, -1, sizeof(::mavsdk::rpc::gimbal::SetAngularRatesResponse)}, - {46, -1, -1, sizeof(::mavsdk::rpc::gimbal::SetRoiLocationRequest)}, - {57, 66, -1, sizeof(::mavsdk::rpc::gimbal::SetRoiLocationResponse)}, - {67, -1, -1, sizeof(::mavsdk::rpc::gimbal::TakeControlRequest)}, - {76, 85, -1, sizeof(::mavsdk::rpc::gimbal::TakeControlResponse)}, - {86, -1, -1, sizeof(::mavsdk::rpc::gimbal::ReleaseControlRequest)}, - {94, 103, -1, sizeof(::mavsdk::rpc::gimbal::ReleaseControlResponse)}, - {104, -1, -1, sizeof(::mavsdk::rpc::gimbal::SubscribeControlRequest)}, - {112, 121, -1, sizeof(::mavsdk::rpc::gimbal::ControlResponse)}, - {122, -1, -1, sizeof(::mavsdk::rpc::gimbal::Quaternion)}, - {134, -1, -1, sizeof(::mavsdk::rpc::gimbal::EulerAngle)}, - {145, -1, -1, sizeof(::mavsdk::rpc::gimbal::AngularVelocityBody)}, - {156, 170, -1, sizeof(::mavsdk::rpc::gimbal::Attitude)}, - {176, -1, -1, sizeof(::mavsdk::rpc::gimbal::SubscribeAttitudeRequest)}, - {184, 193, -1, sizeof(::mavsdk::rpc::gimbal::AttitudeResponse)}, - {194, -1, -1, sizeof(::mavsdk::rpc::gimbal::ControlStatus)}, - {207, -1, -1, sizeof(::mavsdk::rpc::gimbal::GimbalResult)}, + {14, 23, -1, sizeof(::mavsdk::rpc::gimbal::SetAnglesResponse)}, + {24, -1, -1, sizeof(::mavsdk::rpc::gimbal::SetAngularRatesRequest)}, + {38, 47, -1, sizeof(::mavsdk::rpc::gimbal::SetAngularRatesResponse)}, + {48, -1, -1, sizeof(::mavsdk::rpc::gimbal::SetRoiLocationRequest)}, + {60, 69, -1, sizeof(::mavsdk::rpc::gimbal::SetRoiLocationResponse)}, + {70, -1, -1, sizeof(::mavsdk::rpc::gimbal::TakeControlRequest)}, + {80, 89, -1, sizeof(::mavsdk::rpc::gimbal::TakeControlResponse)}, + {90, -1, -1, sizeof(::mavsdk::rpc::gimbal::ReleaseControlRequest)}, + {99, 108, -1, sizeof(::mavsdk::rpc::gimbal::ReleaseControlResponse)}, + {109, -1, -1, sizeof(::mavsdk::rpc::gimbal::SubscribeControlStatusRequest)}, + {117, 126, -1, sizeof(::mavsdk::rpc::gimbal::ControlStatusResponse)}, + {127, -1, -1, sizeof(::mavsdk::rpc::gimbal::GetControlStatusRequest)}, + {136, 146, -1, sizeof(::mavsdk::rpc::gimbal::GetControlStatusResponse)}, + {148, -1, -1, sizeof(::mavsdk::rpc::gimbal::Quaternion)}, + {160, -1, -1, sizeof(::mavsdk::rpc::gimbal::EulerAngle)}, + {171, -1, -1, sizeof(::mavsdk::rpc::gimbal::AngularVelocityBody)}, + {182, 197, -1, sizeof(::mavsdk::rpc::gimbal::Attitude)}, + {204, -1, -1, sizeof(::mavsdk::rpc::gimbal::SubscribeAttitudeRequest)}, + {212, 221, -1, sizeof(::mavsdk::rpc::gimbal::AttitudeResponse)}, + {222, -1, -1, sizeof(::mavsdk::rpc::gimbal::GetAttitudeRequest)}, + {231, 241, -1, sizeof(::mavsdk::rpc::gimbal::GetAttitudeResponse)}, + {243, -1, -1, sizeof(::mavsdk::rpc::gimbal::SubscribeGimbalListRequest)}, + {251, 260, -1, sizeof(::mavsdk::rpc::gimbal::GimbalListResponse)}, + {261, -1, -1, sizeof(::mavsdk::rpc::gimbal::GimbalItem)}, + {275, -1, -1, sizeof(::mavsdk::rpc::gimbal::GimbalList)}, + {284, -1, -1, sizeof(::mavsdk::rpc::gimbal::ControlStatus)}, + {298, -1, -1, sizeof(::mavsdk::rpc::gimbal::GimbalResult)}, }; static const ::_pb::Message* const file_default_instances[] = { @@ -674,101 +944,139 @@ static const ::_pb::Message* const file_default_instances[] = { &::mavsdk::rpc::gimbal::_TakeControlResponse_default_instance_._instance, &::mavsdk::rpc::gimbal::_ReleaseControlRequest_default_instance_._instance, &::mavsdk::rpc::gimbal::_ReleaseControlResponse_default_instance_._instance, - &::mavsdk::rpc::gimbal::_SubscribeControlRequest_default_instance_._instance, - &::mavsdk::rpc::gimbal::_ControlResponse_default_instance_._instance, + &::mavsdk::rpc::gimbal::_SubscribeControlStatusRequest_default_instance_._instance, + &::mavsdk::rpc::gimbal::_ControlStatusResponse_default_instance_._instance, + &::mavsdk::rpc::gimbal::_GetControlStatusRequest_default_instance_._instance, + &::mavsdk::rpc::gimbal::_GetControlStatusResponse_default_instance_._instance, &::mavsdk::rpc::gimbal::_Quaternion_default_instance_._instance, &::mavsdk::rpc::gimbal::_EulerAngle_default_instance_._instance, &::mavsdk::rpc::gimbal::_AngularVelocityBody_default_instance_._instance, &::mavsdk::rpc::gimbal::_Attitude_default_instance_._instance, &::mavsdk::rpc::gimbal::_SubscribeAttitudeRequest_default_instance_._instance, &::mavsdk::rpc::gimbal::_AttitudeResponse_default_instance_._instance, + &::mavsdk::rpc::gimbal::_GetAttitudeRequest_default_instance_._instance, + &::mavsdk::rpc::gimbal::_GetAttitudeResponse_default_instance_._instance, + &::mavsdk::rpc::gimbal::_SubscribeGimbalListRequest_default_instance_._instance, + &::mavsdk::rpc::gimbal::_GimbalListResponse_default_instance_._instance, + &::mavsdk::rpc::gimbal::_GimbalItem_default_instance_._instance, + &::mavsdk::rpc::gimbal::_GimbalList_default_instance_._instance, &::mavsdk::rpc::gimbal::_ControlStatus_default_instance_._instance, &::mavsdk::rpc::gimbal::_GimbalResult_default_instance_._instance, }; const char descriptor_table_protodef_gimbal_2fgimbal_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { "\n\023gimbal/gimbal.proto\022\021mavsdk.rpc.gimbal" - "\032\024mavsdk_options.proto\"\254\001\n\020SetAnglesRequ" - "est\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\0222\n\013gimbal_mode\030\004 \001(\0162\035" - ".mavsdk.rpc.gimbal.GimbalMode\022.\n\tsend_mo" - "de\030\005 \001(\0162\033.mavsdk.rpc.gimbal.SendMode\"K\n" - "\021SetAnglesResponse\0226\n\rgimbal_result\030\001 \001(" - "\0132\037.mavsdk.rpc.gimbal.GimbalResult\"\307\001\n\026S" - "etAngularRatesRequest\022\027\n\017roll_rate_deg_s" - "\030\001 \001(\002\022\030\n\020pitch_rate_deg_s\030\002 \001(\002\022\026\n\016yaw_" - "rate_deg_s\030\003 \001(\002\0222\n\013gimbal_mode\030\004 \001(\0162\035." - "mavsdk.rpc.gimbal.GimbalMode\022.\n\tsend_mod" - "e\030\005 \001(\0162\033.mavsdk.rpc.gimbal.SendMode\"Q\n\027" - "SetAngularRatesResponse\0226\n\rgimbal_result" - "\030\001 \001(\0132\037.mavsdk.rpc.gimbal.GimbalResult\"" - "X\n\025SetRoiLocationRequest\022\024\n\014latitude_deg" - "\030\001 \001(\001\022\025\n\rlongitude_deg\030\002 \001(\001\022\022\n\naltitud" - "e_m\030\003 \001(\002\"P\n\026SetRoiLocationResponse\0226\n\rg" - "imbal_result\030\001 \001(\0132\037.mavsdk.rpc.gimbal.G" - "imbalResult\"J\n\022TakeControlRequest\0224\n\014con" - "trol_mode\030\001 \001(\0162\036.mavsdk.rpc.gimbal.Cont" - "rolMode\"M\n\023TakeControlResponse\0226\n\rgimbal" - "_result\030\001 \001(\0132\037.mavsdk.rpc.gimbal.Gimbal" - "Result\"\027\n\025ReleaseControlRequest\"P\n\026Relea" - "seControlResponse\0226\n\rgimbal_result\030\001 \001(\013" - "2\037.mavsdk.rpc.gimbal.GimbalResult\"\031\n\027Sub" - "scribeControlRequest\"K\n\017ControlResponse\022" - "8\n\016control_status\030\001 \001(\0132 .mavsdk.rpc.gim" - "bal.ControlStatus\"\\\n\nQuaternion\022\022\n\001w\030\001 \001" - "(\002B\007\202\265\030\003NaN\022\022\n\001x\030\002 \001(\002B\007\202\265\030\003NaN\022\022\n\001y\030\003 \001" - "(\002B\007\202\265\030\003NaN\022\022\n\001z\030\004 \001(\002B\007\202\265\030\003NaN\"]\n\nEuler" - "Angle\022\031\n\010roll_deg\030\001 \001(\002B\007\202\265\030\003NaN\022\032\n\tpitc" - "h_deg\030\002 \001(\002B\007\202\265\030\003NaN\022\030\n\007yaw_deg\030\003 \001(\002B\007\202" - "\265\030\003NaN\"l\n\023AngularVelocityBody\022\033\n\nroll_ra" - "d_s\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013pitch_rad_s\030\002 \001(\002B" - "\007\202\265\030\003NaN\022\032\n\tyaw_rad_s\030\003 \001(\002B\007\202\265\030\003NaN\"\314\002\n" - "\010Attitude\022:\n\023euler_angle_forward\030\001 \001(\0132\035" - ".mavsdk.rpc.gimbal.EulerAngle\0229\n\022quatern" - "ion_forward\030\002 \001(\0132\035.mavsdk.rpc.gimbal.Qu" - "aternion\0228\n\021euler_angle_north\030\003 \001(\0132\035.ma" - "vsdk.rpc.gimbal.EulerAngle\0227\n\020quaternion" - "_north\030\004 \001(\0132\035.mavsdk.rpc.gimbal.Quatern" - "ion\022@\n\020angular_velocity\030\005 \001(\0132&.mavsdk.r" - "pc.gimbal.AngularVelocityBody\022\024\n\014timesta" - "mp_us\030\006 \001(\004\"\032\n\030SubscribeAttitudeRequest\"" - "A\n\020AttitudeResponse\022-\n\010attitude\030\001 \001(\0132\033." - "mavsdk.rpc.gimbal.Attitude\"\307\001\n\rControlSt" - "atus\0224\n\014control_mode\030\001 \001(\0162\036.mavsdk.rpc." - "gimbal.ControlMode\022\035\n\025sysid_primary_cont" - "rol\030\002 \001(\005\022\036\n\026compid_primary_control\030\003 \001(" - "\005\022\037\n\027sysid_secondary_control\030\004 \001(\005\022 \n\030co" - "mpid_secondary_control\030\005 \001(\005\"\376\001\n\014GimbalR" - "esult\0226\n\006result\030\001 \001(\0162&.mavsdk.rpc.gimba" - "l.GimbalResult.Result\022\022\n\nresult_str\030\002 \001(" - "\t\"\241\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESU" - "LT_SUCCESS\020\001\022\020\n\014RESULT_ERROR\020\002\022\022\n\016RESULT" - "_TIMEOUT\020\003\022\026\n\022RESULT_UNSUPPORTED\020\004\022\024\n\020RE" - "SULT_NO_SYSTEM\020\005\022\033\n\027RESULT_INVALID_ARGUM" - "ENT\020\006*B\n\nGimbalMode\022\032\n\026GIMBAL_MODE_YAW_F" - "OLLOW\020\000\022\030\n\024GIMBAL_MODE_YAW_LOCK\020\001*Z\n\013Con" - "trolMode\022\025\n\021CONTROL_MODE_NONE\020\000\022\030\n\024CONTR" - "OL_MODE_PRIMARY\020\001\022\032\n\026CONTROL_MODE_SECOND" - "ARY\020\002*4\n\010SendMode\022\022\n\016SEND_MODE_ONCE\020\000\022\024\n" - "\020SEND_MODE_STREAM\020\0012\332\005\n\rGimbalService\022X\n" - "\tSetAngles\022#.mavsdk.rpc.gimbal.SetAngles" - "Request\032$.mavsdk.rpc.gimbal.SetAnglesRes" - "ponse\"\000\022j\n\017SetAngularRates\022).mavsdk.rpc." - "gimbal.SetAngularRatesRequest\032*.mavsdk.r" - "pc.gimbal.SetAngularRatesResponse\"\000\022g\n\016S" - "etRoiLocation\022(.mavsdk.rpc.gimbal.SetRoi" - "LocationRequest\032).mavsdk.rpc.gimbal.SetR" - "oiLocationResponse\"\000\022^\n\013TakeControl\022%.ma" - "vsdk.rpc.gimbal.TakeControlRequest\032&.mav" - "sdk.rpc.gimbal.TakeControlResponse\"\000\022g\n\016" - "ReleaseControl\022(.mavsdk.rpc.gimbal.Relea" - "seControlRequest\032).mavsdk.rpc.gimbal.Rel" - "easeControlResponse\"\000\022f\n\020SubscribeContro" - "l\022*.mavsdk.rpc.gimbal.SubscribeControlRe" - "quest\032\".mavsdk.rpc.gimbal.ControlRespons" - "e\"\0000\001\022i\n\021SubscribeAttitude\022+.mavsdk.rpc." - "gimbal.SubscribeAttitudeRequest\032#.mavsdk" - ".rpc.gimbal.AttitudeResponse\"\0000\001B\037\n\020io.m" - "avsdk.gimbalB\013GimbalProtob\006proto3" + "\032\024mavsdk_options.proto\"\277\001\n\020SetAnglesRequ" + "est\022\021\n\tgimbal_id\030\001 \001(\005\022\020\n\010roll_deg\030\002 \001(\002" + "\022\021\n\tpitch_deg\030\003 \001(\002\022\017\n\007yaw_deg\030\004 \001(\002\0222\n\013" + "gimbal_mode\030\005 \001(\0162\035.mavsdk.rpc.gimbal.Gi" + "mbalMode\022.\n\tsend_mode\030\006 \001(\0162\033.mavsdk.rpc" + ".gimbal.SendMode\"K\n\021SetAnglesResponse\0226\n" + "\rgimbal_result\030\001 \001(\0132\037.mavsdk.rpc.gimbal" + ".GimbalResult\"\332\001\n\026SetAngularRatesRequest" + "\022\021\n\tgimbal_id\030\001 \001(\005\022\027\n\017roll_rate_deg_s\030\002" + " \001(\002\022\030\n\020pitch_rate_deg_s\030\003 \001(\002\022\026\n\016yaw_ra" + "te_deg_s\030\004 \001(\002\0222\n\013gimbal_mode\030\005 \001(\0162\035.ma" + "vsdk.rpc.gimbal.GimbalMode\022.\n\tsend_mode\030" + "\006 \001(\0162\033.mavsdk.rpc.gimbal.SendMode\"Q\n\027Se" + "tAngularRatesResponse\0226\n\rgimbal_result\030\001" + " \001(\0132\037.mavsdk.rpc.gimbal.GimbalResult\"k\n" + "\025SetRoiLocationRequest\022\021\n\tgimbal_id\030\001 \001(" + "\005\022\024\n\014latitude_deg\030\002 \001(\001\022\025\n\rlongitude_deg" + "\030\003 \001(\001\022\022\n\naltitude_m\030\004 \001(\002\"P\n\026SetRoiLoca" + "tionResponse\0226\n\rgimbal_result\030\001 \001(\0132\037.ma" + "vsdk.rpc.gimbal.GimbalResult\"]\n\022TakeCont" + "rolRequest\022\021\n\tgimbal_id\030\001 \001(\005\0224\n\014control" + "_mode\030\002 \001(\0162\036.mavsdk.rpc.gimbal.ControlM" + "ode\"M\n\023TakeControlResponse\0226\n\rgimbal_res" + "ult\030\001 \001(\0132\037.mavsdk.rpc.gimbal.GimbalResu" + "lt\"*\n\025ReleaseControlRequest\022\021\n\tgimbal_id" + "\030\001 \001(\005\"P\n\026ReleaseControlResponse\0226\n\rgimb" + "al_result\030\001 \001(\0132\037.mavsdk.rpc.gimbal.Gimb" + "alResult\"\037\n\035SubscribeControlStatusReques" + "t\"Q\n\025ControlStatusResponse\0228\n\016control_st" + "atus\030\001 \001(\0132 .mavsdk.rpc.gimbal.ControlSt" + "atus\",\n\027GetControlStatusRequest\022\021\n\tgimba" + "l_id\030\001 \001(\005\"\214\001\n\030GetControlStatusResponse\022" + "6\n\rgimbal_result\030\001 \001(\0132\037.mavsdk.rpc.gimb" + "al.GimbalResult\0228\n\016control_status\030\002 \001(\0132" + " .mavsdk.rpc.gimbal.ControlStatus\"\\\n\nQua" + "ternion\022\022\n\001w\030\001 \001(\002B\007\202\265\030\003NaN\022\022\n\001x\030\002 \001(\002B\007" + "\202\265\030\003NaN\022\022\n\001y\030\003 \001(\002B\007\202\265\030\003NaN\022\022\n\001z\030\004 \001(\002B\007" + "\202\265\030\003NaN\"]\n\nEulerAngle\022\031\n\010roll_deg\030\001 \001(\002B" + "\007\202\265\030\003NaN\022\032\n\tpitch_deg\030\002 \001(\002B\007\202\265\030\003NaN\022\030\n\007" + "yaw_deg\030\003 \001(\002B\007\202\265\030\003NaN\"l\n\023AngularVelocit" + "yBody\022\033\n\nroll_rad_s\030\001 \001(\002B\007\202\265\030\003NaN\022\034\n\013pi" + "tch_rad_s\030\002 \001(\002B\007\202\265\030\003NaN\022\032\n\tyaw_rad_s\030\003 " + "\001(\002B\007\202\265\030\003NaN\"\337\002\n\010Attitude\022\021\n\tgimbal_id\030\001" + " \001(\005\022:\n\023euler_angle_forward\030\002 \001(\0132\035.mavs" + "dk.rpc.gimbal.EulerAngle\0229\n\022quaternion_f" + "orward\030\003 \001(\0132\035.mavsdk.rpc.gimbal.Quatern" + "ion\0228\n\021euler_angle_north\030\004 \001(\0132\035.mavsdk." + "rpc.gimbal.EulerAngle\0227\n\020quaternion_nort" + "h\030\005 \001(\0132\035.mavsdk.rpc.gimbal.Quaternion\022@" + "\n\020angular_velocity\030\006 \001(\0132&.mavsdk.rpc.gi" + "mbal.AngularVelocityBody\022\024\n\014timestamp_us" + "\030\007 \001(\004\"\032\n\030SubscribeAttitudeRequest\"A\n\020At" + "titudeResponse\022-\n\010attitude\030\001 \001(\0132\033.mavsd" + "k.rpc.gimbal.Attitude\"\'\n\022GetAttitudeRequ" + "est\022\021\n\tgimbal_id\030\001 \001(\005\"|\n\023GetAttitudeRes" + "ponse\0226\n\rgimbal_result\030\001 \001(\0132\037.mavsdk.rp" + "c.gimbal.GimbalResult\022-\n\010attitude\030\002 \001(\0132" + "\033.mavsdk.rpc.gimbal.Attitude\"\034\n\032Subscrib" + "eGimbalListRequest\"H\n\022GimbalListResponse" + "\0222\n\013gimbal_list\030\001 \001(\0132\035.mavsdk.rpc.gimba" + "l.GimbalList\"\234\001\n\nGimbalItem\022\021\n\tgimbal_id" + "\030\001 \001(\005\022\023\n\013vendor_name\030\002 \001(\t\022\022\n\nmodel_nam" + "e\030\003 \001(\t\022\023\n\013custom_name\030\004 \001(\t\022#\n\033gimbal_m" + "anager_component_id\030\005 \001(\005\022\030\n\020gimbal_devi" + "ce_id\030\006 \001(\005\"<\n\nGimbalList\022.\n\007gimbals\030\001 \003" + "(\0132\035.mavsdk.rpc.gimbal.GimbalItem\"\332\001\n\rCo" + "ntrolStatus\022\021\n\tgimbal_id\030\001 \001(\005\0224\n\014contro" + "l_mode\030\002 \001(\0162\036.mavsdk.rpc.gimbal.Control" + "Mode\022\035\n\025sysid_primary_control\030\003 \001(\005\022\036\n\026c" + "ompid_primary_control\030\004 \001(\005\022\037\n\027sysid_sec" + "ondary_control\030\005 \001(\005\022 \n\030compid_secondary" + "_control\030\006 \001(\005\"\376\001\n\014GimbalResult\0226\n\006resul" + "t\030\001 \001(\0162&.mavsdk.rpc.gimbal.GimbalResult" + ".Result\022\022\n\nresult_str\030\002 \001(\t\"\241\001\n\006Result\022\022" + "\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\020" + "\n\014RESULT_ERROR\020\002\022\022\n\016RESULT_TIMEOUT\020\003\022\026\n\022" + "RESULT_UNSUPPORTED\020\004\022\024\n\020RESULT_NO_SYSTEM" + "\020\005\022\033\n\027RESULT_INVALID_ARGUMENT\020\006*B\n\nGimba" + "lMode\022\032\n\026GIMBAL_MODE_YAW_FOLLOW\020\000\022\030\n\024GIM" + "BAL_MODE_YAW_LOCK\020\001*Z\n\013ControlMode\022\025\n\021CO" + "NTROL_MODE_NONE\020\000\022\030\n\024CONTROL_MODE_PRIMAR" + "Y\020\001\022\032\n\026CONTROL_MODE_SECONDARY\020\002*4\n\010SendM" + "ode\022\022\n\016SEND_MODE_ONCE\020\000\022\024\n\020SEND_MODE_STR" + "EAM\020\0012\274\010\n\rGimbalService\022X\n\tSetAngles\022#.m" + "avsdk.rpc.gimbal.SetAnglesRequest\032$.mavs" + "dk.rpc.gimbal.SetAnglesResponse\"\000\022j\n\017Set" + "AngularRates\022).mavsdk.rpc.gimbal.SetAngu" + "larRatesRequest\032*.mavsdk.rpc.gimbal.SetA" + "ngularRatesResponse\"\000\022g\n\016SetRoiLocation\022" + "(.mavsdk.rpc.gimbal.SetRoiLocationReques" + "t\032).mavsdk.rpc.gimbal.SetRoiLocationResp" + "onse\"\000\022^\n\013TakeControl\022%.mavsdk.rpc.gimba" + "l.TakeControlRequest\032&.mavsdk.rpc.gimbal" + ".TakeControlResponse\"\000\022g\n\016ReleaseControl" + "\022(.mavsdk.rpc.gimbal.ReleaseControlReque" + "st\032).mavsdk.rpc.gimbal.ReleaseControlRes" + "ponse\"\000\022o\n\023SubscribeGimbalList\022-.mavsdk." + "rpc.gimbal.SubscribeGimbalListRequest\032%." + "mavsdk.rpc.gimbal.GimbalListResponse\"\0000\001" + "\022|\n\026SubscribeControlStatus\0220.mavsdk.rpc." + "gimbal.SubscribeControlStatusRequest\032(.m" + "avsdk.rpc.gimbal.ControlStatusResponse\"\004" + "\200\265\030\0000\001\022q\n\020GetControlStatus\022*.mavsdk.rpc." + "gimbal.GetControlStatusRequest\032+.mavsdk." + "rpc.gimbal.GetControlStatusResponse\"\004\200\265\030" + "\001\022m\n\021SubscribeAttitude\022+.mavsdk.rpc.gimb" + "al.SubscribeAttitudeRequest\032#.mavsdk.rpc" + ".gimbal.AttitudeResponse\"\004\200\265\030\0000\001\022b\n\013GetA" + "ttitude\022%.mavsdk.rpc.gimbal.GetAttitudeR" + "equest\032&.mavsdk.rpc.gimbal.GetAttitudeRe" + "sponse\"\004\200\265\030\001B\037\n\020io.mavsdk.gimbalB\013Gimbal" + "Protob\006proto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_gimbal_2fgimbal_2eproto_deps[1] = { @@ -778,13 +1086,13 @@ static ::absl::once_flag descriptor_table_gimbal_2fgimbal_2eproto_once; const ::_pbi::DescriptorTable descriptor_table_gimbal_2fgimbal_2eproto = { false, false, - 3313, + 4493, descriptor_table_protodef_gimbal_2fgimbal_2eproto, "gimbal/gimbal.proto", &descriptor_table_gimbal_2fgimbal_2eproto_once, descriptor_table_gimbal_2fgimbal_2eproto_deps, 1, - 20, + 28, schemas, file_default_instances, TableStruct_gimbal_2fgimbal_2eproto::offsets, @@ -889,10 +1197,10 @@ inline PROTOBUF_NDEBUG_INLINE SetAnglesRequest::Impl_::Impl_( inline void SetAnglesRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); ::memset(reinterpret_cast(&_impl_) + - offsetof(Impl_, roll_deg_), + offsetof(Impl_, gimbal_id_), 0, offsetof(Impl_, send_mode_) - - offsetof(Impl_, roll_deg_) + + offsetof(Impl_, gimbal_id_) + sizeof(Impl_::send_mode_)); } SetAnglesRequest::~SetAnglesRequest() { @@ -912,9 +1220,9 @@ PROTOBUF_NOINLINE void SetAnglesRequest::Clear() { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&_impl_.roll_deg_, 0, static_cast<::size_t>( + ::memset(&_impl_.gimbal_id_, 0, static_cast<::size_t>( reinterpret_cast(&_impl_.send_mode_) - - reinterpret_cast(&_impl_.roll_deg_)) + sizeof(_impl_.send_mode_)); + reinterpret_cast(&_impl_.gimbal_id_)) + sizeof(_impl_.send_mode_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -926,54 +1234,59 @@ const char* SetAnglesRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<3, 5, 0, 0, 2> SetAnglesRequest::_table_ = { +const ::_pbi::TcParseTable<3, 6, 0, 0, 2> SetAnglesRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 5, 56, // max_field_number, fast_idx_mask + 6, 56, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967264, // skipmap + 4294967232, // skipmap offsetof(decltype(_table_), field_entries), - 5, // num_field_entries + 6, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries &_SetAnglesRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ {::_pbi::TcParser::MiniParse, {}}, - // float roll_deg = 1; + // int32 gimbal_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(SetAnglesRequest, _impl_.gimbal_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.gimbal_id_)}}, + // float roll_deg = 2; {::_pbi::TcParser::FastF32S1, - {13, 63, 0, PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.roll_deg_)}}, - // float pitch_deg = 2; + {21, 63, 0, PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.roll_deg_)}}, + // float pitch_deg = 3; {::_pbi::TcParser::FastF32S1, - {21, 63, 0, PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.pitch_deg_)}}, - // float yaw_deg = 3; + {29, 63, 0, PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.pitch_deg_)}}, + // float yaw_deg = 4; {::_pbi::TcParser::FastF32S1, - {29, 63, 0, PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.yaw_deg_)}}, - // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 4; + {37, 63, 0, PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.yaw_deg_)}}, + // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 5; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(SetAnglesRequest, _impl_.gimbal_mode_), 63>(), - {32, 63, 0, PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.gimbal_mode_)}}, - // .mavsdk.rpc.gimbal.SendMode send_mode = 5; + {40, 63, 0, PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.gimbal_mode_)}}, + // .mavsdk.rpc.gimbal.SendMode send_mode = 6; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(SetAnglesRequest, _impl_.send_mode_), 63>(), - {40, 63, 0, PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.send_mode_)}}, - {::_pbi::TcParser::MiniParse, {}}, + {48, 63, 0, PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.send_mode_)}}, {::_pbi::TcParser::MiniParse, {}}, }}, {{ 65535, 65535 }}, {{ - // float roll_deg = 1; + // int32 gimbal_id = 1; + {PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.gimbal_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // float roll_deg = 2; {PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.roll_deg_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float pitch_deg = 2; + // float pitch_deg = 3; {PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.pitch_deg_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float yaw_deg = 3; + // float yaw_deg = 4; {PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.yaw_deg_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 4; + // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 5; {PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.gimbal_mode_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, - // .mavsdk.rpc.gimbal.SendMode send_mode = 5; + // .mavsdk.rpc.gimbal.SendMode send_mode = 6; {PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.send_mode_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, }}, @@ -989,7 +1302,14 @@ ::uint8_t* SetAnglesRequest::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // float roll_deg = 1; + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_gimbal_id(), target); + } + + // float roll_deg = 2; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_roll_deg = this->_internal_roll_deg(); @@ -998,10 +1318,10 @@ ::uint8_t* SetAnglesRequest::_InternalSerialize( if (raw_roll_deg != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 1, this->_internal_roll_deg(), target); + 2, this->_internal_roll_deg(), target); } - // float pitch_deg = 2; + // float pitch_deg = 3; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_pitch_deg = this->_internal_pitch_deg(); @@ -1010,10 +1330,10 @@ ::uint8_t* SetAnglesRequest::_InternalSerialize( if (raw_pitch_deg != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 2, this->_internal_pitch_deg(), target); + 3, this->_internal_pitch_deg(), target); } - // float yaw_deg = 3; + // float yaw_deg = 4; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_yaw_deg = this->_internal_yaw_deg(); @@ -1022,21 +1342,21 @@ ::uint8_t* SetAnglesRequest::_InternalSerialize( if (raw_yaw_deg != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 3, this->_internal_yaw_deg(), target); + 4, this->_internal_yaw_deg(), target); } - // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 4; + // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 5; if (this->_internal_gimbal_mode() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 4, this->_internal_gimbal_mode(), target); + 5, this->_internal_gimbal_mode(), target); } - // .mavsdk.rpc.gimbal.SendMode send_mode = 5; + // .mavsdk.rpc.gimbal.SendMode send_mode = 6; if (this->_internal_send_mode() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 5, this->_internal_send_mode(), target); + 6, this->_internal_send_mode(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -1056,7 +1376,13 @@ ::size_t SetAnglesRequest::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float roll_deg = 1; + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_gimbal_id()); + } + + // float roll_deg = 2; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_roll_deg = this->_internal_roll_deg(); @@ -1066,7 +1392,7 @@ ::size_t SetAnglesRequest::ByteSizeLong() const { total_size += 5; } - // float pitch_deg = 2; + // float pitch_deg = 3; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_pitch_deg = this->_internal_pitch_deg(); @@ -1076,7 +1402,7 @@ ::size_t SetAnglesRequest::ByteSizeLong() const { total_size += 5; } - // float yaw_deg = 3; + // float yaw_deg = 4; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_yaw_deg = this->_internal_yaw_deg(); @@ -1086,13 +1412,13 @@ ::size_t SetAnglesRequest::ByteSizeLong() const { total_size += 5; } - // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 4; + // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 5; if (this->_internal_gimbal_mode() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_gimbal_mode()); } - // .mavsdk.rpc.gimbal.SendMode send_mode = 5; + // .mavsdk.rpc.gimbal.SendMode send_mode = 6; if (this->_internal_send_mode() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_send_mode()); @@ -1117,6 +1443,9 @@ void SetAnglesRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::go ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + if (from._internal_gimbal_id() != 0) { + _this->_internal_set_gimbal_id(from._internal_gimbal_id()); + } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_roll_deg = from._internal_roll_deg(); @@ -1170,9 +1499,9 @@ void SetAnglesRequest::InternalSwap(SetAnglesRequest* PROTOBUF_RESTRICT other) { ::google::protobuf::internal::memswap< PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.send_mode_) + sizeof(SetAnglesRequest::_impl_.send_mode_) - - PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.roll_deg_)>( - reinterpret_cast(&_impl_.roll_deg_), - reinterpret_cast(&other->_impl_.roll_deg_)); + - PROTOBUF_FIELD_OFFSET(SetAnglesRequest, _impl_.gimbal_id_)>( + reinterpret_cast(&_impl_.gimbal_id_), + reinterpret_cast(&other->_impl_.gimbal_id_)); } ::google::protobuf::Metadata SetAnglesRequest::GetMetadata() const { @@ -1411,10 +1740,10 @@ inline PROTOBUF_NDEBUG_INLINE SetAngularRatesRequest::Impl_::Impl_( inline void SetAngularRatesRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); ::memset(reinterpret_cast(&_impl_) + - offsetof(Impl_, roll_rate_deg_s_), + offsetof(Impl_, gimbal_id_), 0, offsetof(Impl_, send_mode_) - - offsetof(Impl_, roll_rate_deg_s_) + + offsetof(Impl_, gimbal_id_) + sizeof(Impl_::send_mode_)); } SetAngularRatesRequest::~SetAngularRatesRequest() { @@ -1434,9 +1763,9 @@ PROTOBUF_NOINLINE void SetAngularRatesRequest::Clear() { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&_impl_.roll_rate_deg_s_, 0, static_cast<::size_t>( + ::memset(&_impl_.gimbal_id_, 0, static_cast<::size_t>( reinterpret_cast(&_impl_.send_mode_) - - reinterpret_cast(&_impl_.roll_rate_deg_s_)) + sizeof(_impl_.send_mode_)); + reinterpret_cast(&_impl_.gimbal_id_)) + sizeof(_impl_.send_mode_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -1448,54 +1777,59 @@ const char* SetAngularRatesRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<3, 5, 0, 0, 2> SetAngularRatesRequest::_table_ = { +const ::_pbi::TcParseTable<3, 6, 0, 0, 2> SetAngularRatesRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 5, 56, // max_field_number, fast_idx_mask + 6, 56, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967264, // skipmap + 4294967232, // skipmap offsetof(decltype(_table_), field_entries), - 5, // num_field_entries + 6, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries &_SetAngularRatesRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ {::_pbi::TcParser::MiniParse, {}}, - // float roll_rate_deg_s = 1; + // int32 gimbal_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(SetAngularRatesRequest, _impl_.gimbal_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.gimbal_id_)}}, + // float roll_rate_deg_s = 2; {::_pbi::TcParser::FastF32S1, - {13, 63, 0, PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.roll_rate_deg_s_)}}, - // float pitch_rate_deg_s = 2; + {21, 63, 0, PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.roll_rate_deg_s_)}}, + // float pitch_rate_deg_s = 3; {::_pbi::TcParser::FastF32S1, - {21, 63, 0, PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.pitch_rate_deg_s_)}}, - // float yaw_rate_deg_s = 3; + {29, 63, 0, PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.pitch_rate_deg_s_)}}, + // float yaw_rate_deg_s = 4; {::_pbi::TcParser::FastF32S1, - {29, 63, 0, PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.yaw_rate_deg_s_)}}, - // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 4; + {37, 63, 0, PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.yaw_rate_deg_s_)}}, + // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 5; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(SetAngularRatesRequest, _impl_.gimbal_mode_), 63>(), - {32, 63, 0, PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.gimbal_mode_)}}, - // .mavsdk.rpc.gimbal.SendMode send_mode = 5; + {40, 63, 0, PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.gimbal_mode_)}}, + // .mavsdk.rpc.gimbal.SendMode send_mode = 6; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(SetAngularRatesRequest, _impl_.send_mode_), 63>(), - {40, 63, 0, PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.send_mode_)}}, - {::_pbi::TcParser::MiniParse, {}}, + {48, 63, 0, PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.send_mode_)}}, {::_pbi::TcParser::MiniParse, {}}, }}, {{ 65535, 65535 }}, {{ - // float roll_rate_deg_s = 1; + // int32 gimbal_id = 1; + {PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.gimbal_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // float roll_rate_deg_s = 2; {PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.roll_rate_deg_s_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float pitch_rate_deg_s = 2; + // float pitch_rate_deg_s = 3; {PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.pitch_rate_deg_s_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float yaw_rate_deg_s = 3; + // float yaw_rate_deg_s = 4; {PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.yaw_rate_deg_s_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 4; + // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 5; {PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.gimbal_mode_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, - // .mavsdk.rpc.gimbal.SendMode send_mode = 5; + // .mavsdk.rpc.gimbal.SendMode send_mode = 6; {PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.send_mode_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, }}, @@ -1511,7 +1845,14 @@ ::uint8_t* SetAngularRatesRequest::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // float roll_rate_deg_s = 1; + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_gimbal_id(), target); + } + + // float roll_rate_deg_s = 2; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_roll_rate_deg_s = this->_internal_roll_rate_deg_s(); @@ -1520,10 +1861,10 @@ ::uint8_t* SetAngularRatesRequest::_InternalSerialize( if (raw_roll_rate_deg_s != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 1, this->_internal_roll_rate_deg_s(), target); + 2, this->_internal_roll_rate_deg_s(), target); } - // float pitch_rate_deg_s = 2; + // float pitch_rate_deg_s = 3; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_pitch_rate_deg_s = this->_internal_pitch_rate_deg_s(); @@ -1532,10 +1873,10 @@ ::uint8_t* SetAngularRatesRequest::_InternalSerialize( if (raw_pitch_rate_deg_s != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 2, this->_internal_pitch_rate_deg_s(), target); + 3, this->_internal_pitch_rate_deg_s(), target); } - // float yaw_rate_deg_s = 3; + // float yaw_rate_deg_s = 4; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_yaw_rate_deg_s = this->_internal_yaw_rate_deg_s(); @@ -1544,21 +1885,21 @@ ::uint8_t* SetAngularRatesRequest::_InternalSerialize( if (raw_yaw_rate_deg_s != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 3, this->_internal_yaw_rate_deg_s(), target); + 4, this->_internal_yaw_rate_deg_s(), target); } - // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 4; + // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 5; if (this->_internal_gimbal_mode() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 4, this->_internal_gimbal_mode(), target); + 5, this->_internal_gimbal_mode(), target); } - // .mavsdk.rpc.gimbal.SendMode send_mode = 5; + // .mavsdk.rpc.gimbal.SendMode send_mode = 6; if (this->_internal_send_mode() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 5, this->_internal_send_mode(), target); + 6, this->_internal_send_mode(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -1578,7 +1919,13 @@ ::size_t SetAngularRatesRequest::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float roll_rate_deg_s = 1; + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_gimbal_id()); + } + + // float roll_rate_deg_s = 2; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_roll_rate_deg_s = this->_internal_roll_rate_deg_s(); @@ -1588,7 +1935,7 @@ ::size_t SetAngularRatesRequest::ByteSizeLong() const { total_size += 5; } - // float pitch_rate_deg_s = 2; + // float pitch_rate_deg_s = 3; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_pitch_rate_deg_s = this->_internal_pitch_rate_deg_s(); @@ -1598,7 +1945,7 @@ ::size_t SetAngularRatesRequest::ByteSizeLong() const { total_size += 5; } - // float yaw_rate_deg_s = 3; + // float yaw_rate_deg_s = 4; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_yaw_rate_deg_s = this->_internal_yaw_rate_deg_s(); @@ -1608,13 +1955,13 @@ ::size_t SetAngularRatesRequest::ByteSizeLong() const { total_size += 5; } - // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 4; + // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 5; if (this->_internal_gimbal_mode() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_gimbal_mode()); } - // .mavsdk.rpc.gimbal.SendMode send_mode = 5; + // .mavsdk.rpc.gimbal.SendMode send_mode = 6; if (this->_internal_send_mode() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_send_mode()); @@ -1639,6 +1986,9 @@ void SetAngularRatesRequest::MergeImpl(::google::protobuf::Message& to_msg, cons ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + if (from._internal_gimbal_id() != 0) { + _this->_internal_set_gimbal_id(from._internal_gimbal_id()); + } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_roll_rate_deg_s = from._internal_roll_rate_deg_s(); @@ -1692,9 +2042,9 @@ void SetAngularRatesRequest::InternalSwap(SetAngularRatesRequest* PROTOBUF_RESTR ::google::protobuf::internal::memswap< PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.send_mode_) + sizeof(SetAngularRatesRequest::_impl_.send_mode_) - - PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.roll_rate_deg_s_)>( - reinterpret_cast(&_impl_.roll_rate_deg_s_), - reinterpret_cast(&other->_impl_.roll_rate_deg_s_)); + - PROTOBUF_FIELD_OFFSET(SetAngularRatesRequest, _impl_.gimbal_id_)>( + reinterpret_cast(&_impl_.gimbal_id_), + reinterpret_cast(&other->_impl_.gimbal_id_)); } ::google::protobuf::Metadata SetAngularRatesRequest::GetMetadata() const { @@ -1935,9 +2285,9 @@ inline void SetRoiLocationRequest::SharedCtor(::_pb::Arena* arena) { ::memset(reinterpret_cast(&_impl_) + offsetof(Impl_, latitude_deg_), 0, - offsetof(Impl_, altitude_m_) - + offsetof(Impl_, longitude_deg_) - offsetof(Impl_, latitude_deg_) + - sizeof(Impl_::altitude_m_)); + sizeof(Impl_::longitude_deg_)); } SetRoiLocationRequest::~SetRoiLocationRequest() { // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.SetRoiLocationRequest) @@ -1957,8 +2307,8 @@ PROTOBUF_NOINLINE void SetRoiLocationRequest::Clear() { (void) cached_has_bits; ::memset(&_impl_.latitude_deg_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.altitude_m_) - - reinterpret_cast(&_impl_.latitude_deg_)) + sizeof(_impl_.altitude_m_)); + reinterpret_cast(&_impl_.longitude_deg_) - + reinterpret_cast(&_impl_.latitude_deg_)) + sizeof(_impl_.longitude_deg_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -1970,40 +2320,45 @@ const char* SetRoiLocationRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<2, 3, 0, 0, 2> SetRoiLocationRequest::_table_ = { +const ::_pbi::TcParseTable<2, 4, 0, 0, 2> SetRoiLocationRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 3, 24, // max_field_number, fast_idx_mask + 4, 24, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967288, // skipmap + 4294967280, // skipmap offsetof(decltype(_table_), field_entries), - 3, // num_field_entries + 4, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries &_SetRoiLocationRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - {::_pbi::TcParser::MiniParse, {}}, - // double latitude_deg = 1; + // float altitude_m = 4; + {::_pbi::TcParser::FastF32S1, + {37, 63, 0, PROTOBUF_FIELD_OFFSET(SetRoiLocationRequest, _impl_.altitude_m_)}}, + // int32 gimbal_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(SetRoiLocationRequest, _impl_.gimbal_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(SetRoiLocationRequest, _impl_.gimbal_id_)}}, + // double latitude_deg = 2; {::_pbi::TcParser::FastF64S1, - {9, 63, 0, PROTOBUF_FIELD_OFFSET(SetRoiLocationRequest, _impl_.latitude_deg_)}}, - // double longitude_deg = 2; + {17, 63, 0, PROTOBUF_FIELD_OFFSET(SetRoiLocationRequest, _impl_.latitude_deg_)}}, + // double longitude_deg = 3; {::_pbi::TcParser::FastF64S1, - {17, 63, 0, PROTOBUF_FIELD_OFFSET(SetRoiLocationRequest, _impl_.longitude_deg_)}}, - // float altitude_m = 3; - {::_pbi::TcParser::FastF32S1, - {29, 63, 0, PROTOBUF_FIELD_OFFSET(SetRoiLocationRequest, _impl_.altitude_m_)}}, + {25, 63, 0, PROTOBUF_FIELD_OFFSET(SetRoiLocationRequest, _impl_.longitude_deg_)}}, }}, {{ 65535, 65535 }}, {{ - // double latitude_deg = 1; + // int32 gimbal_id = 1; + {PROTOBUF_FIELD_OFFSET(SetRoiLocationRequest, _impl_.gimbal_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // double latitude_deg = 2; {PROTOBUF_FIELD_OFFSET(SetRoiLocationRequest, _impl_.latitude_deg_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kDouble)}, - // double longitude_deg = 2; + // double longitude_deg = 3; {PROTOBUF_FIELD_OFFSET(SetRoiLocationRequest, _impl_.longitude_deg_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kDouble)}, - // float altitude_m = 3; + // float altitude_m = 4; {PROTOBUF_FIELD_OFFSET(SetRoiLocationRequest, _impl_.altitude_m_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, }}, @@ -2019,7 +2374,14 @@ ::uint8_t* SetRoiLocationRequest::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // double latitude_deg = 1; + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_gimbal_id(), target); + } + + // double latitude_deg = 2; static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); double tmp_latitude_deg = this->_internal_latitude_deg(); @@ -2028,10 +2390,10 @@ ::uint8_t* SetRoiLocationRequest::_InternalSerialize( if (raw_latitude_deg != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteDoubleToArray( - 1, this->_internal_latitude_deg(), target); + 2, this->_internal_latitude_deg(), target); } - // double longitude_deg = 2; + // double longitude_deg = 3; static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); double tmp_longitude_deg = this->_internal_longitude_deg(); @@ -2040,10 +2402,10 @@ ::uint8_t* SetRoiLocationRequest::_InternalSerialize( if (raw_longitude_deg != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteDoubleToArray( - 2, this->_internal_longitude_deg(), target); + 3, this->_internal_longitude_deg(), target); } - // float altitude_m = 3; + // float altitude_m = 4; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_altitude_m = this->_internal_altitude_m(); @@ -2052,7 +2414,7 @@ ::uint8_t* SetRoiLocationRequest::_InternalSerialize( if (raw_altitude_m != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 3, this->_internal_altitude_m(), target); + 4, this->_internal_altitude_m(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -2072,7 +2434,7 @@ ::size_t SetRoiLocationRequest::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // double latitude_deg = 1; + // double latitude_deg = 2; static_assert(sizeof(::uint64_t) == sizeof(double), "Code assumes ::uint64_t and double are the same size."); double tmp_latitude_deg = this->_internal_latitude_deg(); @@ -2082,17 +2444,13 @@ ::size_t SetRoiLocationRequest::ByteSizeLong() const { total_size += 9; } - // double longitude_deg = 2; - static_assert(sizeof(::uint64_t) == sizeof(double), - "Code assumes ::uint64_t and double are the same size."); - double tmp_longitude_deg = this->_internal_longitude_deg(); - ::uint64_t raw_longitude_deg; - memcpy(&raw_longitude_deg, &tmp_longitude_deg, sizeof(tmp_longitude_deg)); - if (raw_longitude_deg != 0) { - total_size += 9; + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_gimbal_id()); } - // float altitude_m = 3; + // float altitude_m = 4; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); float tmp_altitude_m = this->_internal_altitude_m(); @@ -2102,6 +2460,16 @@ ::size_t SetRoiLocationRequest::ByteSizeLong() const { total_size += 5; } + // double longitude_deg = 3; + static_assert(sizeof(::uint64_t) == sizeof(double), + "Code assumes ::uint64_t and double are the same size."); + double tmp_longitude_deg = this->_internal_longitude_deg(); + ::uint64_t raw_longitude_deg; + memcpy(&raw_longitude_deg, &tmp_longitude_deg, sizeof(tmp_longitude_deg)); + if (raw_longitude_deg != 0) { + total_size += 9; + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } @@ -2129,13 +2497,8 @@ void SetRoiLocationRequest::MergeImpl(::google::protobuf::Message& to_msg, const if (raw_latitude_deg != 0) { _this->_internal_set_latitude_deg(from._internal_latitude_deg()); } - static_assert(sizeof(::uint64_t) == sizeof(double), - "Code assumes ::uint64_t and double are the same size."); - double tmp_longitude_deg = from._internal_longitude_deg(); - ::uint64_t raw_longitude_deg; - memcpy(&raw_longitude_deg, &tmp_longitude_deg, sizeof(tmp_longitude_deg)); - if (raw_longitude_deg != 0) { - _this->_internal_set_longitude_deg(from._internal_longitude_deg()); + if (from._internal_gimbal_id() != 0) { + _this->_internal_set_gimbal_id(from._internal_gimbal_id()); } static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); @@ -2145,6 +2508,14 @@ void SetRoiLocationRequest::MergeImpl(::google::protobuf::Message& to_msg, const if (raw_altitude_m != 0) { _this->_internal_set_altitude_m(from._internal_altitude_m()); } + static_assert(sizeof(::uint64_t) == sizeof(double), + "Code assumes ::uint64_t and double are the same size."); + double tmp_longitude_deg = from._internal_longitude_deg(); + ::uint64_t raw_longitude_deg; + memcpy(&raw_longitude_deg, &tmp_longitude_deg, sizeof(tmp_longitude_deg)); + if (raw_longitude_deg != 0) { + _this->_internal_set_longitude_deg(from._internal_longitude_deg()); + } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } @@ -2166,8 +2537,8 @@ void SetRoiLocationRequest::InternalSwap(SetRoiLocationRequest* PROTOBUF_RESTRIC using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); ::google::protobuf::internal::memswap< - PROTOBUF_FIELD_OFFSET(SetRoiLocationRequest, _impl_.altitude_m_) - + sizeof(SetRoiLocationRequest::_impl_.altitude_m_) + PROTOBUF_FIELD_OFFSET(SetRoiLocationRequest, _impl_.longitude_deg_) + + sizeof(SetRoiLocationRequest::_impl_.longitude_deg_) - PROTOBUF_FIELD_OFFSET(SetRoiLocationRequest, _impl_.latitude_deg_)>( reinterpret_cast(&_impl_.latitude_deg_), reinterpret_cast(&other->_impl_.latitude_deg_)); @@ -2408,7 +2779,12 @@ inline PROTOBUF_NDEBUG_INLINE TakeControlRequest::Impl_::Impl_( inline void TakeControlRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.control_mode_ = {}; + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, gimbal_id_), + 0, + offsetof(Impl_, control_mode_) - + offsetof(Impl_, gimbal_id_) + + sizeof(Impl_::control_mode_)); } TakeControlRequest::~TakeControlRequest() { // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.TakeControlRequest) @@ -2427,7 +2803,9 @@ PROTOBUF_NOINLINE void TakeControlRequest::Clear() { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - _impl_.control_mode_ = 0; + ::memset(&_impl_.gimbal_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.control_mode_) - + reinterpret_cast(&_impl_.gimbal_id_)) + sizeof(_impl_.control_mode_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -2439,27 +2817,33 @@ const char* TakeControlRequest::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 0, 0, 2> TakeControlRequest::_table_ = { +const ::_pbi::TcParseTable<1, 2, 0, 0, 2> TakeControlRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 1, 0, // max_field_number, fast_idx_mask + 2, 8, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967294, // skipmap + 4294967292, // skipmap offsetof(decltype(_table_), field_entries), - 1, // num_field_entries + 2, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries &_TakeControlRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.gimbal.ControlMode control_mode = 1; + // .mavsdk.rpc.gimbal.ControlMode control_mode = 2; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(TakeControlRequest, _impl_.control_mode_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(TakeControlRequest, _impl_.control_mode_)}}, + {16, 63, 0, PROTOBUF_FIELD_OFFSET(TakeControlRequest, _impl_.control_mode_)}}, + // int32 gimbal_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(TakeControlRequest, _impl_.gimbal_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(TakeControlRequest, _impl_.gimbal_id_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.gimbal.ControlMode control_mode = 1; + // int32 gimbal_id = 1; + {PROTOBUF_FIELD_OFFSET(TakeControlRequest, _impl_.gimbal_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // .mavsdk.rpc.gimbal.ControlMode control_mode = 2; {PROTOBUF_FIELD_OFFSET(TakeControlRequest, _impl_.control_mode_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, }}, @@ -2475,11 +2859,18 @@ ::uint8_t* TakeControlRequest::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // .mavsdk.rpc.gimbal.ControlMode control_mode = 1; + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_gimbal_id(), target); + } + + // .mavsdk.rpc.gimbal.ControlMode control_mode = 2; if (this->_internal_control_mode() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 1, this->_internal_control_mode(), target); + 2, this->_internal_control_mode(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -2499,7 +2890,13 @@ ::size_t TakeControlRequest::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.gimbal.ControlMode control_mode = 1; + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_gimbal_id()); + } + + // .mavsdk.rpc.gimbal.ControlMode control_mode = 2; if (this->_internal_control_mode() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_control_mode()); @@ -2524,6 +2921,9 @@ void TakeControlRequest::MergeImpl(::google::protobuf::Message& to_msg, const :: ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + if (from._internal_gimbal_id() != 0) { + _this->_internal_set_gimbal_id(from._internal_gimbal_id()); + } if (from._internal_control_mode() != 0) { _this->_internal_set_control_mode(from._internal_control_mode()); } @@ -2547,7 +2947,12 @@ ::_pbi::CachedSize* TakeControlRequest::AccessCachedSize() const { void TakeControlRequest::InternalSwap(TakeControlRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_.control_mode_, other->_impl_.control_mode_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(TakeControlRequest, _impl_.control_mode_) + + sizeof(TakeControlRequest::_impl_.control_mode_) + - PROTOBUF_FIELD_OFFSET(TakeControlRequest, _impl_.gimbal_id_)>( + reinterpret_cast(&_impl_.gimbal_id_), + reinterpret_cast(&other->_impl_.gimbal_id_)); } ::google::protobuf::Metadata TakeControlRequest::GetMetadata() const { @@ -2769,28 +3174,163 @@ class ReleaseControlRequest::_Internal { }; ReleaseControlRequest::ReleaseControlRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.ReleaseControlRequest) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.ReleaseControlRequest) } ReleaseControlRequest::ReleaseControlRequest( - ::google::protobuf::Arena* arena, - const ReleaseControlRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - ReleaseControlRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); + ::google::protobuf::Arena* arena, const ReleaseControlRequest& from) + : ReleaseControlRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE ReleaseControlRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void ReleaseControlRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.gimbal_id_ = {}; +} +ReleaseControlRequest::~ReleaseControlRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.ReleaseControlRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void ReleaseControlRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void ReleaseControlRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.ReleaseControlRequest) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.gimbal_id_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* ReleaseControlRequest::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> ReleaseControlRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_ReleaseControlRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 gimbal_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ReleaseControlRequest, _impl_.gimbal_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(ReleaseControlRequest, _impl_.gimbal_id_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 gimbal_id = 1; + {PROTOBUF_FIELD_OFFSET(ReleaseControlRequest, _impl_.gimbal_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* ReleaseControlRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.ReleaseControlRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.ReleaseControlRequest) + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_gimbal_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.ReleaseControlRequest) + return target; } +::size_t ReleaseControlRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.ReleaseControlRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_gimbal_id()); + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} +const ::google::protobuf::Message::ClassData ReleaseControlRequest::_class_data_ = { + ReleaseControlRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* ReleaseControlRequest::GetClassData() const { + return &_class_data_; +} +void ReleaseControlRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.ReleaseControlRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + if (from._internal_gimbal_id() != 0) { + _this->_internal_set_gimbal_id(from._internal_gimbal_id()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} +void ReleaseControlRequest::CopyFrom(const ReleaseControlRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.ReleaseControlRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} +PROTOBUF_NOINLINE bool ReleaseControlRequest::IsInitialized() const { + return true; +} +::_pbi::CachedSize* ReleaseControlRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void ReleaseControlRequest::InternalSwap(ReleaseControlRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.gimbal_id_, other->_impl_.gimbal_id_); +} ::google::protobuf::Metadata ReleaseControlRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( @@ -3006,24 +3546,24 @@ ::google::protobuf::Metadata ReleaseControlResponse::GetMetadata() const { } // =================================================================== -class SubscribeControlRequest::_Internal { +class SubscribeControlStatusRequest::_Internal { public: }; -SubscribeControlRequest::SubscribeControlRequest(::google::protobuf::Arena* arena) +SubscribeControlStatusRequest::SubscribeControlStatusRequest(::google::protobuf::Arena* arena) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.SubscribeControlRequest) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.SubscribeControlStatusRequest) } -SubscribeControlRequest::SubscribeControlRequest( +SubscribeControlStatusRequest::SubscribeControlStatusRequest( ::google::protobuf::Arena* arena, - const SubscribeControlRequest& from) + const SubscribeControlStatusRequest& from) : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeControlRequest* const _this = this; + SubscribeControlStatusRequest* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.SubscribeControlRequest) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.SubscribeControlStatusRequest) } @@ -3034,43 +3574,43 @@ SubscribeControlRequest::SubscribeControlRequest( -::google::protobuf::Metadata SubscribeControlRequest::GetMetadata() const { +::google::protobuf::Metadata SubscribeControlStatusRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, file_level_metadata_gimbal_2fgimbal_2eproto[10]); } // =================================================================== -class ControlResponse::_Internal { +class ControlStatusResponse::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); + using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(ControlResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::gimbal::ControlStatus& control_status(const ControlResponse* msg); + 8 * PROTOBUF_FIELD_OFFSET(ControlStatusResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::gimbal::ControlStatus& control_status(const ControlStatusResponse* msg); static void set_has_control_status(HasBits* has_bits) { (*has_bits)[0] |= 1u; } }; -const ::mavsdk::rpc::gimbal::ControlStatus& ControlResponse::_Internal::control_status(const ControlResponse* msg) { +const ::mavsdk::rpc::gimbal::ControlStatus& ControlStatusResponse::_Internal::control_status(const ControlStatusResponse* msg) { return *msg->_impl_.control_status_; } -ControlResponse::ControlResponse(::google::protobuf::Arena* arena) +ControlStatusResponse::ControlStatusResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.ControlResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.ControlStatusResponse) } -inline PROTOBUF_NDEBUG_INLINE ControlResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ControlStatusResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) : _has_bits_{from._has_bits_}, _cached_size_{0} {} -ControlResponse::ControlResponse( +ControlStatusResponse::ControlStatusResponse( ::google::protobuf::Arena* arena, - const ControlResponse& from) + const ControlStatusResponse& from) : ::google::protobuf::Message(arena) { - ControlResponse* const _this = this; + ControlStatusResponse* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); @@ -3080,30 +3620,30 @@ ControlResponse::ControlResponse( ? CreateMaybeMessage<::mavsdk::rpc::gimbal::ControlStatus>(arena, *from._impl_.control_status_) : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.ControlResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.ControlStatusResponse) } -inline PROTOBUF_NDEBUG_INLINE ControlResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE ControlStatusResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void ControlResponse::SharedCtor(::_pb::Arena* arena) { +inline void ControlStatusResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); _impl_.control_status_ = {}; } -ControlResponse::~ControlResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.ControlResponse) +ControlStatusResponse::~ControlStatusResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.ControlStatusResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void ControlResponse::SharedDtor() { +inline void ControlStatusResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); delete _impl_.control_status_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void ControlResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.ControlResponse) +PROTOBUF_NOINLINE void ControlStatusResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.ControlStatusResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused @@ -3118,7 +3658,7 @@ PROTOBUF_NOINLINE void ControlResponse::Clear() { _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* ControlResponse::_InternalParse( +const char* ControlStatusResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -3126,9 +3666,9 @@ const char* ControlResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ControlResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ControlStatusResponse::_table_ = { { - PROTOBUF_FIELD_OFFSET(ControlResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(ControlStatusResponse, _impl_._has_bits_), 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -3137,17 +3677,17 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ControlResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_ControlResponse_default_instance_._instance, + &_ControlStatusResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ // .mavsdk.rpc.gimbal.ControlStatus control_status = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(ControlResponse, _impl_.control_status_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(ControlStatusResponse, _impl_.control_status_)}}, }}, {{ 65535, 65535 }}, {{ // .mavsdk.rpc.gimbal.ControlStatus control_status = 1; - {PROTOBUF_FIELD_OFFSET(ControlResponse, _impl_.control_status_), _Internal::kHasBitsOffset + 0, 0, + {PROTOBUF_FIELD_OFFSET(ControlStatusResponse, _impl_.control_status_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::ControlStatus>()}, @@ -3155,10 +3695,10 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> ControlResponse::_table_ = { }}, }; -::uint8_t* ControlResponse::_InternalSerialize( +::uint8_t* ControlStatusResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.ControlResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.ControlStatusResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; @@ -3175,12 +3715,12 @@ ::uint8_t* ControlResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.ControlResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.ControlStatusResponse) return target; } -::size_t ControlResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.ControlResponse) +::size_t ControlStatusResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.ControlStatusResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; @@ -3197,18 +3737,18 @@ ::size_t ControlResponse::ByteSizeLong() const { return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData ControlResponse::_class_data_ = { - ControlResponse::MergeImpl, +const ::google::protobuf::Message::ClassData ControlStatusResponse::_class_data_ = { + ControlStatusResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* ControlResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* ControlStatusResponse::GetClassData() const { return &_class_data_; } -void ControlResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.ControlResponse) +void ControlStatusResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.ControlStatusResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; @@ -3220,86 +3760,79 @@ void ControlResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::goo _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void ControlResponse::CopyFrom(const ControlResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.ControlResponse) +void ControlStatusResponse::CopyFrom(const ControlStatusResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.ControlStatusResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool ControlResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool ControlStatusResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* ControlResponse::AccessCachedSize() const { +::_pbi::CachedSize* ControlStatusResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void ControlResponse::InternalSwap(ControlResponse* PROTOBUF_RESTRICT other) { +void ControlStatusResponse::InternalSwap(ControlStatusResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); swap(_impl_.control_status_, other->_impl_.control_status_); } -::google::protobuf::Metadata ControlResponse::GetMetadata() const { +::google::protobuf::Metadata ControlStatusResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, file_level_metadata_gimbal_2fgimbal_2eproto[11]); } // =================================================================== -class Quaternion::_Internal { +class GetControlStatusRequest::_Internal { public: }; -Quaternion::Quaternion(::google::protobuf::Arena* arena) +GetControlStatusRequest::GetControlStatusRequest(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.Quaternion) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.GetControlStatusRequest) } -Quaternion::Quaternion( - ::google::protobuf::Arena* arena, const Quaternion& from) - : Quaternion(arena) { +GetControlStatusRequest::GetControlStatusRequest( + ::google::protobuf::Arena* arena, const GetControlStatusRequest& from) + : GetControlStatusRequest(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE Quaternion::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetControlStatusRequest::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void Quaternion::SharedCtor(::_pb::Arena* arena) { +inline void GetControlStatusRequest::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - ::memset(reinterpret_cast(&_impl_) + - offsetof(Impl_, w_), - 0, - offsetof(Impl_, z_) - - offsetof(Impl_, w_) + - sizeof(Impl_::z_)); + _impl_.gimbal_id_ = {}; } -Quaternion::~Quaternion() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.Quaternion) +GetControlStatusRequest::~GetControlStatusRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.GetControlStatusRequest) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void Quaternion::SharedDtor() { +inline void GetControlStatusRequest::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void Quaternion::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.Quaternion) +PROTOBUF_NOINLINE void GetControlStatusRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.GetControlStatusRequest) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&_impl_.w_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.z_) - - reinterpret_cast(&_impl_.w_)) + sizeof(_impl_.z_)); + _impl_.gimbal_id_ = 0; _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* Quaternion::_InternalParse( +const char* GetControlStatusRequest::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -3307,106 +3840,47 @@ const char* Quaternion::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<2, 4, 0, 0, 2> Quaternion::_table_ = { +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> GetControlStatusRequest::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 4, 24, // max_field_number, fast_idx_mask + 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967280, // skipmap + 4294967294, // skipmap offsetof(decltype(_table_), field_entries), - 4, // num_field_entries + 1, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_Quaternion_default_instance_._instance, + &_GetControlStatusRequest_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // float z = 4 [(.mavsdk.options.default_value) = "NaN"]; - {::_pbi::TcParser::FastF32S1, - {37, 63, 0, PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.z_)}}, - // float w = 1 [(.mavsdk.options.default_value) = "NaN"]; - {::_pbi::TcParser::FastF32S1, - {13, 63, 0, PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.w_)}}, - // float x = 2 [(.mavsdk.options.default_value) = "NaN"]; - {::_pbi::TcParser::FastF32S1, - {21, 63, 0, PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.x_)}}, - // float y = 3 [(.mavsdk.options.default_value) = "NaN"]; - {::_pbi::TcParser::FastF32S1, - {29, 63, 0, PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.y_)}}, + // int32 gimbal_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(GetControlStatusRequest, _impl_.gimbal_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(GetControlStatusRequest, _impl_.gimbal_id_)}}, }}, {{ 65535, 65535 }}, {{ - // float w = 1 [(.mavsdk.options.default_value) = "NaN"]; - {PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.w_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float x = 2 [(.mavsdk.options.default_value) = "NaN"]; - {PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.x_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float y = 3 [(.mavsdk.options.default_value) = "NaN"]; - {PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.y_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float z = 4 [(.mavsdk.options.default_value) = "NaN"]; - {PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.z_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // int32 gimbal_id = 1; + {PROTOBUF_FIELD_OFFSET(GetControlStatusRequest, _impl_.gimbal_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, }}, // no aux_entries {{ }}, }; -::uint8_t* Quaternion::_InternalSerialize( +::uint8_t* GetControlStatusRequest::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.Quaternion) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.GetControlStatusRequest) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // float w = 1 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_w = this->_internal_w(); - ::uint32_t raw_w; - memcpy(&raw_w, &tmp_w, sizeof(tmp_w)); - if (raw_w != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 1, this->_internal_w(), target); - } - - // float x = 2 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_x = this->_internal_x(); - ::uint32_t raw_x; - memcpy(&raw_x, &tmp_x, sizeof(tmp_x)); - if (raw_x != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 2, this->_internal_x(), target); - } - - // float y = 3 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_y = this->_internal_y(); - ::uint32_t raw_y; - memcpy(&raw_y, &tmp_y, sizeof(tmp_y)); - if (raw_y != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 3, this->_internal_y(), target); - } - - // float z = 4 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_z = this->_internal_z(); - ::uint32_t raw_z; - memcpy(&raw_z, &tmp_z, sizeof(tmp_z)); - if (raw_z != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 4, this->_internal_z(), target); + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_gimbal_id(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -3414,196 +3888,176 @@ ::uint8_t* Quaternion::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.Quaternion) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.GetControlStatusRequest) return target; } -::size_t Quaternion::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.Quaternion) +::size_t GetControlStatusRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.GetControlStatusRequest) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float w = 1 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_w = this->_internal_w(); - ::uint32_t raw_w; - memcpy(&raw_w, &tmp_w, sizeof(tmp_w)); - if (raw_w != 0) { - total_size += 5; - } - - // float x = 2 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_x = this->_internal_x(); - ::uint32_t raw_x; - memcpy(&raw_x, &tmp_x, sizeof(tmp_x)); - if (raw_x != 0) { - total_size += 5; - } - - // float y = 3 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_y = this->_internal_y(); - ::uint32_t raw_y; - memcpy(&raw_y, &tmp_y, sizeof(tmp_y)); - if (raw_y != 0) { - total_size += 5; - } - - // float z = 4 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_z = this->_internal_z(); - ::uint32_t raw_z; - memcpy(&raw_z, &tmp_z, sizeof(tmp_z)); - if (raw_z != 0) { - total_size += 5; + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_gimbal_id()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData Quaternion::_class_data_ = { - Quaternion::MergeImpl, +const ::google::protobuf::Message::ClassData GetControlStatusRequest::_class_data_ = { + GetControlStatusRequest::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* Quaternion::GetClassData() const { +const ::google::protobuf::Message::ClassData* GetControlStatusRequest::GetClassData() const { return &_class_data_; } -void Quaternion::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.Quaternion) +void GetControlStatusRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.GetControlStatusRequest) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_w = from._internal_w(); - ::uint32_t raw_w; - memcpy(&raw_w, &tmp_w, sizeof(tmp_w)); - if (raw_w != 0) { - _this->_internal_set_w(from._internal_w()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_x = from._internal_x(); - ::uint32_t raw_x; - memcpy(&raw_x, &tmp_x, sizeof(tmp_x)); - if (raw_x != 0) { - _this->_internal_set_x(from._internal_x()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_y = from._internal_y(); - ::uint32_t raw_y; - memcpy(&raw_y, &tmp_y, sizeof(tmp_y)); - if (raw_y != 0) { - _this->_internal_set_y(from._internal_y()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_z = from._internal_z(); - ::uint32_t raw_z; - memcpy(&raw_z, &tmp_z, sizeof(tmp_z)); - if (raw_z != 0) { - _this->_internal_set_z(from._internal_z()); + if (from._internal_gimbal_id() != 0) { + _this->_internal_set_gimbal_id(from._internal_gimbal_id()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void Quaternion::CopyFrom(const Quaternion& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.Quaternion) +void GetControlStatusRequest::CopyFrom(const GetControlStatusRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.GetControlStatusRequest) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool Quaternion::IsInitialized() const { +PROTOBUF_NOINLINE bool GetControlStatusRequest::IsInitialized() const { return true; } -::_pbi::CachedSize* Quaternion::AccessCachedSize() const { +::_pbi::CachedSize* GetControlStatusRequest::AccessCachedSize() const { return &_impl_._cached_size_; } -void Quaternion::InternalSwap(Quaternion* PROTOBUF_RESTRICT other) { +void GetControlStatusRequest::InternalSwap(GetControlStatusRequest* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - ::google::protobuf::internal::memswap< - PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.z_) - + sizeof(Quaternion::_impl_.z_) - - PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.w_)>( - reinterpret_cast(&_impl_.w_), - reinterpret_cast(&other->_impl_.w_)); + swap(_impl_.gimbal_id_, other->_impl_.gimbal_id_); } -::google::protobuf::Metadata Quaternion::GetMetadata() const { +::google::protobuf::Metadata GetControlStatusRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, file_level_metadata_gimbal_2fgimbal_2eproto[12]); } // =================================================================== -class EulerAngle::_Internal { +class GetControlStatusResponse::_Internal { public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(GetControlStatusResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::gimbal::GimbalResult& gimbal_result(const GetControlStatusResponse* msg); + static void set_has_gimbal_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } + static const ::mavsdk::rpc::gimbal::ControlStatus& control_status(const GetControlStatusResponse* msg); + static void set_has_control_status(HasBits* has_bits) { + (*has_bits)[0] |= 2u; + } }; -EulerAngle::EulerAngle(::google::protobuf::Arena* arena) +const ::mavsdk::rpc::gimbal::GimbalResult& GetControlStatusResponse::_Internal::gimbal_result(const GetControlStatusResponse* msg) { + return *msg->_impl_.gimbal_result_; +} +const ::mavsdk::rpc::gimbal::ControlStatus& GetControlStatusResponse::_Internal::control_status(const GetControlStatusResponse* msg) { + return *msg->_impl_.control_status_; +} +GetControlStatusResponse::GetControlStatusResponse(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.EulerAngle) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.GetControlStatusResponse) } -EulerAngle::EulerAngle( - ::google::protobuf::Arena* arena, const EulerAngle& from) - : EulerAngle(arena) { - MergeFrom(from); +inline PROTOBUF_NDEBUG_INLINE GetControlStatusResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +GetControlStatusResponse::GetControlStatusResponse( + ::google::protobuf::Arena* arena, + const GetControlStatusResponse& from) + : ::google::protobuf::Message(arena) { + GetControlStatusResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.gimbal_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::gimbal::GimbalResult>(arena, *from._impl_.gimbal_result_) + : nullptr; + _impl_.control_status_ = (cached_has_bits & 0x00000002u) + ? CreateMaybeMessage<::mavsdk::rpc::gimbal::ControlStatus>(arena, *from._impl_.control_status_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.GetControlStatusResponse) } -inline PROTOBUF_NDEBUG_INLINE EulerAngle::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GetControlStatusResponse::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void EulerAngle::SharedCtor(::_pb::Arena* arena) { +inline void GetControlStatusResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); ::memset(reinterpret_cast(&_impl_) + - offsetof(Impl_, roll_deg_), + offsetof(Impl_, gimbal_result_), 0, - offsetof(Impl_, yaw_deg_) - - offsetof(Impl_, roll_deg_) + - sizeof(Impl_::yaw_deg_)); + offsetof(Impl_, control_status_) - + offsetof(Impl_, gimbal_result_) + + sizeof(Impl_::control_status_)); } -EulerAngle::~EulerAngle() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.EulerAngle) +GetControlStatusResponse::~GetControlStatusResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.GetControlStatusResponse) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void EulerAngle::SharedDtor() { +inline void GetControlStatusResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.gimbal_result_; + delete _impl_.control_status_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void EulerAngle::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.EulerAngle) +PROTOBUF_NOINLINE void GetControlStatusResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.GetControlStatusResponse) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&_impl_.roll_deg_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.yaw_deg_) - - reinterpret_cast(&_impl_.roll_deg_)) + sizeof(_impl_.yaw_deg_)); + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.gimbal_result_ != nullptr); + _impl_.gimbal_result_->Clear(); + } + if (cached_has_bits & 0x00000002u) { + ABSL_DCHECK(_impl_.control_status_ != nullptr); + _impl_.control_status_->Clear(); + } + } + _impl_._has_bits_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* EulerAngle::_InternalParse( +const char* GetControlStatusResponse::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -3611,89 +4065,62 @@ const char* EulerAngle::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<2, 3, 0, 0, 2> EulerAngle::_table_ = { +const ::_pbi::TcParseTable<1, 2, 2, 0, 2> GetControlStatusResponse::_table_ = { { - 0, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(GetControlStatusResponse, _impl_._has_bits_), 0, // no _extensions_ - 3, 24, // max_field_number, fast_idx_mask + 2, 8, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967288, // skipmap + 4294967292, // skipmap offsetof(decltype(_table_), field_entries), - 3, // num_field_entries - 0, // num_aux_entries - offsetof(decltype(_table_), field_names), // no aux_entries - &_EulerAngle_default_instance_._instance, + 2, // num_field_entries + 2, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_GetControlStatusResponse_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - {::_pbi::TcParser::MiniParse, {}}, - // float roll_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; - {::_pbi::TcParser::FastF32S1, - {13, 63, 0, PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.roll_deg_)}}, - // float pitch_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; - {::_pbi::TcParser::FastF32S1, - {21, 63, 0, PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.pitch_deg_)}}, - // float yaw_deg = 3 [(.mavsdk.options.default_value) = "NaN"]; - {::_pbi::TcParser::FastF32S1, - {29, 63, 0, PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.yaw_deg_)}}, + // .mavsdk.rpc.gimbal.ControlStatus control_status = 2; + {::_pbi::TcParser::FastMtS1, + {18, 1, 1, PROTOBUF_FIELD_OFFSET(GetControlStatusResponse, _impl_.control_status_)}}, + // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(GetControlStatusResponse, _impl_.gimbal_result_)}}, }}, {{ 65535, 65535 }}, {{ - // float roll_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; - {PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.roll_deg_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float pitch_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; - {PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.pitch_deg_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float yaw_deg = 3 [(.mavsdk.options.default_value) = "NaN"]; - {PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.yaw_deg_), 0, 0, - (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - }}, - // no aux_entries - {{ + // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; + {PROTOBUF_FIELD_OFFSET(GetControlStatusResponse, _impl_.gimbal_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // .mavsdk.rpc.gimbal.ControlStatus control_status = 2; + {PROTOBUF_FIELD_OFFSET(GetControlStatusResponse, _impl_.control_status_), _Internal::kHasBitsOffset + 1, 1, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::GimbalResult>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::ControlStatus>()}, + }}, {{ }}, }; -::uint8_t* EulerAngle::_InternalSerialize( +::uint8_t* GetControlStatusResponse::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.EulerAngle) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.GetControlStatusResponse) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // float roll_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_roll_deg = this->_internal_roll_deg(); - ::uint32_t raw_roll_deg; - memcpy(&raw_roll_deg, &tmp_roll_deg, sizeof(tmp_roll_deg)); - if (raw_roll_deg != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 1, this->_internal_roll_deg(), target); - } - - // float pitch_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_pitch_deg = this->_internal_pitch_deg(); - ::uint32_t raw_pitch_deg; - memcpy(&raw_pitch_deg, &tmp_pitch_deg, sizeof(tmp_pitch_deg)); - if (raw_pitch_deg != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 2, this->_internal_pitch_deg(), target); + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::gimbal_result(this), + _Internal::gimbal_result(this).GetCachedSize(), target, stream); } - // float yaw_deg = 3 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_yaw_deg = this->_internal_yaw_deg(); - ::uint32_t raw_yaw_deg; - memcpy(&raw_yaw_deg, &tmp_yaw_deg, sizeof(tmp_yaw_deg)); - if (raw_yaw_deg != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 3, this->_internal_yaw_deg(), target); + // .mavsdk.rpc.gimbal.ControlStatus control_status = 2; + if (cached_has_bits & 0x00000002u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 2, _Internal::control_status(this), + _Internal::control_status(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -3701,178 +4128,151 @@ ::uint8_t* EulerAngle::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.EulerAngle) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.GetControlStatusResponse) return target; } -::size_t EulerAngle::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.EulerAngle) +::size_t GetControlStatusResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.GetControlStatusResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float roll_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_roll_deg = this->_internal_roll_deg(); - ::uint32_t raw_roll_deg; - memcpy(&raw_roll_deg, &tmp_roll_deg, sizeof(tmp_roll_deg)); - if (raw_roll_deg != 0) { - total_size += 5; - } + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.gimbal_result_); + } - // float pitch_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_pitch_deg = this->_internal_pitch_deg(); - ::uint32_t raw_pitch_deg; - memcpy(&raw_pitch_deg, &tmp_pitch_deg, sizeof(tmp_pitch_deg)); - if (raw_pitch_deg != 0) { - total_size += 5; - } + // .mavsdk.rpc.gimbal.ControlStatus control_status = 2; + if (cached_has_bits & 0x00000002u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.control_status_); + } - // float yaw_deg = 3 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_yaw_deg = this->_internal_yaw_deg(); - ::uint32_t raw_yaw_deg; - memcpy(&raw_yaw_deg, &tmp_yaw_deg, sizeof(tmp_yaw_deg)); - if (raw_yaw_deg != 0) { - total_size += 5; } - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData EulerAngle::_class_data_ = { - EulerAngle::MergeImpl, +const ::google::protobuf::Message::ClassData GetControlStatusResponse::_class_data_ = { + GetControlStatusResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* EulerAngle::GetClassData() const { +const ::google::protobuf::Message::ClassData* GetControlStatusResponse::GetClassData() const { return &_class_data_; } -void EulerAngle::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.EulerAngle) +void GetControlStatusResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.GetControlStatusResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_roll_deg = from._internal_roll_deg(); - ::uint32_t raw_roll_deg; - memcpy(&raw_roll_deg, &tmp_roll_deg, sizeof(tmp_roll_deg)); - if (raw_roll_deg != 0) { - _this->_internal_set_roll_deg(from._internal_roll_deg()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_pitch_deg = from._internal_pitch_deg(); - ::uint32_t raw_pitch_deg; - memcpy(&raw_pitch_deg, &tmp_pitch_deg, sizeof(tmp_pitch_deg)); - if (raw_pitch_deg != 0) { - _this->_internal_set_pitch_deg(from._internal_pitch_deg()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_yaw_deg = from._internal_yaw_deg(); - ::uint32_t raw_yaw_deg; - memcpy(&raw_yaw_deg, &tmp_yaw_deg, sizeof(tmp_yaw_deg)); - if (raw_yaw_deg != 0) { - _this->_internal_set_yaw_deg(from._internal_yaw_deg()); + cached_has_bits = from._impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + if (cached_has_bits & 0x00000001u) { + _this->_internal_mutable_gimbal_result()->::mavsdk::rpc::gimbal::GimbalResult::MergeFrom( + from._internal_gimbal_result()); + } + if (cached_has_bits & 0x00000002u) { + _this->_internal_mutable_control_status()->::mavsdk::rpc::gimbal::ControlStatus::MergeFrom( + from._internal_control_status()); + } } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void EulerAngle::CopyFrom(const EulerAngle& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.EulerAngle) +void GetControlStatusResponse::CopyFrom(const GetControlStatusResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.GetControlStatusResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool EulerAngle::IsInitialized() const { +PROTOBUF_NOINLINE bool GetControlStatusResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* EulerAngle::AccessCachedSize() const { +::_pbi::CachedSize* GetControlStatusResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void EulerAngle::InternalSwap(EulerAngle* PROTOBUF_RESTRICT other) { +void GetControlStatusResponse::InternalSwap(GetControlStatusResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); ::google::protobuf::internal::memswap< - PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.yaw_deg_) - + sizeof(EulerAngle::_impl_.yaw_deg_) - - PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.roll_deg_)>( - reinterpret_cast(&_impl_.roll_deg_), - reinterpret_cast(&other->_impl_.roll_deg_)); + PROTOBUF_FIELD_OFFSET(GetControlStatusResponse, _impl_.control_status_) + + sizeof(GetControlStatusResponse::_impl_.control_status_) + - PROTOBUF_FIELD_OFFSET(GetControlStatusResponse, _impl_.gimbal_result_)>( + reinterpret_cast(&_impl_.gimbal_result_), + reinterpret_cast(&other->_impl_.gimbal_result_)); } -::google::protobuf::Metadata EulerAngle::GetMetadata() const { +::google::protobuf::Metadata GetControlStatusResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, file_level_metadata_gimbal_2fgimbal_2eproto[13]); } // =================================================================== -class AngularVelocityBody::_Internal { +class Quaternion::_Internal { public: }; -AngularVelocityBody::AngularVelocityBody(::google::protobuf::Arena* arena) +Quaternion::Quaternion(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.AngularVelocityBody) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.Quaternion) } -AngularVelocityBody::AngularVelocityBody( - ::google::protobuf::Arena* arena, const AngularVelocityBody& from) - : AngularVelocityBody(arena) { +Quaternion::Quaternion( + ::google::protobuf::Arena* arena, const Quaternion& from) + : Quaternion(arena) { MergeFrom(from); } -inline PROTOBUF_NDEBUG_INLINE AngularVelocityBody::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE Quaternion::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) : _cached_size_{0} {} -inline void AngularVelocityBody::SharedCtor(::_pb::Arena* arena) { +inline void Quaternion::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); ::memset(reinterpret_cast(&_impl_) + - offsetof(Impl_, roll_rad_s_), + offsetof(Impl_, w_), 0, - offsetof(Impl_, yaw_rad_s_) - - offsetof(Impl_, roll_rad_s_) + - sizeof(Impl_::yaw_rad_s_)); + offsetof(Impl_, z_) - + offsetof(Impl_, w_) + + sizeof(Impl_::z_)); } -AngularVelocityBody::~AngularVelocityBody() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.AngularVelocityBody) +Quaternion::~Quaternion() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.Quaternion) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void AngularVelocityBody::SharedDtor() { +inline void Quaternion::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void AngularVelocityBody::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.AngularVelocityBody) +PROTOBUF_NOINLINE void Quaternion::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.Quaternion) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&_impl_.roll_rad_s_, 0, static_cast<::size_t>( - reinterpret_cast(&_impl_.yaw_rad_s_) - - reinterpret_cast(&_impl_.roll_rad_s_)) + sizeof(_impl_.yaw_rad_s_)); + ::memset(&_impl_.w_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.z_) - + reinterpret_cast(&_impl_.w_)) + sizeof(_impl_.z_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* AngularVelocityBody::_InternalParse( +const char* Quaternion::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -3880,41 +4280,46 @@ const char* AngularVelocityBody::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<2, 3, 0, 0, 2> AngularVelocityBody::_table_ = { +const ::_pbi::TcParseTable<2, 4, 0, 0, 2> Quaternion::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 3, 24, // max_field_number, fast_idx_mask + 4, 24, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967288, // skipmap + 4294967280, // skipmap offsetof(decltype(_table_), field_entries), - 3, // num_field_entries + 4, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries - &_AngularVelocityBody_default_instance_._instance, + &_Quaternion_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - {::_pbi::TcParser::MiniParse, {}}, - // float roll_rad_s = 1 [(.mavsdk.options.default_value) = "NaN"]; + // float z = 4 [(.mavsdk.options.default_value) = "NaN"]; {::_pbi::TcParser::FastF32S1, - {13, 63, 0, PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.roll_rad_s_)}}, - // float pitch_rad_s = 2 [(.mavsdk.options.default_value) = "NaN"]; + {37, 63, 0, PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.z_)}}, + // float w = 1 [(.mavsdk.options.default_value) = "NaN"]; {::_pbi::TcParser::FastF32S1, - {21, 63, 0, PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.pitch_rad_s_)}}, - // float yaw_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; + {13, 63, 0, PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.w_)}}, + // float x = 2 [(.mavsdk.options.default_value) = "NaN"]; {::_pbi::TcParser::FastF32S1, - {29, 63, 0, PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.yaw_rad_s_)}}, + {21, 63, 0, PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.x_)}}, + // float y = 3 [(.mavsdk.options.default_value) = "NaN"]; + {::_pbi::TcParser::FastF32S1, + {29, 63, 0, PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.y_)}}, }}, {{ 65535, 65535 }}, {{ - // float roll_rad_s = 1 [(.mavsdk.options.default_value) = "NaN"]; - {PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.roll_rad_s_), 0, 0, + // float w = 1 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.w_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float pitch_rad_s = 2 [(.mavsdk.options.default_value) = "NaN"]; - {PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.pitch_rad_s_), 0, 0, + // float x = 2 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.x_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, - // float yaw_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; - {PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.yaw_rad_s_), 0, 0, + // float y = 3 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.y_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float z = 4 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.z_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, }}, // no aux_entries @@ -3922,47 +4327,2014 @@ const ::_pbi::TcParseTable<2, 3, 0, 0, 2> AngularVelocityBody::_table_ = { }}, }; -::uint8_t* AngularVelocityBody::_InternalSerialize( +::uint8_t* Quaternion::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.AngularVelocityBody) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.Quaternion) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // float roll_rad_s = 1 [(.mavsdk.options.default_value) = "NaN"]; + // float w = 1 [(.mavsdk.options.default_value) = "NaN"]; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_roll_rad_s = this->_internal_roll_rad_s(); - ::uint32_t raw_roll_rad_s; - memcpy(&raw_roll_rad_s, &tmp_roll_rad_s, sizeof(tmp_roll_rad_s)); - if (raw_roll_rad_s != 0) { + float tmp_w = this->_internal_w(); + ::uint32_t raw_w; + memcpy(&raw_w, &tmp_w, sizeof(tmp_w)); + if (raw_w != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 1, this->_internal_roll_rad_s(), target); + 1, this->_internal_w(), target); } - // float pitch_rad_s = 2 [(.mavsdk.options.default_value) = "NaN"]; + // float x = 2 [(.mavsdk.options.default_value) = "NaN"]; static_assert(sizeof(::uint32_t) == sizeof(float), "Code assumes ::uint32_t and float are the same size."); - float tmp_pitch_rad_s = this->_internal_pitch_rad_s(); - ::uint32_t raw_pitch_rad_s; - memcpy(&raw_pitch_rad_s, &tmp_pitch_rad_s, sizeof(tmp_pitch_rad_s)); - if (raw_pitch_rad_s != 0) { + float tmp_x = this->_internal_x(); + ::uint32_t raw_x; + memcpy(&raw_x, &tmp_x, sizeof(tmp_x)); + if (raw_x != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteFloatToArray( - 2, this->_internal_pitch_rad_s(), target); + 2, this->_internal_x(), target); + } + + // float y = 3 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_y = this->_internal_y(); + ::uint32_t raw_y; + memcpy(&raw_y, &tmp_y, sizeof(tmp_y)); + if (raw_y != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 3, this->_internal_y(), target); + } + + // float z = 4 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_z = this->_internal_z(); + ::uint32_t raw_z; + memcpy(&raw_z, &tmp_z, sizeof(tmp_z)); + if (raw_z != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 4, this->_internal_z(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.Quaternion) + return target; +} + +::size_t Quaternion::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.Quaternion) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // float w = 1 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_w = this->_internal_w(); + ::uint32_t raw_w; + memcpy(&raw_w, &tmp_w, sizeof(tmp_w)); + if (raw_w != 0) { + total_size += 5; + } + + // float x = 2 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_x = this->_internal_x(); + ::uint32_t raw_x; + memcpy(&raw_x, &tmp_x, sizeof(tmp_x)); + if (raw_x != 0) { + total_size += 5; + } + + // float y = 3 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_y = this->_internal_y(); + ::uint32_t raw_y; + memcpy(&raw_y, &tmp_y, sizeof(tmp_y)); + if (raw_y != 0) { + total_size += 5; + } + + // float z = 4 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_z = this->_internal_z(); + ::uint32_t raw_z; + memcpy(&raw_z, &tmp_z, sizeof(tmp_z)); + if (raw_z != 0) { + total_size += 5; + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData Quaternion::_class_data_ = { + Quaternion::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* Quaternion::GetClassData() const { + return &_class_data_; +} + +void Quaternion::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.Quaternion) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_w = from._internal_w(); + ::uint32_t raw_w; + memcpy(&raw_w, &tmp_w, sizeof(tmp_w)); + if (raw_w != 0) { + _this->_internal_set_w(from._internal_w()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_x = from._internal_x(); + ::uint32_t raw_x; + memcpy(&raw_x, &tmp_x, sizeof(tmp_x)); + if (raw_x != 0) { + _this->_internal_set_x(from._internal_x()); } + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_y = from._internal_y(); + ::uint32_t raw_y; + memcpy(&raw_y, &tmp_y, sizeof(tmp_y)); + if (raw_y != 0) { + _this->_internal_set_y(from._internal_y()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_z = from._internal_z(); + ::uint32_t raw_z; + memcpy(&raw_z, &tmp_z, sizeof(tmp_z)); + if (raw_z != 0) { + _this->_internal_set_z(from._internal_z()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void Quaternion::CopyFrom(const Quaternion& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.Quaternion) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool Quaternion::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* Quaternion::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void Quaternion::InternalSwap(Quaternion* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.z_) + + sizeof(Quaternion::_impl_.z_) + - PROTOBUF_FIELD_OFFSET(Quaternion, _impl_.w_)>( + reinterpret_cast(&_impl_.w_), + reinterpret_cast(&other->_impl_.w_)); +} + +::google::protobuf::Metadata Quaternion::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, + file_level_metadata_gimbal_2fgimbal_2eproto[14]); +} +// =================================================================== + +class EulerAngle::_Internal { + public: +}; + +EulerAngle::EulerAngle(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.EulerAngle) +} +EulerAngle::EulerAngle( + ::google::protobuf::Arena* arena, const EulerAngle& from) + : EulerAngle(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE EulerAngle::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void EulerAngle::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, roll_deg_), + 0, + offsetof(Impl_, yaw_deg_) - + offsetof(Impl_, roll_deg_) + + sizeof(Impl_::yaw_deg_)); +} +EulerAngle::~EulerAngle() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.EulerAngle) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void EulerAngle::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void EulerAngle::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.EulerAngle) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&_impl_.roll_deg_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.yaw_deg_) - + reinterpret_cast(&_impl_.roll_deg_)) + sizeof(_impl_.yaw_deg_)); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* EulerAngle::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<2, 3, 0, 0, 2> EulerAngle::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 3, 24, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967288, // skipmap + offsetof(decltype(_table_), field_entries), + 3, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_EulerAngle_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + {::_pbi::TcParser::MiniParse, {}}, + // float roll_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; + {::_pbi::TcParser::FastF32S1, + {13, 63, 0, PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.roll_deg_)}}, + // float pitch_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; + {::_pbi::TcParser::FastF32S1, + {21, 63, 0, PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.pitch_deg_)}}, + // float yaw_deg = 3 [(.mavsdk.options.default_value) = "NaN"]; + {::_pbi::TcParser::FastF32S1, + {29, 63, 0, PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.yaw_deg_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // float roll_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.roll_deg_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float pitch_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.pitch_deg_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float yaw_deg = 3 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.yaw_deg_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* EulerAngle::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.EulerAngle) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // float roll_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_roll_deg = this->_internal_roll_deg(); + ::uint32_t raw_roll_deg; + memcpy(&raw_roll_deg, &tmp_roll_deg, sizeof(tmp_roll_deg)); + if (raw_roll_deg != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 1, this->_internal_roll_deg(), target); + } + + // float pitch_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_pitch_deg = this->_internal_pitch_deg(); + ::uint32_t raw_pitch_deg; + memcpy(&raw_pitch_deg, &tmp_pitch_deg, sizeof(tmp_pitch_deg)); + if (raw_pitch_deg != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 2, this->_internal_pitch_deg(), target); + } + + // float yaw_deg = 3 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_yaw_deg = this->_internal_yaw_deg(); + ::uint32_t raw_yaw_deg; + memcpy(&raw_yaw_deg, &tmp_yaw_deg, sizeof(tmp_yaw_deg)); + if (raw_yaw_deg != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 3, this->_internal_yaw_deg(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.EulerAngle) + return target; +} + +::size_t EulerAngle::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.EulerAngle) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // float roll_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_roll_deg = this->_internal_roll_deg(); + ::uint32_t raw_roll_deg; + memcpy(&raw_roll_deg, &tmp_roll_deg, sizeof(tmp_roll_deg)); + if (raw_roll_deg != 0) { + total_size += 5; + } + + // float pitch_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_pitch_deg = this->_internal_pitch_deg(); + ::uint32_t raw_pitch_deg; + memcpy(&raw_pitch_deg, &tmp_pitch_deg, sizeof(tmp_pitch_deg)); + if (raw_pitch_deg != 0) { + total_size += 5; + } + + // float yaw_deg = 3 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_yaw_deg = this->_internal_yaw_deg(); + ::uint32_t raw_yaw_deg; + memcpy(&raw_yaw_deg, &tmp_yaw_deg, sizeof(tmp_yaw_deg)); + if (raw_yaw_deg != 0) { + total_size += 5; + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData EulerAngle::_class_data_ = { + EulerAngle::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* EulerAngle::GetClassData() const { + return &_class_data_; +} + +void EulerAngle::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.EulerAngle) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_roll_deg = from._internal_roll_deg(); + ::uint32_t raw_roll_deg; + memcpy(&raw_roll_deg, &tmp_roll_deg, sizeof(tmp_roll_deg)); + if (raw_roll_deg != 0) { + _this->_internal_set_roll_deg(from._internal_roll_deg()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_pitch_deg = from._internal_pitch_deg(); + ::uint32_t raw_pitch_deg; + memcpy(&raw_pitch_deg, &tmp_pitch_deg, sizeof(tmp_pitch_deg)); + if (raw_pitch_deg != 0) { + _this->_internal_set_pitch_deg(from._internal_pitch_deg()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_yaw_deg = from._internal_yaw_deg(); + ::uint32_t raw_yaw_deg; + memcpy(&raw_yaw_deg, &tmp_yaw_deg, sizeof(tmp_yaw_deg)); + if (raw_yaw_deg != 0) { + _this->_internal_set_yaw_deg(from._internal_yaw_deg()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void EulerAngle::CopyFrom(const EulerAngle& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.EulerAngle) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool EulerAngle::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* EulerAngle::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void EulerAngle::InternalSwap(EulerAngle* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.yaw_deg_) + + sizeof(EulerAngle::_impl_.yaw_deg_) + - PROTOBUF_FIELD_OFFSET(EulerAngle, _impl_.roll_deg_)>( + reinterpret_cast(&_impl_.roll_deg_), + reinterpret_cast(&other->_impl_.roll_deg_)); +} + +::google::protobuf::Metadata EulerAngle::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, + file_level_metadata_gimbal_2fgimbal_2eproto[15]); +} +// =================================================================== + +class AngularVelocityBody::_Internal { + public: +}; + +AngularVelocityBody::AngularVelocityBody(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.AngularVelocityBody) +} +AngularVelocityBody::AngularVelocityBody( + ::google::protobuf::Arena* arena, const AngularVelocityBody& from) + : AngularVelocityBody(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE AngularVelocityBody::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void AngularVelocityBody::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, roll_rad_s_), + 0, + offsetof(Impl_, yaw_rad_s_) - + offsetof(Impl_, roll_rad_s_) + + sizeof(Impl_::yaw_rad_s_)); +} +AngularVelocityBody::~AngularVelocityBody() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.AngularVelocityBody) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void AngularVelocityBody::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void AngularVelocityBody::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.AngularVelocityBody) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + ::memset(&_impl_.roll_rad_s_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.yaw_rad_s_) - + reinterpret_cast(&_impl_.roll_rad_s_)) + sizeof(_impl_.yaw_rad_s_)); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* AngularVelocityBody::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<2, 3, 0, 0, 2> AngularVelocityBody::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 3, 24, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967288, // skipmap + offsetof(decltype(_table_), field_entries), + 3, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_AngularVelocityBody_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + {::_pbi::TcParser::MiniParse, {}}, + // float roll_rad_s = 1 [(.mavsdk.options.default_value) = "NaN"]; + {::_pbi::TcParser::FastF32S1, + {13, 63, 0, PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.roll_rad_s_)}}, + // float pitch_rad_s = 2 [(.mavsdk.options.default_value) = "NaN"]; + {::_pbi::TcParser::FastF32S1, + {21, 63, 0, PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.pitch_rad_s_)}}, + // float yaw_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; + {::_pbi::TcParser::FastF32S1, + {29, 63, 0, PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.yaw_rad_s_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // float roll_rad_s = 1 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.roll_rad_s_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float pitch_rad_s = 2 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.pitch_rad_s_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + // float yaw_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; + {PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.yaw_rad_s_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kFloat)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* AngularVelocityBody::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.AngularVelocityBody) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // float roll_rad_s = 1 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_roll_rad_s = this->_internal_roll_rad_s(); + ::uint32_t raw_roll_rad_s; + memcpy(&raw_roll_rad_s, &tmp_roll_rad_s, sizeof(tmp_roll_rad_s)); + if (raw_roll_rad_s != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 1, this->_internal_roll_rad_s(), target); + } + + // float pitch_rad_s = 2 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_pitch_rad_s = this->_internal_pitch_rad_s(); + ::uint32_t raw_pitch_rad_s; + memcpy(&raw_pitch_rad_s, &tmp_pitch_rad_s, sizeof(tmp_pitch_rad_s)); + if (raw_pitch_rad_s != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 2, this->_internal_pitch_rad_s(), target); + } + + // float yaw_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_yaw_rad_s = this->_internal_yaw_rad_s(); + ::uint32_t raw_yaw_rad_s; + memcpy(&raw_yaw_rad_s, &tmp_yaw_rad_s, sizeof(tmp_yaw_rad_s)); + if (raw_yaw_rad_s != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteFloatToArray( + 3, this->_internal_yaw_rad_s(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.AngularVelocityBody) + return target; +} + +::size_t AngularVelocityBody::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.AngularVelocityBody) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // float roll_rad_s = 1 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_roll_rad_s = this->_internal_roll_rad_s(); + ::uint32_t raw_roll_rad_s; + memcpy(&raw_roll_rad_s, &tmp_roll_rad_s, sizeof(tmp_roll_rad_s)); + if (raw_roll_rad_s != 0) { + total_size += 5; + } + + // float pitch_rad_s = 2 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_pitch_rad_s = this->_internal_pitch_rad_s(); + ::uint32_t raw_pitch_rad_s; + memcpy(&raw_pitch_rad_s, &tmp_pitch_rad_s, sizeof(tmp_pitch_rad_s)); + if (raw_pitch_rad_s != 0) { + total_size += 5; + } + + // float yaw_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_yaw_rad_s = this->_internal_yaw_rad_s(); + ::uint32_t raw_yaw_rad_s; + memcpy(&raw_yaw_rad_s, &tmp_yaw_rad_s, sizeof(tmp_yaw_rad_s)); + if (raw_yaw_rad_s != 0) { + total_size += 5; + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData AngularVelocityBody::_class_data_ = { + AngularVelocityBody::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* AngularVelocityBody::GetClassData() const { + return &_class_data_; +} + +void AngularVelocityBody::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.AngularVelocityBody) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_roll_rad_s = from._internal_roll_rad_s(); + ::uint32_t raw_roll_rad_s; + memcpy(&raw_roll_rad_s, &tmp_roll_rad_s, sizeof(tmp_roll_rad_s)); + if (raw_roll_rad_s != 0) { + _this->_internal_set_roll_rad_s(from._internal_roll_rad_s()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_pitch_rad_s = from._internal_pitch_rad_s(); + ::uint32_t raw_pitch_rad_s; + memcpy(&raw_pitch_rad_s, &tmp_pitch_rad_s, sizeof(tmp_pitch_rad_s)); + if (raw_pitch_rad_s != 0) { + _this->_internal_set_pitch_rad_s(from._internal_pitch_rad_s()); + } + static_assert(sizeof(::uint32_t) == sizeof(float), + "Code assumes ::uint32_t and float are the same size."); + float tmp_yaw_rad_s = from._internal_yaw_rad_s(); + ::uint32_t raw_yaw_rad_s; + memcpy(&raw_yaw_rad_s, &tmp_yaw_rad_s, sizeof(tmp_yaw_rad_s)); + if (raw_yaw_rad_s != 0) { + _this->_internal_set_yaw_rad_s(from._internal_yaw_rad_s()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void AngularVelocityBody::CopyFrom(const AngularVelocityBody& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.AngularVelocityBody) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool AngularVelocityBody::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* AngularVelocityBody::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void AngularVelocityBody::InternalSwap(AngularVelocityBody* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.yaw_rad_s_) + + sizeof(AngularVelocityBody::_impl_.yaw_rad_s_) + - PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.roll_rad_s_)>( + reinterpret_cast(&_impl_.roll_rad_s_), + reinterpret_cast(&other->_impl_.roll_rad_s_)); +} + +::google::protobuf::Metadata AngularVelocityBody::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, + file_level_metadata_gimbal_2fgimbal_2eproto[16]); +} +// =================================================================== + +class Attitude::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(Attitude, _impl_._has_bits_); + static const ::mavsdk::rpc::gimbal::EulerAngle& euler_angle_forward(const Attitude* msg); + static void set_has_euler_angle_forward(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } + static const ::mavsdk::rpc::gimbal::Quaternion& quaternion_forward(const Attitude* msg); + static void set_has_quaternion_forward(HasBits* has_bits) { + (*has_bits)[0] |= 2u; + } + static const ::mavsdk::rpc::gimbal::EulerAngle& euler_angle_north(const Attitude* msg); + static void set_has_euler_angle_north(HasBits* has_bits) { + (*has_bits)[0] |= 4u; + } + static const ::mavsdk::rpc::gimbal::Quaternion& quaternion_north(const Attitude* msg); + static void set_has_quaternion_north(HasBits* has_bits) { + (*has_bits)[0] |= 8u; + } + static const ::mavsdk::rpc::gimbal::AngularVelocityBody& angular_velocity(const Attitude* msg); + static void set_has_angular_velocity(HasBits* has_bits) { + (*has_bits)[0] |= 16u; + } +}; + +const ::mavsdk::rpc::gimbal::EulerAngle& Attitude::_Internal::euler_angle_forward(const Attitude* msg) { + return *msg->_impl_.euler_angle_forward_; +} +const ::mavsdk::rpc::gimbal::Quaternion& Attitude::_Internal::quaternion_forward(const Attitude* msg) { + return *msg->_impl_.quaternion_forward_; +} +const ::mavsdk::rpc::gimbal::EulerAngle& Attitude::_Internal::euler_angle_north(const Attitude* msg) { + return *msg->_impl_.euler_angle_north_; +} +const ::mavsdk::rpc::gimbal::Quaternion& Attitude::_Internal::quaternion_north(const Attitude* msg) { + return *msg->_impl_.quaternion_north_; +} +const ::mavsdk::rpc::gimbal::AngularVelocityBody& Attitude::_Internal::angular_velocity(const Attitude* msg) { + return *msg->_impl_.angular_velocity_; +} +Attitude::Attitude(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.Attitude) +} +inline PROTOBUF_NDEBUG_INLINE Attitude::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +Attitude::Attitude( + ::google::protobuf::Arena* arena, + const Attitude& from) + : ::google::protobuf::Message(arena) { + Attitude* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.euler_angle_forward_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::gimbal::EulerAngle>(arena, *from._impl_.euler_angle_forward_) + : nullptr; + _impl_.quaternion_forward_ = (cached_has_bits & 0x00000002u) + ? CreateMaybeMessage<::mavsdk::rpc::gimbal::Quaternion>(arena, *from._impl_.quaternion_forward_) + : nullptr; + _impl_.euler_angle_north_ = (cached_has_bits & 0x00000004u) + ? CreateMaybeMessage<::mavsdk::rpc::gimbal::EulerAngle>(arena, *from._impl_.euler_angle_north_) + : nullptr; + _impl_.quaternion_north_ = (cached_has_bits & 0x00000008u) + ? CreateMaybeMessage<::mavsdk::rpc::gimbal::Quaternion>(arena, *from._impl_.quaternion_north_) + : nullptr; + _impl_.angular_velocity_ = (cached_has_bits & 0x00000010u) + ? CreateMaybeMessage<::mavsdk::rpc::gimbal::AngularVelocityBody>(arena, *from._impl_.angular_velocity_) + : nullptr; + ::memcpy(reinterpret_cast(&_impl_) + + offsetof(Impl_, timestamp_us_), + reinterpret_cast(&from._impl_) + + offsetof(Impl_, timestamp_us_), + offsetof(Impl_, gimbal_id_) - + offsetof(Impl_, timestamp_us_) + + sizeof(Impl_::gimbal_id_)); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.Attitude) +} +inline PROTOBUF_NDEBUG_INLINE Attitude::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void Attitude::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, euler_angle_forward_), + 0, + offsetof(Impl_, gimbal_id_) - + offsetof(Impl_, euler_angle_forward_) + + sizeof(Impl_::gimbal_id_)); +} +Attitude::~Attitude() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.Attitude) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void Attitude::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.euler_angle_forward_; + delete _impl_.quaternion_forward_; + delete _impl_.euler_angle_north_; + delete _impl_.quaternion_north_; + delete _impl_.angular_velocity_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void Attitude::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.Attitude) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x0000001fu) { + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.euler_angle_forward_ != nullptr); + _impl_.euler_angle_forward_->Clear(); + } + if (cached_has_bits & 0x00000002u) { + ABSL_DCHECK(_impl_.quaternion_forward_ != nullptr); + _impl_.quaternion_forward_->Clear(); + } + if (cached_has_bits & 0x00000004u) { + ABSL_DCHECK(_impl_.euler_angle_north_ != nullptr); + _impl_.euler_angle_north_->Clear(); + } + if (cached_has_bits & 0x00000008u) { + ABSL_DCHECK(_impl_.quaternion_north_ != nullptr); + _impl_.quaternion_north_->Clear(); + } + if (cached_has_bits & 0x00000010u) { + ABSL_DCHECK(_impl_.angular_velocity_ != nullptr); + _impl_.angular_velocity_->Clear(); + } + } + ::memset(&_impl_.timestamp_us_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.gimbal_id_) - + reinterpret_cast(&_impl_.timestamp_us_)) + sizeof(_impl_.gimbal_id_)); + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* Attitude::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<3, 7, 5, 0, 2> Attitude::_table_ = { + { + PROTOBUF_FIELD_OFFSET(Attitude, _impl_._has_bits_), + 0, // no _extensions_ + 7, 56, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967168, // skipmap + offsetof(decltype(_table_), field_entries), + 7, // num_field_entries + 5, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_Attitude_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + {::_pbi::TcParser::MiniParse, {}}, + // int32 gimbal_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(Attitude, _impl_.gimbal_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(Attitude, _impl_.gimbal_id_)}}, + // .mavsdk.rpc.gimbal.EulerAngle euler_angle_forward = 2; + {::_pbi::TcParser::FastMtS1, + {18, 0, 0, PROTOBUF_FIELD_OFFSET(Attitude, _impl_.euler_angle_forward_)}}, + // .mavsdk.rpc.gimbal.Quaternion quaternion_forward = 3; + {::_pbi::TcParser::FastMtS1, + {26, 1, 1, PROTOBUF_FIELD_OFFSET(Attitude, _impl_.quaternion_forward_)}}, + // .mavsdk.rpc.gimbal.EulerAngle euler_angle_north = 4; + {::_pbi::TcParser::FastMtS1, + {34, 2, 2, PROTOBUF_FIELD_OFFSET(Attitude, _impl_.euler_angle_north_)}}, + // .mavsdk.rpc.gimbal.Quaternion quaternion_north = 5; + {::_pbi::TcParser::FastMtS1, + {42, 3, 3, PROTOBUF_FIELD_OFFSET(Attitude, _impl_.quaternion_north_)}}, + // .mavsdk.rpc.gimbal.AngularVelocityBody angular_velocity = 6; + {::_pbi::TcParser::FastMtS1, + {50, 4, 4, PROTOBUF_FIELD_OFFSET(Attitude, _impl_.angular_velocity_)}}, + // uint64 timestamp_us = 7; + {::_pbi::TcParser::SingularVarintNoZag1<::uint64_t, offsetof(Attitude, _impl_.timestamp_us_), 63>(), + {56, 63, 0, PROTOBUF_FIELD_OFFSET(Attitude, _impl_.timestamp_us_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 gimbal_id = 1; + {PROTOBUF_FIELD_OFFSET(Attitude, _impl_.gimbal_id_), -1, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // .mavsdk.rpc.gimbal.EulerAngle euler_angle_forward = 2; + {PROTOBUF_FIELD_OFFSET(Attitude, _impl_.euler_angle_forward_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // .mavsdk.rpc.gimbal.Quaternion quaternion_forward = 3; + {PROTOBUF_FIELD_OFFSET(Attitude, _impl_.quaternion_forward_), _Internal::kHasBitsOffset + 1, 1, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // .mavsdk.rpc.gimbal.EulerAngle euler_angle_north = 4; + {PROTOBUF_FIELD_OFFSET(Attitude, _impl_.euler_angle_north_), _Internal::kHasBitsOffset + 2, 2, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // .mavsdk.rpc.gimbal.Quaternion quaternion_north = 5; + {PROTOBUF_FIELD_OFFSET(Attitude, _impl_.quaternion_north_), _Internal::kHasBitsOffset + 3, 3, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // .mavsdk.rpc.gimbal.AngularVelocityBody angular_velocity = 6; + {PROTOBUF_FIELD_OFFSET(Attitude, _impl_.angular_velocity_), _Internal::kHasBitsOffset + 4, 4, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // uint64 timestamp_us = 7; + {PROTOBUF_FIELD_OFFSET(Attitude, _impl_.timestamp_us_), -1, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUInt64)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::EulerAngle>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::Quaternion>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::EulerAngle>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::Quaternion>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::AngularVelocityBody>()}, + }}, {{ + }}, +}; + +::uint8_t* Attitude::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.Attitude) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_gimbal_id(), target); + } + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.gimbal.EulerAngle euler_angle_forward = 2; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 2, _Internal::euler_angle_forward(this), + _Internal::euler_angle_forward(this).GetCachedSize(), target, stream); + } + + // .mavsdk.rpc.gimbal.Quaternion quaternion_forward = 3; + if (cached_has_bits & 0x00000002u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 3, _Internal::quaternion_forward(this), + _Internal::quaternion_forward(this).GetCachedSize(), target, stream); + } + + // .mavsdk.rpc.gimbal.EulerAngle euler_angle_north = 4; + if (cached_has_bits & 0x00000004u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 4, _Internal::euler_angle_north(this), + _Internal::euler_angle_north(this).GetCachedSize(), target, stream); + } + + // .mavsdk.rpc.gimbal.Quaternion quaternion_north = 5; + if (cached_has_bits & 0x00000008u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 5, _Internal::quaternion_north(this), + _Internal::quaternion_north(this).GetCachedSize(), target, stream); + } + + // .mavsdk.rpc.gimbal.AngularVelocityBody angular_velocity = 6; + if (cached_has_bits & 0x00000010u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 6, _Internal::angular_velocity(this), + _Internal::angular_velocity(this).GetCachedSize(), target, stream); + } + + // uint64 timestamp_us = 7; + if (this->_internal_timestamp_us() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteUInt64ToArray( + 7, this->_internal_timestamp_us(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.Attitude) + return target; +} + +::size_t Attitude::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.Attitude) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x0000001fu) { + // .mavsdk.rpc.gimbal.EulerAngle euler_angle_forward = 2; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.euler_angle_forward_); + } + + // .mavsdk.rpc.gimbal.Quaternion quaternion_forward = 3; + if (cached_has_bits & 0x00000002u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.quaternion_forward_); + } + + // .mavsdk.rpc.gimbal.EulerAngle euler_angle_north = 4; + if (cached_has_bits & 0x00000004u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.euler_angle_north_); + } + + // .mavsdk.rpc.gimbal.Quaternion quaternion_north = 5; + if (cached_has_bits & 0x00000008u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.quaternion_north_); + } + + // .mavsdk.rpc.gimbal.AngularVelocityBody angular_velocity = 6; + if (cached_has_bits & 0x00000010u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.angular_velocity_); + } + + } + // uint64 timestamp_us = 7; + if (this->_internal_timestamp_us() != 0) { + total_size += ::_pbi::WireFormatLite::UInt64SizePlusOne( + this->_internal_timestamp_us()); + } + + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_gimbal_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData Attitude::_class_data_ = { + Attitude::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* Attitude::GetClassData() const { + return &_class_data_; +} + +void Attitude::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.Attitude) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = from._impl_._has_bits_[0]; + if (cached_has_bits & 0x0000001fu) { + if (cached_has_bits & 0x00000001u) { + _this->_internal_mutable_euler_angle_forward()->::mavsdk::rpc::gimbal::EulerAngle::MergeFrom( + from._internal_euler_angle_forward()); + } + if (cached_has_bits & 0x00000002u) { + _this->_internal_mutable_quaternion_forward()->::mavsdk::rpc::gimbal::Quaternion::MergeFrom( + from._internal_quaternion_forward()); + } + if (cached_has_bits & 0x00000004u) { + _this->_internal_mutable_euler_angle_north()->::mavsdk::rpc::gimbal::EulerAngle::MergeFrom( + from._internal_euler_angle_north()); + } + if (cached_has_bits & 0x00000008u) { + _this->_internal_mutable_quaternion_north()->::mavsdk::rpc::gimbal::Quaternion::MergeFrom( + from._internal_quaternion_north()); + } + if (cached_has_bits & 0x00000010u) { + _this->_internal_mutable_angular_velocity()->::mavsdk::rpc::gimbal::AngularVelocityBody::MergeFrom( + from._internal_angular_velocity()); + } + } + if (from._internal_timestamp_us() != 0) { + _this->_internal_set_timestamp_us(from._internal_timestamp_us()); + } + if (from._internal_gimbal_id() != 0) { + _this->_internal_set_gimbal_id(from._internal_gimbal_id()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void Attitude::CopyFrom(const Attitude& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.Attitude) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool Attitude::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* Attitude::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void Attitude::InternalSwap(Attitude* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(Attitude, _impl_.gimbal_id_) + + sizeof(Attitude::_impl_.gimbal_id_) + - PROTOBUF_FIELD_OFFSET(Attitude, _impl_.euler_angle_forward_)>( + reinterpret_cast(&_impl_.euler_angle_forward_), + reinterpret_cast(&other->_impl_.euler_angle_forward_)); +} + +::google::protobuf::Metadata Attitude::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, + file_level_metadata_gimbal_2fgimbal_2eproto[17]); +} +// =================================================================== + +class SubscribeAttitudeRequest::_Internal { + public: +}; + +SubscribeAttitudeRequest::SubscribeAttitudeRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.SubscribeAttitudeRequest) +} +SubscribeAttitudeRequest::SubscribeAttitudeRequest( + ::google::protobuf::Arena* arena, + const SubscribeAttitudeRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + SubscribeAttitudeRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.SubscribeAttitudeRequest) +} + + + + + + + + + +::google::protobuf::Metadata SubscribeAttitudeRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, + file_level_metadata_gimbal_2fgimbal_2eproto[18]); +} +// =================================================================== + +class AttitudeResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(AttitudeResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::gimbal::Attitude& attitude(const AttitudeResponse* msg); + static void set_has_attitude(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::gimbal::Attitude& AttitudeResponse::_Internal::attitude(const AttitudeResponse* msg) { + return *msg->_impl_.attitude_; +} +AttitudeResponse::AttitudeResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.AttitudeResponse) +} +inline PROTOBUF_NDEBUG_INLINE AttitudeResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +AttitudeResponse::AttitudeResponse( + ::google::protobuf::Arena* arena, + const AttitudeResponse& from) + : ::google::protobuf::Message(arena) { + AttitudeResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.attitude_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::gimbal::Attitude>(arena, *from._impl_.attitude_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.AttitudeResponse) +} +inline PROTOBUF_NDEBUG_INLINE AttitudeResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void AttitudeResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.attitude_ = {}; +} +AttitudeResponse::~AttitudeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.AttitudeResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void AttitudeResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.attitude_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void AttitudeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.AttitudeResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.attitude_ != nullptr); + _impl_.attitude_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* AttitudeResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> AttitudeResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(AttitudeResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_AttitudeResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.gimbal.Attitude attitude = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(AttitudeResponse, _impl_.attitude_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.gimbal.Attitude attitude = 1; + {PROTOBUF_FIELD_OFFSET(AttitudeResponse, _impl_.attitude_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::Attitude>()}, + }}, {{ + }}, +}; + +::uint8_t* AttitudeResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.AttitudeResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.gimbal.Attitude attitude = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::attitude(this), + _Internal::attitude(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.AttitudeResponse) + return target; +} + +::size_t AttitudeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.AttitudeResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // .mavsdk.rpc.gimbal.Attitude attitude = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.attitude_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData AttitudeResponse::_class_data_ = { + AttitudeResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* AttitudeResponse::GetClassData() const { + return &_class_data_; +} + +void AttitudeResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.AttitudeResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_attitude()->::mavsdk::rpc::gimbal::Attitude::MergeFrom( + from._internal_attitude()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void AttitudeResponse::CopyFrom(const AttitudeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.AttitudeResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool AttitudeResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* AttitudeResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void AttitudeResponse::InternalSwap(AttitudeResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.attitude_, other->_impl_.attitude_); +} + +::google::protobuf::Metadata AttitudeResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, + file_level_metadata_gimbal_2fgimbal_2eproto[19]); +} +// =================================================================== + +class GetAttitudeRequest::_Internal { + public: +}; + +GetAttitudeRequest::GetAttitudeRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.GetAttitudeRequest) +} +GetAttitudeRequest::GetAttitudeRequest( + ::google::protobuf::Arena* arena, const GetAttitudeRequest& from) + : GetAttitudeRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE GetAttitudeRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void GetAttitudeRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.gimbal_id_ = {}; +} +GetAttitudeRequest::~GetAttitudeRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.GetAttitudeRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void GetAttitudeRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void GetAttitudeRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.GetAttitudeRequest) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + _impl_.gimbal_id_ = 0; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* GetAttitudeRequest::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 0, 0, 2> GetAttitudeRequest::_table_ = { + { + 0, // no _has_bits_ + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_GetAttitudeRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // int32 gimbal_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(GetAttitudeRequest, _impl_.gimbal_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(GetAttitudeRequest, _impl_.gimbal_id_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // int32 gimbal_id = 1; + {PROTOBUF_FIELD_OFFSET(GetAttitudeRequest, _impl_.gimbal_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* GetAttitudeRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.GetAttitudeRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_gimbal_id(), target); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.GetAttitudeRequest) + return target; +} + +::size_t GetAttitudeRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.GetAttitudeRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_gimbal_id()); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData GetAttitudeRequest::_class_data_ = { + GetAttitudeRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* GetAttitudeRequest::GetClassData() const { + return &_class_data_; +} + +void GetAttitudeRequest::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.GetAttitudeRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_gimbal_id() != 0) { + _this->_internal_set_gimbal_id(from._internal_gimbal_id()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void GetAttitudeRequest::CopyFrom(const GetAttitudeRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.GetAttitudeRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool GetAttitudeRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* GetAttitudeRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void GetAttitudeRequest::InternalSwap(GetAttitudeRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.gimbal_id_, other->_impl_.gimbal_id_); +} + +::google::protobuf::Metadata GetAttitudeRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, + file_level_metadata_gimbal_2fgimbal_2eproto[20]); +} +// =================================================================== + +class GetAttitudeResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(GetAttitudeResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::gimbal::GimbalResult& gimbal_result(const GetAttitudeResponse* msg); + static void set_has_gimbal_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } + static const ::mavsdk::rpc::gimbal::Attitude& attitude(const GetAttitudeResponse* msg); + static void set_has_attitude(HasBits* has_bits) { + (*has_bits)[0] |= 2u; + } +}; + +const ::mavsdk::rpc::gimbal::GimbalResult& GetAttitudeResponse::_Internal::gimbal_result(const GetAttitudeResponse* msg) { + return *msg->_impl_.gimbal_result_; +} +const ::mavsdk::rpc::gimbal::Attitude& GetAttitudeResponse::_Internal::attitude(const GetAttitudeResponse* msg) { + return *msg->_impl_.attitude_; +} +GetAttitudeResponse::GetAttitudeResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.GetAttitudeResponse) +} +inline PROTOBUF_NDEBUG_INLINE GetAttitudeResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +GetAttitudeResponse::GetAttitudeResponse( + ::google::protobuf::Arena* arena, + const GetAttitudeResponse& from) + : ::google::protobuf::Message(arena) { + GetAttitudeResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.gimbal_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::gimbal::GimbalResult>(arena, *from._impl_.gimbal_result_) + : nullptr; + _impl_.attitude_ = (cached_has_bits & 0x00000002u) + ? CreateMaybeMessage<::mavsdk::rpc::gimbal::Attitude>(arena, *from._impl_.attitude_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.GetAttitudeResponse) +} +inline PROTOBUF_NDEBUG_INLINE GetAttitudeResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void GetAttitudeResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + ::memset(reinterpret_cast(&_impl_) + + offsetof(Impl_, gimbal_result_), + 0, + offsetof(Impl_, attitude_) - + offsetof(Impl_, gimbal_result_) + + sizeof(Impl_::attitude_)); +} +GetAttitudeResponse::~GetAttitudeResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.GetAttitudeResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void GetAttitudeResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.gimbal_result_; + delete _impl_.attitude_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void GetAttitudeResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.GetAttitudeResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.gimbal_result_ != nullptr); + _impl_.gimbal_result_->Clear(); + } + if (cached_has_bits & 0x00000002u) { + ABSL_DCHECK(_impl_.attitude_ != nullptr); + _impl_.attitude_->Clear(); + } + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* GetAttitudeResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<1, 2, 2, 0, 2> GetAttitudeResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(GetAttitudeResponse, _impl_._has_bits_), + 0, // no _extensions_ + 2, 8, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967292, // skipmap + offsetof(decltype(_table_), field_entries), + 2, // num_field_entries + 2, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_GetAttitudeResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.gimbal.Attitude attitude = 2; + {::_pbi::TcParser::FastMtS1, + {18, 1, 1, PROTOBUF_FIELD_OFFSET(GetAttitudeResponse, _impl_.attitude_)}}, + // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(GetAttitudeResponse, _impl_.gimbal_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; + {PROTOBUF_FIELD_OFFSET(GetAttitudeResponse, _impl_.gimbal_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // .mavsdk.rpc.gimbal.Attitude attitude = 2; + {PROTOBUF_FIELD_OFFSET(GetAttitudeResponse, _impl_.attitude_), _Internal::kHasBitsOffset + 1, 1, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::GimbalResult>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::Attitude>()}, + }}, {{ + }}, +}; + +::uint8_t* GetAttitudeResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.GetAttitudeResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::gimbal_result(this), + _Internal::gimbal_result(this).GetCachedSize(), target, stream); + } + + // .mavsdk.rpc.gimbal.Attitude attitude = 2; + if (cached_has_bits & 0x00000002u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 2, _Internal::attitude(this), + _Internal::attitude(this).GetCachedSize(), target, stream); + } + + if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { + target = + ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( + _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); + } + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.GetAttitudeResponse) + return target; +} + +::size_t GetAttitudeResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.GetAttitudeResponse) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.gimbal_result_); + } + + // .mavsdk.rpc.gimbal.Attitude attitude = 2; + if (cached_has_bits & 0x00000002u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.attitude_); + } + + } + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData GetAttitudeResponse::_class_data_ = { + GetAttitudeResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* GetAttitudeResponse::GetClassData() const { + return &_class_data_; +} + +void GetAttitudeResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.GetAttitudeResponse) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + cached_has_bits = from._impl_._has_bits_[0]; + if (cached_has_bits & 0x00000003u) { + if (cached_has_bits & 0x00000001u) { + _this->_internal_mutable_gimbal_result()->::mavsdk::rpc::gimbal::GimbalResult::MergeFrom( + from._internal_gimbal_result()); + } + if (cached_has_bits & 0x00000002u) { + _this->_internal_mutable_attitude()->::mavsdk::rpc::gimbal::Attitude::MergeFrom( + from._internal_attitude()); + } + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void GetAttitudeResponse::CopyFrom(const GetAttitudeResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.GetAttitudeResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool GetAttitudeResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* GetAttitudeResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void GetAttitudeResponse::InternalSwap(GetAttitudeResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + ::google::protobuf::internal::memswap< + PROTOBUF_FIELD_OFFSET(GetAttitudeResponse, _impl_.attitude_) + + sizeof(GetAttitudeResponse::_impl_.attitude_) + - PROTOBUF_FIELD_OFFSET(GetAttitudeResponse, _impl_.gimbal_result_)>( + reinterpret_cast(&_impl_.gimbal_result_), + reinterpret_cast(&other->_impl_.gimbal_result_)); +} + +::google::protobuf::Metadata GetAttitudeResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, + file_level_metadata_gimbal_2fgimbal_2eproto[21]); +} +// =================================================================== + +class SubscribeGimbalListRequest::_Internal { + public: +}; + +SubscribeGimbalListRequest::SubscribeGimbalListRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.SubscribeGimbalListRequest) +} +SubscribeGimbalListRequest::SubscribeGimbalListRequest( + ::google::protobuf::Arena* arena, + const SubscribeGimbalListRequest& from) + : ::google::protobuf::internal::ZeroFieldsBase(arena) { + SubscribeGimbalListRequest* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.SubscribeGimbalListRequest) +} + + + + + + + + + +::google::protobuf::Metadata SubscribeGimbalListRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, + file_level_metadata_gimbal_2fgimbal_2eproto[22]); +} +// =================================================================== + +class GimbalListResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(GimbalListResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::gimbal::GimbalList& gimbal_list(const GimbalListResponse* msg); + static void set_has_gimbal_list(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::gimbal::GimbalList& GimbalListResponse::_Internal::gimbal_list(const GimbalListResponse* msg) { + return *msg->_impl_.gimbal_list_; +} +GimbalListResponse::GimbalListResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.GimbalListResponse) +} +inline PROTOBUF_NDEBUG_INLINE GimbalListResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +GimbalListResponse::GimbalListResponse( + ::google::protobuf::Arena* arena, + const GimbalListResponse& from) + : ::google::protobuf::Message(arena) { + GimbalListResponse* const _this = this; + (void)_this; + _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( + from._internal_metadata_); + new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); + ::uint32_t cached_has_bits = _impl_._has_bits_[0]; + _impl_.gimbal_list_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::gimbal::GimbalList>(arena, *from._impl_.gimbal_list_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.GimbalListResponse) +} +inline PROTOBUF_NDEBUG_INLINE GimbalListResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void GimbalListResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.gimbal_list_ = {}; +} +GimbalListResponse::~GimbalListResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.GimbalListResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void GimbalListResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.gimbal_list_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void GimbalListResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.GimbalListResponse) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + ABSL_DCHECK(_impl_.gimbal_list_ != nullptr); + _impl_.gimbal_list_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* GimbalListResponse::_InternalParse( + const char* ptr, ::_pbi::ParseContext* ctx) { + ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); + return ptr; +} + + +PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> GimbalListResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(GimbalListResponse, _impl_._has_bits_), + 0, // no _extensions_ + 1, 0, // max_field_number, fast_idx_mask + offsetof(decltype(_table_), field_lookup_table), + 4294967294, // skipmap + offsetof(decltype(_table_), field_entries), + 1, // num_field_entries + 1, // num_aux_entries + offsetof(decltype(_table_), aux_entries), + &_GimbalListResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.gimbal.GimbalList gimbal_list = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(GimbalListResponse, _impl_.gimbal_list_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.gimbal.GimbalList gimbal_list = 1; + {PROTOBUF_FIELD_OFFSET(GimbalListResponse, _impl_.gimbal_list_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::GimbalList>()}, + }}, {{ + }}, +}; - // float yaw_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_yaw_rad_s = this->_internal_yaw_rad_s(); - ::uint32_t raw_yaw_rad_s; - memcpy(&raw_yaw_rad_s, &tmp_yaw_rad_s, sizeof(tmp_yaw_rad_s)); - if (raw_yaw_rad_s != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteFloatToArray( - 3, this->_internal_yaw_rad_s(), target); +::uint8_t* GimbalListResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.GimbalListResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.gimbal.GimbalList gimbal_list = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::gimbal_list(this), + _Internal::gimbal_list(this).GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -3970,273 +6342,162 @@ ::uint8_t* AngularVelocityBody::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.AngularVelocityBody) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.GimbalListResponse) return target; } -::size_t AngularVelocityBody::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.AngularVelocityBody) +::size_t GimbalListResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.GimbalListResponse) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // float roll_rad_s = 1 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_roll_rad_s = this->_internal_roll_rad_s(); - ::uint32_t raw_roll_rad_s; - memcpy(&raw_roll_rad_s, &tmp_roll_rad_s, sizeof(tmp_roll_rad_s)); - if (raw_roll_rad_s != 0) { - total_size += 5; - } - - // float pitch_rad_s = 2 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_pitch_rad_s = this->_internal_pitch_rad_s(); - ::uint32_t raw_pitch_rad_s; - memcpy(&raw_pitch_rad_s, &tmp_pitch_rad_s, sizeof(tmp_pitch_rad_s)); - if (raw_pitch_rad_s != 0) { - total_size += 5; - } - - // float yaw_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_yaw_rad_s = this->_internal_yaw_rad_s(); - ::uint32_t raw_yaw_rad_s; - memcpy(&raw_yaw_rad_s, &tmp_yaw_rad_s, sizeof(tmp_yaw_rad_s)); - if (raw_yaw_rad_s != 0) { - total_size += 5; + // .mavsdk.rpc.gimbal.GimbalList gimbal_list = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.gimbal_list_); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData AngularVelocityBody::_class_data_ = { - AngularVelocityBody::MergeImpl, +const ::google::protobuf::Message::ClassData GimbalListResponse::_class_data_ = { + GimbalListResponse::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* AngularVelocityBody::GetClassData() const { +const ::google::protobuf::Message::ClassData* GimbalListResponse::GetClassData() const { return &_class_data_; } -void AngularVelocityBody::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.AngularVelocityBody) +void GimbalListResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.GimbalListResponse) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_roll_rad_s = from._internal_roll_rad_s(); - ::uint32_t raw_roll_rad_s; - memcpy(&raw_roll_rad_s, &tmp_roll_rad_s, sizeof(tmp_roll_rad_s)); - if (raw_roll_rad_s != 0) { - _this->_internal_set_roll_rad_s(from._internal_roll_rad_s()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_pitch_rad_s = from._internal_pitch_rad_s(); - ::uint32_t raw_pitch_rad_s; - memcpy(&raw_pitch_rad_s, &tmp_pitch_rad_s, sizeof(tmp_pitch_rad_s)); - if (raw_pitch_rad_s != 0) { - _this->_internal_set_pitch_rad_s(from._internal_pitch_rad_s()); - } - static_assert(sizeof(::uint32_t) == sizeof(float), - "Code assumes ::uint32_t and float are the same size."); - float tmp_yaw_rad_s = from._internal_yaw_rad_s(); - ::uint32_t raw_yaw_rad_s; - memcpy(&raw_yaw_rad_s, &tmp_yaw_rad_s, sizeof(tmp_yaw_rad_s)); - if (raw_yaw_rad_s != 0) { - _this->_internal_set_yaw_rad_s(from._internal_yaw_rad_s()); + if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { + _this->_internal_mutable_gimbal_list()->::mavsdk::rpc::gimbal::GimbalList::MergeFrom( + from._internal_gimbal_list()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void AngularVelocityBody::CopyFrom(const AngularVelocityBody& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.AngularVelocityBody) +void GimbalListResponse::CopyFrom(const GimbalListResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.GimbalListResponse) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool AngularVelocityBody::IsInitialized() const { +PROTOBUF_NOINLINE bool GimbalListResponse::IsInitialized() const { return true; } -::_pbi::CachedSize* AngularVelocityBody::AccessCachedSize() const { +::_pbi::CachedSize* GimbalListResponse::AccessCachedSize() const { return &_impl_._cached_size_; } -void AngularVelocityBody::InternalSwap(AngularVelocityBody* PROTOBUF_RESTRICT other) { +void GimbalListResponse::InternalSwap(GimbalListResponse* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - ::google::protobuf::internal::memswap< - PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.yaw_rad_s_) - + sizeof(AngularVelocityBody::_impl_.yaw_rad_s_) - - PROTOBUF_FIELD_OFFSET(AngularVelocityBody, _impl_.roll_rad_s_)>( - reinterpret_cast(&_impl_.roll_rad_s_), - reinterpret_cast(&other->_impl_.roll_rad_s_)); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.gimbal_list_, other->_impl_.gimbal_list_); } -::google::protobuf::Metadata AngularVelocityBody::GetMetadata() const { +::google::protobuf::Metadata GimbalListResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, - file_level_metadata_gimbal_2fgimbal_2eproto[14]); + file_level_metadata_gimbal_2fgimbal_2eproto[23]); } // =================================================================== -class Attitude::_Internal { +class GimbalItem::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(Attitude, _impl_._has_bits_); - static const ::mavsdk::rpc::gimbal::EulerAngle& euler_angle_forward(const Attitude* msg); - static void set_has_euler_angle_forward(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } - static const ::mavsdk::rpc::gimbal::Quaternion& quaternion_forward(const Attitude* msg); - static void set_has_quaternion_forward(HasBits* has_bits) { - (*has_bits)[0] |= 2u; - } - static const ::mavsdk::rpc::gimbal::EulerAngle& euler_angle_north(const Attitude* msg); - static void set_has_euler_angle_north(HasBits* has_bits) { - (*has_bits)[0] |= 4u; - } - static const ::mavsdk::rpc::gimbal::Quaternion& quaternion_north(const Attitude* msg); - static void set_has_quaternion_north(HasBits* has_bits) { - (*has_bits)[0] |= 8u; - } - static const ::mavsdk::rpc::gimbal::AngularVelocityBody& angular_velocity(const Attitude* msg); - static void set_has_angular_velocity(HasBits* has_bits) { - (*has_bits)[0] |= 16u; - } }; -const ::mavsdk::rpc::gimbal::EulerAngle& Attitude::_Internal::euler_angle_forward(const Attitude* msg) { - return *msg->_impl_.euler_angle_forward_; -} -const ::mavsdk::rpc::gimbal::Quaternion& Attitude::_Internal::quaternion_forward(const Attitude* msg) { - return *msg->_impl_.quaternion_forward_; -} -const ::mavsdk::rpc::gimbal::EulerAngle& Attitude::_Internal::euler_angle_north(const Attitude* msg) { - return *msg->_impl_.euler_angle_north_; -} -const ::mavsdk::rpc::gimbal::Quaternion& Attitude::_Internal::quaternion_north(const Attitude* msg) { - return *msg->_impl_.quaternion_north_; -} -const ::mavsdk::rpc::gimbal::AngularVelocityBody& Attitude::_Internal::angular_velocity(const Attitude* msg) { - return *msg->_impl_.angular_velocity_; -} -Attitude::Attitude(::google::protobuf::Arena* arena) +GimbalItem::GimbalItem(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.Attitude) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.GimbalItem) } -inline PROTOBUF_NDEBUG_INLINE Attitude::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GimbalItem::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) - : _has_bits_{from._has_bits_}, + : vendor_name_(arena, from.vendor_name_), + model_name_(arena, from.model_name_), + custom_name_(arena, from.custom_name_), _cached_size_{0} {} -Attitude::Attitude( +GimbalItem::GimbalItem( ::google::protobuf::Arena* arena, - const Attitude& from) + const GimbalItem& from) : ::google::protobuf::Message(arena) { - Attitude* const _this = this; + GimbalItem* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); - ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.euler_angle_forward_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::gimbal::EulerAngle>(arena, *from._impl_.euler_angle_forward_) - : nullptr; - _impl_.quaternion_forward_ = (cached_has_bits & 0x00000002u) - ? CreateMaybeMessage<::mavsdk::rpc::gimbal::Quaternion>(arena, *from._impl_.quaternion_forward_) - : nullptr; - _impl_.euler_angle_north_ = (cached_has_bits & 0x00000004u) - ? CreateMaybeMessage<::mavsdk::rpc::gimbal::EulerAngle>(arena, *from._impl_.euler_angle_north_) - : nullptr; - _impl_.quaternion_north_ = (cached_has_bits & 0x00000008u) - ? CreateMaybeMessage<::mavsdk::rpc::gimbal::Quaternion>(arena, *from._impl_.quaternion_north_) - : nullptr; - _impl_.angular_velocity_ = (cached_has_bits & 0x00000010u) - ? CreateMaybeMessage<::mavsdk::rpc::gimbal::AngularVelocityBody>(arena, *from._impl_.angular_velocity_) - : nullptr; - _impl_.timestamp_us_ = from._impl_.timestamp_us_; + ::memcpy(reinterpret_cast(&_impl_) + + offsetof(Impl_, gimbal_id_), + reinterpret_cast(&from._impl_) + + offsetof(Impl_, gimbal_id_), + offsetof(Impl_, gimbal_device_id_) - + offsetof(Impl_, gimbal_id_) + + sizeof(Impl_::gimbal_device_id_)); - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.Attitude) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.GimbalItem) } -inline PROTOBUF_NDEBUG_INLINE Attitude::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GimbalItem::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) - : _cached_size_{0} {} + : vendor_name_(arena), + model_name_(arena), + custom_name_(arena), + _cached_size_{0} {} -inline void Attitude::SharedCtor(::_pb::Arena* arena) { +inline void GimbalItem::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); ::memset(reinterpret_cast(&_impl_) + - offsetof(Impl_, euler_angle_forward_), + offsetof(Impl_, gimbal_id_), 0, - offsetof(Impl_, timestamp_us_) - - offsetof(Impl_, euler_angle_forward_) + - sizeof(Impl_::timestamp_us_)); + offsetof(Impl_, gimbal_device_id_) - + offsetof(Impl_, gimbal_id_) + + sizeof(Impl_::gimbal_device_id_)); } -Attitude::~Attitude() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.Attitude) +GimbalItem::~GimbalItem() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.GimbalItem) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void Attitude::SharedDtor() { +inline void GimbalItem::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.euler_angle_forward_; - delete _impl_.quaternion_forward_; - delete _impl_.euler_angle_north_; - delete _impl_.quaternion_north_; - delete _impl_.angular_velocity_; + _impl_.vendor_name_.Destroy(); + _impl_.model_name_.Destroy(); + _impl_.custom_name_.Destroy(); _impl_.~Impl_(); } -PROTOBUF_NOINLINE void Attitude::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.Attitude) +PROTOBUF_NOINLINE void GimbalItem::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.GimbalItem) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x0000001fu) { - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.euler_angle_forward_ != nullptr); - _impl_.euler_angle_forward_->Clear(); - } - if (cached_has_bits & 0x00000002u) { - ABSL_DCHECK(_impl_.quaternion_forward_ != nullptr); - _impl_.quaternion_forward_->Clear(); - } - if (cached_has_bits & 0x00000004u) { - ABSL_DCHECK(_impl_.euler_angle_north_ != nullptr); - _impl_.euler_angle_north_->Clear(); - } - if (cached_has_bits & 0x00000008u) { - ABSL_DCHECK(_impl_.quaternion_north_ != nullptr); - _impl_.quaternion_north_->Clear(); - } - if (cached_has_bits & 0x00000010u) { - ABSL_DCHECK(_impl_.angular_velocity_ != nullptr); - _impl_.angular_velocity_->Clear(); - } - } - _impl_.timestamp_us_ = ::uint64_t{0u}; - _impl_._has_bits_.Clear(); + _impl_.vendor_name_.ClearToEmpty(); + _impl_.model_name_.ClearToEmpty(); + _impl_.custom_name_.ClearToEmpty(); + ::memset(&_impl_.gimbal_id_, 0, static_cast<::size_t>( + reinterpret_cast(&_impl_.gimbal_device_id_) - + reinterpret_cast(&_impl_.gimbal_id_)) + sizeof(_impl_.gimbal_device_id_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* Attitude::_InternalParse( +const char* GimbalItem::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -4244,119 +6505,122 @@ const char* Attitude::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<3, 6, 5, 0, 2> Attitude::_table_ = { +const ::_pbi::TcParseTable<3, 6, 0, 69, 2> GimbalItem::_table_ = { { - PROTOBUF_FIELD_OFFSET(Attitude, _impl_._has_bits_), + 0, // no _has_bits_ 0, // no _extensions_ 6, 56, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), 4294967232, // skipmap offsetof(decltype(_table_), field_entries), 6, // num_field_entries - 5, // num_aux_entries - offsetof(decltype(_table_), aux_entries), - &_Attitude_default_instance_._instance, + 0, // num_aux_entries + offsetof(decltype(_table_), field_names), // no aux_entries + &_GimbalItem_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ {::_pbi::TcParser::MiniParse, {}}, - // .mavsdk.rpc.gimbal.EulerAngle euler_angle_forward = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(Attitude, _impl_.euler_angle_forward_)}}, - // .mavsdk.rpc.gimbal.Quaternion quaternion_forward = 2; - {::_pbi::TcParser::FastMtS1, - {18, 1, 1, PROTOBUF_FIELD_OFFSET(Attitude, _impl_.quaternion_forward_)}}, - // .mavsdk.rpc.gimbal.EulerAngle euler_angle_north = 3; - {::_pbi::TcParser::FastMtS1, - {26, 2, 2, PROTOBUF_FIELD_OFFSET(Attitude, _impl_.euler_angle_north_)}}, - // .mavsdk.rpc.gimbal.Quaternion quaternion_north = 4; - {::_pbi::TcParser::FastMtS1, - {34, 3, 3, PROTOBUF_FIELD_OFFSET(Attitude, _impl_.quaternion_north_)}}, - // .mavsdk.rpc.gimbal.AngularVelocityBody angular_velocity = 5; - {::_pbi::TcParser::FastMtS1, - {42, 4, 4, PROTOBUF_FIELD_OFFSET(Attitude, _impl_.angular_velocity_)}}, - // uint64 timestamp_us = 6; - {::_pbi::TcParser::SingularVarintNoZag1<::uint64_t, offsetof(Attitude, _impl_.timestamp_us_), 63>(), - {48, 63, 0, PROTOBUF_FIELD_OFFSET(Attitude, _impl_.timestamp_us_)}}, + // int32 gimbal_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(GimbalItem, _impl_.gimbal_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(GimbalItem, _impl_.gimbal_id_)}}, + // string vendor_name = 2; + {::_pbi::TcParser::FastUS1, + {18, 63, 0, PROTOBUF_FIELD_OFFSET(GimbalItem, _impl_.vendor_name_)}}, + // string model_name = 3; + {::_pbi::TcParser::FastUS1, + {26, 63, 0, PROTOBUF_FIELD_OFFSET(GimbalItem, _impl_.model_name_)}}, + // string custom_name = 4; + {::_pbi::TcParser::FastUS1, + {34, 63, 0, PROTOBUF_FIELD_OFFSET(GimbalItem, _impl_.custom_name_)}}, + // int32 gimbal_manager_component_id = 5; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(GimbalItem, _impl_.gimbal_manager_component_id_), 63>(), + {40, 63, 0, PROTOBUF_FIELD_OFFSET(GimbalItem, _impl_.gimbal_manager_component_id_)}}, + // int32 gimbal_device_id = 6; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(GimbalItem, _impl_.gimbal_device_id_), 63>(), + {48, 63, 0, PROTOBUF_FIELD_OFFSET(GimbalItem, _impl_.gimbal_device_id_)}}, {::_pbi::TcParser::MiniParse, {}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.gimbal.EulerAngle euler_angle_forward = 1; - {PROTOBUF_FIELD_OFFSET(Attitude, _impl_.euler_angle_forward_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - // .mavsdk.rpc.gimbal.Quaternion quaternion_forward = 2; - {PROTOBUF_FIELD_OFFSET(Attitude, _impl_.quaternion_forward_), _Internal::kHasBitsOffset + 1, 1, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - // .mavsdk.rpc.gimbal.EulerAngle euler_angle_north = 3; - {PROTOBUF_FIELD_OFFSET(Attitude, _impl_.euler_angle_north_), _Internal::kHasBitsOffset + 2, 2, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - // .mavsdk.rpc.gimbal.Quaternion quaternion_north = 4; - {PROTOBUF_FIELD_OFFSET(Attitude, _impl_.quaternion_north_), _Internal::kHasBitsOffset + 3, 3, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - // .mavsdk.rpc.gimbal.AngularVelocityBody angular_velocity = 5; - {PROTOBUF_FIELD_OFFSET(Attitude, _impl_.angular_velocity_), _Internal::kHasBitsOffset + 4, 4, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, - // uint64 timestamp_us = 6; - {PROTOBUF_FIELD_OFFSET(Attitude, _impl_.timestamp_us_), -1, 0, - (0 | ::_fl::kFcSingular | ::_fl::kUInt64)}, - }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::EulerAngle>()}, - {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::Quaternion>()}, - {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::EulerAngle>()}, - {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::Quaternion>()}, - {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::AngularVelocityBody>()}, - }}, {{ + // int32 gimbal_id = 1; + {PROTOBUF_FIELD_OFFSET(GimbalItem, _impl_.gimbal_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // string vendor_name = 2; + {PROTOBUF_FIELD_OFFSET(GimbalItem, _impl_.vendor_name_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // string model_name = 3; + {PROTOBUF_FIELD_OFFSET(GimbalItem, _impl_.model_name_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // string custom_name = 4; + {PROTOBUF_FIELD_OFFSET(GimbalItem, _impl_.custom_name_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kUtf8String | ::_fl::kRepAString)}, + // int32 gimbal_manager_component_id = 5; + {PROTOBUF_FIELD_OFFSET(GimbalItem, _impl_.gimbal_manager_component_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // int32 gimbal_device_id = 6; + {PROTOBUF_FIELD_OFFSET(GimbalItem, _impl_.gimbal_device_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + }}, + // no aux_entries + {{ + "\34\0\13\12\13\0\0\0" + "mavsdk.rpc.gimbal.GimbalItem" + "vendor_name" + "model_name" + "custom_name" }}, }; -::uint8_t* Attitude::_InternalSerialize( +::uint8_t* GimbalItem::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.Attitude) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.GimbalItem) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.gimbal.EulerAngle euler_angle_forward = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::euler_angle_forward(this), - _Internal::euler_angle_forward(this).GetCachedSize(), target, stream); + + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_gimbal_id(), target); } - // .mavsdk.rpc.gimbal.Quaternion quaternion_forward = 2; - if (cached_has_bits & 0x00000002u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 2, _Internal::quaternion_forward(this), - _Internal::quaternion_forward(this).GetCachedSize(), target, stream); + // string vendor_name = 2; + if (!this->_internal_vendor_name().empty()) { + const std::string& _s = this->_internal_vendor_name(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.gimbal.GimbalItem.vendor_name"); + target = stream->WriteStringMaybeAliased(2, _s, target); } - // .mavsdk.rpc.gimbal.EulerAngle euler_angle_north = 3; - if (cached_has_bits & 0x00000004u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 3, _Internal::euler_angle_north(this), - _Internal::euler_angle_north(this).GetCachedSize(), target, stream); + // string model_name = 3; + if (!this->_internal_model_name().empty()) { + const std::string& _s = this->_internal_model_name(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.gimbal.GimbalItem.model_name"); + target = stream->WriteStringMaybeAliased(3, _s, target); } - // .mavsdk.rpc.gimbal.Quaternion quaternion_north = 4; - if (cached_has_bits & 0x00000008u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 4, _Internal::quaternion_north(this), - _Internal::quaternion_north(this).GetCachedSize(), target, stream); + // string custom_name = 4; + if (!this->_internal_custom_name().empty()) { + const std::string& _s = this->_internal_custom_name(); + ::google::protobuf::internal::WireFormatLite::VerifyUtf8String( + _s.data(), static_cast(_s.length()), ::google::protobuf::internal::WireFormatLite::SERIALIZE, "mavsdk.rpc.gimbal.GimbalItem.custom_name"); + target = stream->WriteStringMaybeAliased(4, _s, target); } - // .mavsdk.rpc.gimbal.AngularVelocityBody angular_velocity = 5; - if (cached_has_bits & 0x00000010u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 5, _Internal::angular_velocity(this), - _Internal::angular_velocity(this).GetCachedSize(), target, stream); + // int32 gimbal_manager_component_id = 5; + if (this->_internal_gimbal_manager_component_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<5>( + stream, this->_internal_gimbal_manager_component_id(), target); } - // uint64 timestamp_us = 6; - if (this->_internal_timestamp_us() != 0) { - target = stream->EnsureSpace(target); - target = ::_pbi::WireFormatLite::WriteUInt64ToArray( - 6, this->_internal_timestamp_us(), target); + // int32 gimbal_device_id = 6; + if (this->_internal_gimbal_device_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<6>( + stream, this->_internal_gimbal_device_id(), target); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -4364,251 +6628,189 @@ ::uint8_t* Attitude::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.Attitude) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.GimbalItem) return target; } -::size_t Attitude::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.Attitude) +::size_t GimbalItem::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.GimbalItem) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x0000001fu) { - // .mavsdk.rpc.gimbal.EulerAngle euler_angle_forward = 1; - if (cached_has_bits & 0x00000001u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.euler_angle_forward_); - } - - // .mavsdk.rpc.gimbal.Quaternion quaternion_forward = 2; - if (cached_has_bits & 0x00000002u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.quaternion_forward_); - } + // string vendor_name = 2; + if (!this->_internal_vendor_name().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_vendor_name()); + } - // .mavsdk.rpc.gimbal.EulerAngle euler_angle_north = 3; - if (cached_has_bits & 0x00000004u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.euler_angle_north_); - } + // string model_name = 3; + if (!this->_internal_model_name().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_model_name()); + } - // .mavsdk.rpc.gimbal.Quaternion quaternion_north = 4; - if (cached_has_bits & 0x00000008u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.quaternion_north_); - } + // string custom_name = 4; + if (!this->_internal_custom_name().empty()) { + total_size += 1 + ::google::protobuf::internal::WireFormatLite::StringSize( + this->_internal_custom_name()); + } - // .mavsdk.rpc.gimbal.AngularVelocityBody angular_velocity = 5; - if (cached_has_bits & 0x00000010u) { - total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.angular_velocity_); - } + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_gimbal_id()); + } + // int32 gimbal_manager_component_id = 5; + if (this->_internal_gimbal_manager_component_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_gimbal_manager_component_id()); } - // uint64 timestamp_us = 6; - if (this->_internal_timestamp_us() != 0) { - total_size += ::_pbi::WireFormatLite::UInt64SizePlusOne( - this->_internal_timestamp_us()); + + // int32 gimbal_device_id = 6; + if (this->_internal_gimbal_device_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_gimbal_device_id()); } return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData Attitude::_class_data_ = { - Attitude::MergeImpl, +const ::google::protobuf::Message::ClassData GimbalItem::_class_data_ = { + GimbalItem::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* Attitude::GetClassData() const { +const ::google::protobuf::Message::ClassData* GimbalItem::GetClassData() const { return &_class_data_; } -void Attitude::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.Attitude) +void GimbalItem::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.GimbalItem) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - cached_has_bits = from._impl_._has_bits_[0]; - if (cached_has_bits & 0x0000001fu) { - if (cached_has_bits & 0x00000001u) { - _this->_internal_mutable_euler_angle_forward()->::mavsdk::rpc::gimbal::EulerAngle::MergeFrom( - from._internal_euler_angle_forward()); - } - if (cached_has_bits & 0x00000002u) { - _this->_internal_mutable_quaternion_forward()->::mavsdk::rpc::gimbal::Quaternion::MergeFrom( - from._internal_quaternion_forward()); - } - if (cached_has_bits & 0x00000004u) { - _this->_internal_mutable_euler_angle_north()->::mavsdk::rpc::gimbal::EulerAngle::MergeFrom( - from._internal_euler_angle_north()); - } - if (cached_has_bits & 0x00000008u) { - _this->_internal_mutable_quaternion_north()->::mavsdk::rpc::gimbal::Quaternion::MergeFrom( - from._internal_quaternion_north()); - } - if (cached_has_bits & 0x00000010u) { - _this->_internal_mutable_angular_velocity()->::mavsdk::rpc::gimbal::AngularVelocityBody::MergeFrom( - from._internal_angular_velocity()); - } + if (!from._internal_vendor_name().empty()) { + _this->_internal_set_vendor_name(from._internal_vendor_name()); } - if (from._internal_timestamp_us() != 0) { - _this->_internal_set_timestamp_us(from._internal_timestamp_us()); + if (!from._internal_model_name().empty()) { + _this->_internal_set_model_name(from._internal_model_name()); + } + if (!from._internal_custom_name().empty()) { + _this->_internal_set_custom_name(from._internal_custom_name()); + } + if (from._internal_gimbal_id() != 0) { + _this->_internal_set_gimbal_id(from._internal_gimbal_id()); + } + if (from._internal_gimbal_manager_component_id() != 0) { + _this->_internal_set_gimbal_manager_component_id(from._internal_gimbal_manager_component_id()); + } + if (from._internal_gimbal_device_id() != 0) { + _this->_internal_set_gimbal_device_id(from._internal_gimbal_device_id()); } _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void Attitude::CopyFrom(const Attitude& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.Attitude) +void GimbalItem::CopyFrom(const GimbalItem& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.GimbalItem) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool Attitude::IsInitialized() const { +PROTOBUF_NOINLINE bool GimbalItem::IsInitialized() const { return true; } -::_pbi::CachedSize* Attitude::AccessCachedSize() const { +::_pbi::CachedSize* GimbalItem::AccessCachedSize() const { return &_impl_._cached_size_; } -void Attitude::InternalSwap(Attitude* PROTOBUF_RESTRICT other) { +void GimbalItem::InternalSwap(GimbalItem* PROTOBUF_RESTRICT other) { using std::swap; + auto* arena = GetArena(); + ABSL_DCHECK_EQ(arena, other->GetArena()); _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.vendor_name_, &other->_impl_.vendor_name_, arena); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.model_name_, &other->_impl_.model_name_, arena); + ::_pbi::ArenaStringPtr::InternalSwap(&_impl_.custom_name_, &other->_impl_.custom_name_, arena); ::google::protobuf::internal::memswap< - PROTOBUF_FIELD_OFFSET(Attitude, _impl_.timestamp_us_) - + sizeof(Attitude::_impl_.timestamp_us_) - - PROTOBUF_FIELD_OFFSET(Attitude, _impl_.euler_angle_forward_)>( - reinterpret_cast(&_impl_.euler_angle_forward_), - reinterpret_cast(&other->_impl_.euler_angle_forward_)); -} - -::google::protobuf::Metadata Attitude::GetMetadata() const { - return ::_pbi::AssignDescriptors( - &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, - file_level_metadata_gimbal_2fgimbal_2eproto[15]); -} -// =================================================================== - -class SubscribeAttitudeRequest::_Internal { - public: -}; - -SubscribeAttitudeRequest::SubscribeAttitudeRequest(::google::protobuf::Arena* arena) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.SubscribeAttitudeRequest) -} -SubscribeAttitudeRequest::SubscribeAttitudeRequest( - ::google::protobuf::Arena* arena, - const SubscribeAttitudeRequest& from) - : ::google::protobuf::internal::ZeroFieldsBase(arena) { - SubscribeAttitudeRequest* const _this = this; - (void)_this; - _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( - from._internal_metadata_); - - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.SubscribeAttitudeRequest) + PROTOBUF_FIELD_OFFSET(GimbalItem, _impl_.gimbal_device_id_) + + sizeof(GimbalItem::_impl_.gimbal_device_id_) + - PROTOBUF_FIELD_OFFSET(GimbalItem, _impl_.gimbal_id_)>( + reinterpret_cast(&_impl_.gimbal_id_), + reinterpret_cast(&other->_impl_.gimbal_id_)); } - - - - - - - - -::google::protobuf::Metadata SubscribeAttitudeRequest::GetMetadata() const { +::google::protobuf::Metadata GimbalItem::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, - file_level_metadata_gimbal_2fgimbal_2eproto[16]); + file_level_metadata_gimbal_2fgimbal_2eproto[24]); } // =================================================================== -class AttitudeResponse::_Internal { +class GimbalList::_Internal { public: - using HasBits = decltype(std::declval()._impl_._has_bits_); - static constexpr ::int32_t kHasBitsOffset = - 8 * PROTOBUF_FIELD_OFFSET(AttitudeResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::gimbal::Attitude& attitude(const AttitudeResponse* msg); - static void set_has_attitude(HasBits* has_bits) { - (*has_bits)[0] |= 1u; - } }; -const ::mavsdk::rpc::gimbal::Attitude& AttitudeResponse::_Internal::attitude(const AttitudeResponse* msg) { - return *msg->_impl_.attitude_; -} -AttitudeResponse::AttitudeResponse(::google::protobuf::Arena* arena) +GimbalList::GimbalList(::google::protobuf::Arena* arena) : ::google::protobuf::Message(arena) { SharedCtor(arena); - // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.AttitudeResponse) + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.gimbal.GimbalList) } -inline PROTOBUF_NDEBUG_INLINE AttitudeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GimbalList::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from) - : _has_bits_{from._has_bits_}, + : gimbals_{visibility, arena, from.gimbals_}, _cached_size_{0} {} -AttitudeResponse::AttitudeResponse( +GimbalList::GimbalList( ::google::protobuf::Arena* arena, - const AttitudeResponse& from) + const GimbalList& from) : ::google::protobuf::Message(arena) { - AttitudeResponse* const _this = this; + GimbalList* const _this = this; (void)_this; _internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); - ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.attitude_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::gimbal::Attitude>(arena, *from._impl_.attitude_) - : nullptr; - // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.AttitudeResponse) + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.gimbal.GimbalList) } -inline PROTOBUF_NDEBUG_INLINE AttitudeResponse::Impl_::Impl_( +inline PROTOBUF_NDEBUG_INLINE GimbalList::Impl_::Impl_( ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena) - : _cached_size_{0} {} + : gimbals_{visibility, arena}, + _cached_size_{0} {} -inline void AttitudeResponse::SharedCtor(::_pb::Arena* arena) { +inline void GimbalList::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); - _impl_.attitude_ = {}; } -AttitudeResponse::~AttitudeResponse() { - // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.AttitudeResponse) +GimbalList::~GimbalList() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.gimbal.GimbalList) _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); SharedDtor(); } -inline void AttitudeResponse::SharedDtor() { +inline void GimbalList::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.attitude_; _impl_.~Impl_(); } -PROTOBUF_NOINLINE void AttitudeResponse::Clear() { -// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.AttitudeResponse) +PROTOBUF_NOINLINE void GimbalList::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.gimbal.GimbalList) PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.attitude_ != nullptr); - _impl_.attitude_->Clear(); - } - _impl_._has_bits_.Clear(); + _impl_.gimbals_.Clear(); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } -const char* AttitudeResponse::_InternalParse( +const char* GimbalList::_InternalParse( const char* ptr, ::_pbi::ParseContext* ctx) { ptr = ::_pbi::TcParser::ParseLoop(this, ptr, ctx, &_table_.header); return ptr; @@ -4616,9 +6818,9 @@ const char* AttitudeResponse::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<0, 1, 1, 0, 2> AttitudeResponse::_table_ = { +const ::_pbi::TcParseTable<0, 1, 1, 0, 2> GimbalList::_table_ = { { - PROTOBUF_FIELD_OFFSET(AttitudeResponse, _impl_._has_bits_), + 0, // no _has_bits_ 0, // no _extensions_ 1, 0, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), @@ -4627,37 +6829,37 @@ const ::_pbi::TcParseTable<0, 1, 1, 0, 2> AttitudeResponse::_table_ = { 1, // num_field_entries 1, // num_aux_entries offsetof(decltype(_table_), aux_entries), - &_AttitudeResponse_default_instance_._instance, + &_GimbalList_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ - // .mavsdk.rpc.gimbal.Attitude attitude = 1; - {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(AttitudeResponse, _impl_.attitude_)}}, + // repeated .mavsdk.rpc.gimbal.GimbalItem gimbals = 1; + {::_pbi::TcParser::FastMtR1, + {10, 63, 0, PROTOBUF_FIELD_OFFSET(GimbalList, _impl_.gimbals_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.gimbal.Attitude attitude = 1; - {PROTOBUF_FIELD_OFFSET(AttitudeResponse, _impl_.attitude_), _Internal::kHasBitsOffset + 0, 0, - (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + // repeated .mavsdk.rpc.gimbal.GimbalItem gimbals = 1; + {PROTOBUF_FIELD_OFFSET(GimbalList, _impl_.gimbals_), 0, 0, + (0 | ::_fl::kFcRepeated | ::_fl::kMessage | ::_fl::kTvTable)}, }}, {{ - {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::Attitude>()}, + {::_pbi::TcParser::GetTable<::mavsdk::rpc::gimbal::GimbalItem>()}, }}, {{ }}, }; -::uint8_t* AttitudeResponse::_InternalSerialize( +::uint8_t* GimbalList::_InternalSerialize( ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const { - // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.AttitudeResponse) + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.gimbal.GimbalList) ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.gimbal.Attitude attitude = 1; - if (cached_has_bits & 0x00000001u) { - target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::attitude(this), - _Internal::attitude(this).GetCachedSize(), target, stream); + // repeated .mavsdk.rpc.gimbal.GimbalItem gimbals = 1; + for (unsigned i = 0, + n = static_cast(this->_internal_gimbals_size()); i < n; i++) { + const auto& repfield = this->_internal_gimbals().Get(i); + target = ::google::protobuf::internal::WireFormatLite:: + InternalWriteMessage(1, repfield, repfield.GetCachedSize(), target, stream); } if (PROTOBUF_PREDICT_FALSE(_internal_metadata_.have_unknown_fields())) { @@ -4665,76 +6867,72 @@ ::uint8_t* AttitudeResponse::_InternalSerialize( ::_pbi::WireFormat::InternalSerializeUnknownFieldsToArray( _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance), target, stream); } - // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.AttitudeResponse) + // @@protoc_insertion_point(serialize_to_array_end:mavsdk.rpc.gimbal.GimbalList) return target; } -::size_t AttitudeResponse::ByteSizeLong() const { -// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.AttitudeResponse) +::size_t GimbalList::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.gimbal.GimbalList) ::size_t total_size = 0; ::uint32_t cached_has_bits = 0; // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.gimbal.Attitude attitude = 1; - cached_has_bits = _impl_._has_bits_[0]; - if (cached_has_bits & 0x00000001u) { + // repeated .mavsdk.rpc.gimbal.GimbalItem gimbals = 1; + total_size += 1UL * this->_internal_gimbals_size(); + for (const auto& msg : this->_internal_gimbals()) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.attitude_); + ::google::protobuf::internal::WireFormatLite::MessageSize(msg); } - return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); } -const ::google::protobuf::Message::ClassData AttitudeResponse::_class_data_ = { - AttitudeResponse::MergeImpl, +const ::google::protobuf::Message::ClassData GimbalList::_class_data_ = { + GimbalList::MergeImpl, nullptr, // OnDemandRegisterArenaDtor }; -const ::google::protobuf::Message::ClassData* AttitudeResponse::GetClassData() const { +const ::google::protobuf::Message::ClassData* GimbalList::GetClassData() const { return &_class_data_; } -void AttitudeResponse::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { - auto* const _this = static_cast(&to_msg); - auto& from = static_cast(from_msg); - // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.AttitudeResponse) +void GimbalList::MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg) { + auto* const _this = static_cast(&to_msg); + auto& from = static_cast(from_msg); + // @@protoc_insertion_point(class_specific_merge_from_start:mavsdk.rpc.gimbal.GimbalList) ABSL_DCHECK_NE(&from, _this); ::uint32_t cached_has_bits = 0; (void) cached_has_bits; - if ((from._impl_._has_bits_[0] & 0x00000001u) != 0) { - _this->_internal_mutable_attitude()->::mavsdk::rpc::gimbal::Attitude::MergeFrom( - from._internal_attitude()); - } + _this->_internal_mutable_gimbals()->MergeFrom( + from._internal_gimbals()); _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); } -void AttitudeResponse::CopyFrom(const AttitudeResponse& from) { -// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.AttitudeResponse) +void GimbalList::CopyFrom(const GimbalList& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.gimbal.GimbalList) if (&from == this) return; Clear(); MergeFrom(from); } -PROTOBUF_NOINLINE bool AttitudeResponse::IsInitialized() const { +PROTOBUF_NOINLINE bool GimbalList::IsInitialized() const { return true; } -::_pbi::CachedSize* AttitudeResponse::AccessCachedSize() const { +::_pbi::CachedSize* GimbalList::AccessCachedSize() const { return &_impl_._cached_size_; } -void AttitudeResponse::InternalSwap(AttitudeResponse* PROTOBUF_RESTRICT other) { +void GimbalList::InternalSwap(GimbalList* PROTOBUF_RESTRICT other) { using std::swap; _internal_metadata_.InternalSwap(&other->_internal_metadata_); - swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); - swap(_impl_.attitude_, other->_impl_.attitude_); + _impl_.gimbals_.InternalSwap(&other->_impl_.gimbals_); } -::google::protobuf::Metadata AttitudeResponse::GetMetadata() const { +::google::protobuf::Metadata GimbalList::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, - file_level_metadata_gimbal_2fgimbal_2eproto[17]); + file_level_metadata_gimbal_2fgimbal_2eproto[25]); } // =================================================================== @@ -4760,10 +6958,10 @@ inline PROTOBUF_NDEBUG_INLINE ControlStatus::Impl_::Impl_( inline void ControlStatus::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); ::memset(reinterpret_cast(&_impl_) + - offsetof(Impl_, control_mode_), + offsetof(Impl_, gimbal_id_), 0, offsetof(Impl_, compid_secondary_control_) - - offsetof(Impl_, control_mode_) + + offsetof(Impl_, gimbal_id_) + sizeof(Impl_::compid_secondary_control_)); } ControlStatus::~ControlStatus() { @@ -4783,9 +6981,9 @@ PROTOBUF_NOINLINE void ControlStatus::Clear() { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - ::memset(&_impl_.control_mode_, 0, static_cast<::size_t>( + ::memset(&_impl_.gimbal_id_, 0, static_cast<::size_t>( reinterpret_cast(&_impl_.compid_secondary_control_) - - reinterpret_cast(&_impl_.control_mode_)) + sizeof(_impl_.compid_secondary_control_)); + reinterpret_cast(&_impl_.gimbal_id_)) + sizeof(_impl_.compid_secondary_control_)); _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); } @@ -4797,54 +6995,59 @@ const char* ControlStatus::_InternalParse( PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 -const ::_pbi::TcParseTable<3, 5, 0, 0, 2> ControlStatus::_table_ = { +const ::_pbi::TcParseTable<3, 6, 0, 0, 2> ControlStatus::_table_ = { { 0, // no _has_bits_ 0, // no _extensions_ - 5, 56, // max_field_number, fast_idx_mask + 6, 56, // max_field_number, fast_idx_mask offsetof(decltype(_table_), field_lookup_table), - 4294967264, // skipmap + 4294967232, // skipmap offsetof(decltype(_table_), field_entries), - 5, // num_field_entries + 6, // num_field_entries 0, // num_aux_entries offsetof(decltype(_table_), field_names), // no aux_entries &_ControlStatus_default_instance_._instance, ::_pbi::TcParser::GenericFallback, // fallback }, {{ {::_pbi::TcParser::MiniParse, {}}, - // .mavsdk.rpc.gimbal.ControlMode control_mode = 1; + // int32 gimbal_id = 1; + {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ControlStatus, _impl_.gimbal_id_), 63>(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.gimbal_id_)}}, + // .mavsdk.rpc.gimbal.ControlMode control_mode = 2; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ControlStatus, _impl_.control_mode_), 63>(), - {8, 63, 0, PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.control_mode_)}}, - // int32 sysid_primary_control = 2; + {16, 63, 0, PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.control_mode_)}}, + // int32 sysid_primary_control = 3; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ControlStatus, _impl_.sysid_primary_control_), 63>(), - {16, 63, 0, PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.sysid_primary_control_)}}, - // int32 compid_primary_control = 3; + {24, 63, 0, PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.sysid_primary_control_)}}, + // int32 compid_primary_control = 4; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ControlStatus, _impl_.compid_primary_control_), 63>(), - {24, 63, 0, PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.compid_primary_control_)}}, - // int32 sysid_secondary_control = 4; + {32, 63, 0, PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.compid_primary_control_)}}, + // int32 sysid_secondary_control = 5; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ControlStatus, _impl_.sysid_secondary_control_), 63>(), - {32, 63, 0, PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.sysid_secondary_control_)}}, - // int32 compid_secondary_control = 5; + {40, 63, 0, PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.sysid_secondary_control_)}}, + // int32 compid_secondary_control = 6; {::_pbi::TcParser::SingularVarintNoZag1<::uint32_t, offsetof(ControlStatus, _impl_.compid_secondary_control_), 63>(), - {40, 63, 0, PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.compid_secondary_control_)}}, - {::_pbi::TcParser::MiniParse, {}}, + {48, 63, 0, PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.compid_secondary_control_)}}, {::_pbi::TcParser::MiniParse, {}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.gimbal.ControlMode control_mode = 1; + // int32 gimbal_id = 1; + {PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.gimbal_id_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, + // .mavsdk.rpc.gimbal.ControlMode control_mode = 2; {PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.control_mode_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kOpenEnum)}, - // int32 sysid_primary_control = 2; + // int32 sysid_primary_control = 3; {PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.sysid_primary_control_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, - // int32 compid_primary_control = 3; + // int32 compid_primary_control = 4; {PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.compid_primary_control_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, - // int32 sysid_secondary_control = 4; + // int32 sysid_secondary_control = 5; {PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.sysid_secondary_control_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, - // int32 compid_secondary_control = 5; + // int32 compid_secondary_control = 6; {PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.compid_secondary_control_), 0, 0, (0 | ::_fl::kFcSingular | ::_fl::kInt32)}, }}, @@ -4860,38 +7063,45 @@ ::uint8_t* ControlStatus::_InternalSerialize( ::uint32_t cached_has_bits = 0; (void)cached_has_bits; - // .mavsdk.rpc.gimbal.ControlMode control_mode = 1; + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + target = ::google::protobuf::internal::WireFormatLite:: + WriteInt32ToArrayWithField<1>( + stream, this->_internal_gimbal_id(), target); + } + + // .mavsdk.rpc.gimbal.ControlMode control_mode = 2; if (this->_internal_control_mode() != 0) { target = stream->EnsureSpace(target); target = ::_pbi::WireFormatLite::WriteEnumToArray( - 1, this->_internal_control_mode(), target); + 2, this->_internal_control_mode(), target); } - // int32 sysid_primary_control = 2; + // int32 sysid_primary_control = 3; if (this->_internal_sysid_primary_control() != 0) { target = ::google::protobuf::internal::WireFormatLite:: - WriteInt32ToArrayWithField<2>( + WriteInt32ToArrayWithField<3>( stream, this->_internal_sysid_primary_control(), target); } - // int32 compid_primary_control = 3; + // int32 compid_primary_control = 4; if (this->_internal_compid_primary_control() != 0) { target = ::google::protobuf::internal::WireFormatLite:: - WriteInt32ToArrayWithField<3>( + WriteInt32ToArrayWithField<4>( stream, this->_internal_compid_primary_control(), target); } - // int32 sysid_secondary_control = 4; + // int32 sysid_secondary_control = 5; if (this->_internal_sysid_secondary_control() != 0) { target = ::google::protobuf::internal::WireFormatLite:: - WriteInt32ToArrayWithField<4>( + WriteInt32ToArrayWithField<5>( stream, this->_internal_sysid_secondary_control(), target); } - // int32 compid_secondary_control = 5; + // int32 compid_secondary_control = 6; if (this->_internal_compid_secondary_control() != 0) { target = ::google::protobuf::internal::WireFormatLite:: - WriteInt32ToArrayWithField<5>( + WriteInt32ToArrayWithField<6>( stream, this->_internal_compid_secondary_control(), target); } @@ -4912,31 +7122,37 @@ ::size_t ControlStatus::ByteSizeLong() const { // Prevent compiler warnings about cached_has_bits being unused (void) cached_has_bits; - // .mavsdk.rpc.gimbal.ControlMode control_mode = 1; + // int32 gimbal_id = 1; + if (this->_internal_gimbal_id() != 0) { + total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( + this->_internal_gimbal_id()); + } + + // .mavsdk.rpc.gimbal.ControlMode control_mode = 2; if (this->_internal_control_mode() != 0) { total_size += 1 + ::_pbi::WireFormatLite::EnumSize(this->_internal_control_mode()); } - // int32 sysid_primary_control = 2; + // int32 sysid_primary_control = 3; if (this->_internal_sysid_primary_control() != 0) { total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( this->_internal_sysid_primary_control()); } - // int32 compid_primary_control = 3; + // int32 compid_primary_control = 4; if (this->_internal_compid_primary_control() != 0) { total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( this->_internal_compid_primary_control()); } - // int32 sysid_secondary_control = 4; + // int32 sysid_secondary_control = 5; if (this->_internal_sysid_secondary_control() != 0) { total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( this->_internal_sysid_secondary_control()); } - // int32 compid_secondary_control = 5; + // int32 compid_secondary_control = 6; if (this->_internal_compid_secondary_control() != 0) { total_size += ::_pbi::WireFormatLite::Int32SizePlusOne( this->_internal_compid_secondary_control()); @@ -4961,6 +7177,9 @@ void ControlStatus::MergeImpl(::google::protobuf::Message& to_msg, const ::googl ::uint32_t cached_has_bits = 0; (void) cached_has_bits; + if (from._internal_gimbal_id() != 0) { + _this->_internal_set_gimbal_id(from._internal_gimbal_id()); + } if (from._internal_control_mode() != 0) { _this->_internal_set_control_mode(from._internal_control_mode()); } @@ -4999,15 +7218,15 @@ void ControlStatus::InternalSwap(ControlStatus* PROTOBUF_RESTRICT other) { ::google::protobuf::internal::memswap< PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.compid_secondary_control_) + sizeof(ControlStatus::_impl_.compid_secondary_control_) - - PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.control_mode_)>( - reinterpret_cast(&_impl_.control_mode_), - reinterpret_cast(&other->_impl_.control_mode_)); + - PROTOBUF_FIELD_OFFSET(ControlStatus, _impl_.gimbal_id_)>( + reinterpret_cast(&_impl_.gimbal_id_), + reinterpret_cast(&other->_impl_.gimbal_id_)); } ::google::protobuf::Metadata ControlStatus::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, - file_level_metadata_gimbal_2fgimbal_2eproto[18]); + file_level_metadata_gimbal_2fgimbal_2eproto[26]); } // =================================================================== @@ -5223,7 +7442,7 @@ void GimbalResult::InternalSwap(GimbalResult* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata GimbalResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_gimbal_2fgimbal_2eproto_getter, &descriptor_table_gimbal_2fgimbal_2eproto_once, - file_level_metadata_gimbal_2fgimbal_2eproto[19]); + file_level_metadata_gimbal_2fgimbal_2eproto[27]); } // @@protoc_insertion_point(namespace_scope) } // namespace gimbal diff --git a/src/mavsdk_server/src/generated/gimbal/gimbal.pb.h b/src/mavsdk_server/src/generated/gimbal/gimbal.pb.h index cd8ddd9e46..0212a1ad78 100644 --- a/src/mavsdk_server/src/generated/gimbal/gimbal.pb.h +++ b/src/mavsdk_server/src/generated/gimbal/gimbal.pb.h @@ -70,15 +70,36 @@ extern AttitudeDefaultTypeInternal _Attitude_default_instance_; class AttitudeResponse; struct AttitudeResponseDefaultTypeInternal; extern AttitudeResponseDefaultTypeInternal _AttitudeResponse_default_instance_; -class ControlResponse; -struct ControlResponseDefaultTypeInternal; -extern ControlResponseDefaultTypeInternal _ControlResponse_default_instance_; class ControlStatus; struct ControlStatusDefaultTypeInternal; extern ControlStatusDefaultTypeInternal _ControlStatus_default_instance_; +class ControlStatusResponse; +struct ControlStatusResponseDefaultTypeInternal; +extern ControlStatusResponseDefaultTypeInternal _ControlStatusResponse_default_instance_; class EulerAngle; struct EulerAngleDefaultTypeInternal; extern EulerAngleDefaultTypeInternal _EulerAngle_default_instance_; +class GetAttitudeRequest; +struct GetAttitudeRequestDefaultTypeInternal; +extern GetAttitudeRequestDefaultTypeInternal _GetAttitudeRequest_default_instance_; +class GetAttitudeResponse; +struct GetAttitudeResponseDefaultTypeInternal; +extern GetAttitudeResponseDefaultTypeInternal _GetAttitudeResponse_default_instance_; +class GetControlStatusRequest; +struct GetControlStatusRequestDefaultTypeInternal; +extern GetControlStatusRequestDefaultTypeInternal _GetControlStatusRequest_default_instance_; +class GetControlStatusResponse; +struct GetControlStatusResponseDefaultTypeInternal; +extern GetControlStatusResponseDefaultTypeInternal _GetControlStatusResponse_default_instance_; +class GimbalItem; +struct GimbalItemDefaultTypeInternal; +extern GimbalItemDefaultTypeInternal _GimbalItem_default_instance_; +class GimbalList; +struct GimbalListDefaultTypeInternal; +extern GimbalListDefaultTypeInternal _GimbalList_default_instance_; +class GimbalListResponse; +struct GimbalListResponseDefaultTypeInternal; +extern GimbalListResponseDefaultTypeInternal _GimbalListResponse_default_instance_; class GimbalResult; struct GimbalResultDefaultTypeInternal; extern GimbalResultDefaultTypeInternal _GimbalResult_default_instance_; @@ -112,9 +133,12 @@ extern SetRoiLocationResponseDefaultTypeInternal _SetRoiLocationResponse_default class SubscribeAttitudeRequest; struct SubscribeAttitudeRequestDefaultTypeInternal; extern SubscribeAttitudeRequestDefaultTypeInternal _SubscribeAttitudeRequest_default_instance_; -class SubscribeControlRequest; -struct SubscribeControlRequestDefaultTypeInternal; -extern SubscribeControlRequestDefaultTypeInternal _SubscribeControlRequest_default_instance_; +class SubscribeControlStatusRequest; +struct SubscribeControlStatusRequestDefaultTypeInternal; +extern SubscribeControlStatusRequestDefaultTypeInternal _SubscribeControlStatusRequest_default_instance_; +class SubscribeGimbalListRequest; +struct SubscribeGimbalListRequestDefaultTypeInternal; +extern SubscribeGimbalListRequestDefaultTypeInternal _SubscribeGimbalListRequest_default_instance_; class TakeControlRequest; struct TakeControlRequestDefaultTypeInternal; extern TakeControlRequestDefaultTypeInternal _TakeControlRequest_default_instance_; @@ -408,9 +432,20 @@ class TakeControlRequest final : // accessors ------------------------------------------------------- enum : int { - kControlModeFieldNumber = 1, + kGimbalIdFieldNumber = 1, + kControlModeFieldNumber = 2, }; - // .mavsdk.rpc.gimbal.ControlMode control_mode = 1; + // int32 gimbal_id = 1; + void clear_gimbal_id() ; + ::int32_t gimbal_id() const; + void set_gimbal_id(::int32_t value); + + private: + ::int32_t _internal_gimbal_id() const; + void _internal_set_gimbal_id(::int32_t value); + + public: + // .mavsdk.rpc.gimbal.ControlMode control_mode = 2; void clear_control_mode() ; ::mavsdk::rpc::gimbal::ControlMode control_mode() const; void set_control_mode(::mavsdk::rpc::gimbal::ControlMode value); @@ -426,7 +461,7 @@ class TakeControlRequest final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 0, + 1, 2, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -443,6 +478,7 @@ class TakeControlRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t gimbal_id_; int control_mode_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER @@ -451,25 +487,161 @@ class TakeControlRequest final : friend struct ::TableStruct_gimbal_2fgimbal_2eproto; };// ------------------------------------------------------------------- -class SubscribeControlRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.SubscribeControlRequest) */ { +class SubscribeGimbalListRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.SubscribeGimbalListRequest) */ { + public: + inline SubscribeGimbalListRequest() : SubscribeGimbalListRequest(nullptr) {} + template + explicit PROTOBUF_CONSTEXPR SubscribeGimbalListRequest(::google::protobuf::internal::ConstantInitialized); + + inline SubscribeGimbalListRequest(const SubscribeGimbalListRequest& from) + : SubscribeGimbalListRequest(nullptr, from) {} + SubscribeGimbalListRequest(SubscribeGimbalListRequest&& from) noexcept + : SubscribeGimbalListRequest() { + *this = ::std::move(from); + } + + inline SubscribeGimbalListRequest& operator=(const SubscribeGimbalListRequest& from) { + CopyFrom(from); + return *this; + } + inline SubscribeGimbalListRequest& operator=(SubscribeGimbalListRequest&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const SubscribeGimbalListRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SubscribeGimbalListRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeGimbalListRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 22; + + friend void swap(SubscribeGimbalListRequest& a, SubscribeGimbalListRequest& b) { + a.Swap(&b); + } + inline void Swap(SubscribeGimbalListRequest* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(SubscribeGimbalListRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SubscribeGimbalListRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; + inline void CopyFrom(const SubscribeGimbalListRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); + } + using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; + void MergeFrom(const SubscribeGimbalListRequest& from) { + ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + } + public: + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.gimbal.SubscribeGimbalListRequest"; + } + protected: + explicit SubscribeGimbalListRequest(::google::protobuf::Arena* arena); + SubscribeGimbalListRequest(::google::protobuf::Arena* arena, const SubscribeGimbalListRequest& from); + public: + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.SubscribeGimbalListRequest) + private: + class _Internal; + + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + PROTOBUF_TSAN_DECLARE_MEMBER + }; + friend struct ::TableStruct_gimbal_2fgimbal_2eproto; +};// ------------------------------------------------------------------- + +class SubscribeControlStatusRequest final : + public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.SubscribeControlStatusRequest) */ { public: - inline SubscribeControlRequest() : SubscribeControlRequest(nullptr) {} + inline SubscribeControlStatusRequest() : SubscribeControlStatusRequest(nullptr) {} template - explicit PROTOBUF_CONSTEXPR SubscribeControlRequest(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SubscribeControlStatusRequest(::google::protobuf::internal::ConstantInitialized); - inline SubscribeControlRequest(const SubscribeControlRequest& from) - : SubscribeControlRequest(nullptr, from) {} - SubscribeControlRequest(SubscribeControlRequest&& from) noexcept - : SubscribeControlRequest() { + inline SubscribeControlStatusRequest(const SubscribeControlStatusRequest& from) + : SubscribeControlStatusRequest(nullptr, from) {} + SubscribeControlStatusRequest(SubscribeControlStatusRequest&& from) noexcept + : SubscribeControlStatusRequest() { *this = ::std::move(from); } - inline SubscribeControlRequest& operator=(const SubscribeControlRequest& from) { + inline SubscribeControlStatusRequest& operator=(const SubscribeControlStatusRequest& from) { CopyFrom(from); return *this; } - inline SubscribeControlRequest& operator=(SubscribeControlRequest&& from) noexcept { + inline SubscribeControlStatusRequest& operator=(SubscribeControlStatusRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -501,20 +673,20 @@ class SubscribeControlRequest final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SubscribeControlRequest& default_instance() { + static const SubscribeControlStatusRequest& default_instance() { return *internal_default_instance(); } - static inline const SubscribeControlRequest* internal_default_instance() { - return reinterpret_cast( - &_SubscribeControlRequest_default_instance_); + static inline const SubscribeControlStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_SubscribeControlStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = 10; - friend void swap(SubscribeControlRequest& a, SubscribeControlRequest& b) { + friend void swap(SubscribeControlStatusRequest& a, SubscribeControlStatusRequest& b) { a.Swap(&b); } - inline void Swap(SubscribeControlRequest* other) { + inline void Swap(SubscribeControlStatusRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -527,7 +699,7 @@ class SubscribeControlRequest final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SubscribeControlRequest* other) { + void UnsafeArenaSwap(SubscribeControlStatusRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -535,15 +707,15 @@ class SubscribeControlRequest final : // implements Message ---------------------------------------------- - SubscribeControlRequest* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SubscribeControlStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const SubscribeControlRequest& from) { + inline void CopyFrom(const SubscribeControlStatusRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); } using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const SubscribeControlRequest& from) { + void MergeFrom(const SubscribeControlStatusRequest& from) { ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); } public: @@ -551,11 +723,11 @@ class SubscribeControlRequest final : private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.gimbal.SubscribeControlRequest"; + return "mavsdk.rpc.gimbal.SubscribeControlStatusRequest"; } protected: - explicit SubscribeControlRequest(::google::protobuf::Arena* arena); - SubscribeControlRequest(::google::protobuf::Arena* arena, const SubscribeControlRequest& from); + explicit SubscribeControlStatusRequest(::google::protobuf::Arena* arena); + SubscribeControlStatusRequest(::google::protobuf::Arena* arena, const SubscribeControlStatusRequest& from); public: ::google::protobuf::Metadata GetMetadata() const final; @@ -564,7 +736,7 @@ class SubscribeControlRequest final : // accessors ------------------------------------------------------- - // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.SubscribeControlRequest) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.SubscribeControlStatusRequest) private: class _Internal; @@ -645,7 +817,7 @@ class SubscribeAttitudeRequest final : &_SubscribeAttitudeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 16; + 18; friend void swap(SubscribeAttitudeRequest& a, SubscribeAttitudeRequest& b) { a.Swap(&b); @@ -855,11 +1027,12 @@ class SetRoiLocationRequest final : // accessors ------------------------------------------------------- enum : int { - kLatitudeDegFieldNumber = 1, - kLongitudeDegFieldNumber = 2, - kAltitudeMFieldNumber = 3, + kLatitudeDegFieldNumber = 2, + kGimbalIdFieldNumber = 1, + kAltitudeMFieldNumber = 4, + kLongitudeDegFieldNumber = 3, }; - // double latitude_deg = 1; + // double latitude_deg = 2; void clear_latitude_deg() ; double latitude_deg() const; void set_latitude_deg(double value); @@ -869,17 +1042,17 @@ class SetRoiLocationRequest final : void _internal_set_latitude_deg(double value); public: - // double longitude_deg = 2; - void clear_longitude_deg() ; - double longitude_deg() const; - void set_longitude_deg(double value); + // int32 gimbal_id = 1; + void clear_gimbal_id() ; + ::int32_t gimbal_id() const; + void set_gimbal_id(::int32_t value); private: - double _internal_longitude_deg() const; - void _internal_set_longitude_deg(double value); + ::int32_t _internal_gimbal_id() const; + void _internal_set_gimbal_id(::int32_t value); public: - // float altitude_m = 3; + // float altitude_m = 4; void clear_altitude_m() ; float altitude_m() const; void set_altitude_m(float value); @@ -888,6 +1061,16 @@ class SetRoiLocationRequest final : float _internal_altitude_m() const; void _internal_set_altitude_m(float value); + public: + // double longitude_deg = 3; + void clear_longitude_deg() ; + double longitude_deg() const; + void set_longitude_deg(double value); + + private: + double _internal_longitude_deg() const; + void _internal_set_longitude_deg(double value); + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.SetRoiLocationRequest) private: @@ -895,7 +1078,7 @@ class SetRoiLocationRequest final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 0, + 2, 4, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -913,8 +1096,9 @@ class SetRoiLocationRequest final : inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); double latitude_deg_; - double longitude_deg_; + ::int32_t gimbal_id_; float altitude_m_; + double longitude_deg_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -1054,13 +1238,24 @@ class SetAngularRatesRequest final : // accessors ------------------------------------------------------- enum : int { - kRollRateDegSFieldNumber = 1, - kPitchRateDegSFieldNumber = 2, - kYawRateDegSFieldNumber = 3, - kGimbalModeFieldNumber = 4, - kSendModeFieldNumber = 5, + kGimbalIdFieldNumber = 1, + kRollRateDegSFieldNumber = 2, + kPitchRateDegSFieldNumber = 3, + kYawRateDegSFieldNumber = 4, + kGimbalModeFieldNumber = 5, + kSendModeFieldNumber = 6, }; - // float roll_rate_deg_s = 1; + // int32 gimbal_id = 1; + void clear_gimbal_id() ; + ::int32_t gimbal_id() const; + void set_gimbal_id(::int32_t value); + + private: + ::int32_t _internal_gimbal_id() const; + void _internal_set_gimbal_id(::int32_t value); + + public: + // float roll_rate_deg_s = 2; void clear_roll_rate_deg_s() ; float roll_rate_deg_s() const; void set_roll_rate_deg_s(float value); @@ -1070,7 +1265,7 @@ class SetAngularRatesRequest final : void _internal_set_roll_rate_deg_s(float value); public: - // float pitch_rate_deg_s = 2; + // float pitch_rate_deg_s = 3; void clear_pitch_rate_deg_s() ; float pitch_rate_deg_s() const; void set_pitch_rate_deg_s(float value); @@ -1080,7 +1275,7 @@ class SetAngularRatesRequest final : void _internal_set_pitch_rate_deg_s(float value); public: - // float yaw_rate_deg_s = 3; + // float yaw_rate_deg_s = 4; void clear_yaw_rate_deg_s() ; float yaw_rate_deg_s() const; void set_yaw_rate_deg_s(float value); @@ -1090,7 +1285,7 @@ class SetAngularRatesRequest final : void _internal_set_yaw_rate_deg_s(float value); public: - // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 4; + // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 5; void clear_gimbal_mode() ; ::mavsdk::rpc::gimbal::GimbalMode gimbal_mode() const; void set_gimbal_mode(::mavsdk::rpc::gimbal::GimbalMode value); @@ -1100,7 +1295,7 @@ class SetAngularRatesRequest final : void _internal_set_gimbal_mode(::mavsdk::rpc::gimbal::GimbalMode value); public: - // .mavsdk.rpc.gimbal.SendMode send_mode = 5; + // .mavsdk.rpc.gimbal.SendMode send_mode = 6; void clear_send_mode() ; ::mavsdk::rpc::gimbal::SendMode send_mode() const; void set_send_mode(::mavsdk::rpc::gimbal::SendMode value); @@ -1116,7 +1311,7 @@ class SetAngularRatesRequest final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 3, 5, 0, + 3, 6, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -1133,6 +1328,7 @@ class SetAngularRatesRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t gimbal_id_; float roll_rate_deg_s_; float pitch_rate_deg_s_; float yaw_rate_deg_s_; @@ -1277,13 +1473,24 @@ class SetAnglesRequest final : // accessors ------------------------------------------------------- enum : int { - kRollDegFieldNumber = 1, - kPitchDegFieldNumber = 2, - kYawDegFieldNumber = 3, - kGimbalModeFieldNumber = 4, - kSendModeFieldNumber = 5, + kGimbalIdFieldNumber = 1, + kRollDegFieldNumber = 2, + kPitchDegFieldNumber = 3, + kYawDegFieldNumber = 4, + kGimbalModeFieldNumber = 5, + kSendModeFieldNumber = 6, }; - // float roll_deg = 1; + // int32 gimbal_id = 1; + void clear_gimbal_id() ; + ::int32_t gimbal_id() const; + void set_gimbal_id(::int32_t value); + + private: + ::int32_t _internal_gimbal_id() const; + void _internal_set_gimbal_id(::int32_t value); + + public: + // float roll_deg = 2; void clear_roll_deg() ; float roll_deg() const; void set_roll_deg(float value); @@ -1293,7 +1500,7 @@ class SetAnglesRequest final : void _internal_set_roll_deg(float value); public: - // float pitch_deg = 2; + // float pitch_deg = 3; void clear_pitch_deg() ; float pitch_deg() const; void set_pitch_deg(float value); @@ -1303,7 +1510,7 @@ class SetAnglesRequest final : void _internal_set_pitch_deg(float value); public: - // float yaw_deg = 3; + // float yaw_deg = 4; void clear_yaw_deg() ; float yaw_deg() const; void set_yaw_deg(float value); @@ -1313,7 +1520,7 @@ class SetAnglesRequest final : void _internal_set_yaw_deg(float value); public: - // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 4; + // .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 5; void clear_gimbal_mode() ; ::mavsdk::rpc::gimbal::GimbalMode gimbal_mode() const; void set_gimbal_mode(::mavsdk::rpc::gimbal::GimbalMode value); @@ -1323,7 +1530,7 @@ class SetAnglesRequest final : void _internal_set_gimbal_mode(::mavsdk::rpc::gimbal::GimbalMode value); public: - // .mavsdk.rpc.gimbal.SendMode send_mode = 5; + // .mavsdk.rpc.gimbal.SendMode send_mode = 6; void clear_send_mode() ; ::mavsdk::rpc::gimbal::SendMode send_mode() const; void set_send_mode(::mavsdk::rpc::gimbal::SendMode value); @@ -1339,7 +1546,7 @@ class SetAnglesRequest final : friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 3, 5, 0, + 3, 6, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -1356,6 +1563,7 @@ class SetAnglesRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t gimbal_id_; float roll_deg_; float pitch_deg_; float yaw_deg_; @@ -1369,9 +1577,10 @@ class SetAnglesRequest final : };// ------------------------------------------------------------------- class ReleaseControlRequest final : - public ::google::protobuf::internal::ZeroFieldsBase /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.ReleaseControlRequest) */ { + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.ReleaseControlRequest) */ { public: inline ReleaseControlRequest() : ReleaseControlRequest(nullptr) {} + ~ReleaseControlRequest() override; template explicit PROTOBUF_CONSTEXPR ReleaseControlRequest(::google::protobuf::internal::ConstantInitialized); @@ -1455,15 +1664,29 @@ class ReleaseControlRequest final : ReleaseControlRequest* New(::google::protobuf::Arena* arena = nullptr) const final { return CreateMaybeMessage(arena); } - using ::google::protobuf::internal::ZeroFieldsBase::CopyFrom; - inline void CopyFrom(const ReleaseControlRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::CopyImpl(*this, from); - } - using ::google::protobuf::internal::ZeroFieldsBase::MergeFrom; - void MergeFrom(const ReleaseControlRequest& from) { - ::google::protobuf::internal::ZeroFieldsBase::MergeImpl(*this, from); + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const ReleaseControlRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const ReleaseControlRequest& from) { + ReleaseControlRequest::MergeImpl(*this, from); } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(ReleaseControlRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; @@ -1475,16 +1698,37 @@ class ReleaseControlRequest final : ReleaseControlRequest(::google::protobuf::Arena* arena, const ReleaseControlRequest& from); public: + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + ::google::protobuf::Metadata GetMetadata() const final; // nested types ---------------------------------------------------- // accessors ------------------------------------------------------- + enum : int { + kGimbalIdFieldNumber = 1, + }; + // int32 gimbal_id = 1; + void clear_gimbal_id() ; + ::int32_t gimbal_id() const; + void set_gimbal_id(::int32_t value); + + private: + ::int32_t _internal_gimbal_id() const; + void _internal_set_gimbal_id(::int32_t value); + + public: // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.ReleaseControlRequest) private: class _Internal; + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 0, + 0, 2> + _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; template @@ -1499,8 +1743,11 @@ class ReleaseControlRequest final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); + ::int32_t gimbal_id_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; + union { Impl_ _impl_; }; friend struct ::TableStruct_gimbal_2fgimbal_2eproto; };// ------------------------------------------------------------------- @@ -1563,7 +1810,7 @@ class Quaternion final : &_Quaternion_default_instance_); } static constexpr int kIndexInFileMessages = - 12; + 14; friend void swap(Quaternion& a, Quaternion& b) { a.Swap(&b); @@ -1774,7 +2021,7 @@ class GimbalResult final : &_GimbalResult_default_instance_); } static constexpr int kIndexInFileMessages = - 19; + 27; friend void swap(GimbalResult& a, GimbalResult& b) { a.Swap(&b); @@ -1933,26 +2180,26 @@ class GimbalResult final : friend struct ::TableStruct_gimbal_2fgimbal_2eproto; };// ------------------------------------------------------------------- -class EulerAngle final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.EulerAngle) */ { +class GimbalItem final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.GimbalItem) */ { public: - inline EulerAngle() : EulerAngle(nullptr) {} - ~EulerAngle() override; + inline GimbalItem() : GimbalItem(nullptr) {} + ~GimbalItem() override; template - explicit PROTOBUF_CONSTEXPR EulerAngle(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR GimbalItem(::google::protobuf::internal::ConstantInitialized); - inline EulerAngle(const EulerAngle& from) - : EulerAngle(nullptr, from) {} - EulerAngle(EulerAngle&& from) noexcept - : EulerAngle() { + inline GimbalItem(const GimbalItem& from) + : GimbalItem(nullptr, from) {} + GimbalItem(GimbalItem&& from) noexcept + : GimbalItem() { *this = ::std::move(from); } - inline EulerAngle& operator=(const EulerAngle& from) { + inline GimbalItem& operator=(const GimbalItem& from) { CopyFrom(from); return *this; } - inline EulerAngle& operator=(EulerAngle&& from) noexcept { + inline GimbalItem& operator=(GimbalItem&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -1984,20 +2231,20 @@ class EulerAngle final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const EulerAngle& default_instance() { + static const GimbalItem& default_instance() { return *internal_default_instance(); } - static inline const EulerAngle* internal_default_instance() { - return reinterpret_cast( - &_EulerAngle_default_instance_); + static inline const GimbalItem* internal_default_instance() { + return reinterpret_cast( + &_GimbalItem_default_instance_); } static constexpr int kIndexInFileMessages = - 13; + 24; - friend void swap(EulerAngle& a, EulerAngle& b) { + friend void swap(GimbalItem& a, GimbalItem& b) { a.Swap(&b); } - inline void Swap(EulerAngle* other) { + inline void Swap(GimbalItem* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2010,7 +2257,7 @@ class EulerAngle final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(EulerAngle* other) { + void UnsafeArenaSwap(GimbalItem* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2018,14 +2265,14 @@ class EulerAngle final : // implements Message ---------------------------------------------- - EulerAngle* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + GimbalItem* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const EulerAngle& from); + void CopyFrom(const GimbalItem& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const EulerAngle& from) { - EulerAngle::MergeImpl(*this, from); + void MergeFrom( const GimbalItem& from) { + GimbalItem::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -2043,16 +2290,16 @@ class EulerAngle final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(EulerAngle* other); + void InternalSwap(GimbalItem* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.gimbal.EulerAngle"; + return "mavsdk.rpc.gimbal.GimbalItem"; } protected: - explicit EulerAngle(::google::protobuf::Arena* arena); - EulerAngle(::google::protobuf::Arena* arena, const EulerAngle& from); + explicit GimbalItem(::google::protobuf::Arena* arena); + GimbalItem(::google::protobuf::Arena* arena, const GimbalItem& from); public: static const ClassData _class_data_; @@ -2065,48 +2312,99 @@ class EulerAngle final : // accessors ------------------------------------------------------- enum : int { - kRollDegFieldNumber = 1, - kPitchDegFieldNumber = 2, - kYawDegFieldNumber = 3, + kVendorNameFieldNumber = 2, + kModelNameFieldNumber = 3, + kCustomNameFieldNumber = 4, + kGimbalIdFieldNumber = 1, + kGimbalManagerComponentIdFieldNumber = 5, + kGimbalDeviceIdFieldNumber = 6, }; - // float roll_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_roll_deg() ; - float roll_deg() const; - void set_roll_deg(float value); + // string vendor_name = 2; + void clear_vendor_name() ; + const std::string& vendor_name() const; + template + void set_vendor_name(Arg_&& arg, Args_... args); + std::string* mutable_vendor_name(); + PROTOBUF_NODISCARD std::string* release_vendor_name(); + void set_allocated_vendor_name(std::string* value); private: - float _internal_roll_deg() const; - void _internal_set_roll_deg(float value); + const std::string& _internal_vendor_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_vendor_name( + const std::string& value); + std::string* _internal_mutable_vendor_name(); public: - // float pitch_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_pitch_deg() ; - float pitch_deg() const; - void set_pitch_deg(float value); + // string model_name = 3; + void clear_model_name() ; + const std::string& model_name() const; + template + void set_model_name(Arg_&& arg, Args_... args); + std::string* mutable_model_name(); + PROTOBUF_NODISCARD std::string* release_model_name(); + void set_allocated_model_name(std::string* value); private: - float _internal_pitch_deg() const; - void _internal_set_pitch_deg(float value); + const std::string& _internal_model_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_model_name( + const std::string& value); + std::string* _internal_mutable_model_name(); public: - // float yaw_deg = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_yaw_deg() ; - float yaw_deg() const; - void set_yaw_deg(float value); + // string custom_name = 4; + void clear_custom_name() ; + const std::string& custom_name() const; + template + void set_custom_name(Arg_&& arg, Args_... args); + std::string* mutable_custom_name(); + PROTOBUF_NODISCARD std::string* release_custom_name(); + void set_allocated_custom_name(std::string* value); private: - float _internal_yaw_deg() const; - void _internal_set_yaw_deg(float value); + const std::string& _internal_custom_name() const; + inline PROTOBUF_ALWAYS_INLINE void _internal_set_custom_name( + const std::string& value); + std::string* _internal_mutable_custom_name(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.EulerAngle) + // int32 gimbal_id = 1; + void clear_gimbal_id() ; + ::int32_t gimbal_id() const; + void set_gimbal_id(::int32_t value); + + private: + ::int32_t _internal_gimbal_id() const; + void _internal_set_gimbal_id(::int32_t value); + + public: + // int32 gimbal_manager_component_id = 5; + void clear_gimbal_manager_component_id() ; + ::int32_t gimbal_manager_component_id() const; + void set_gimbal_manager_component_id(::int32_t value); + + private: + ::int32_t _internal_gimbal_manager_component_id() const; + void _internal_set_gimbal_manager_component_id(::int32_t value); + + public: + // int32 gimbal_device_id = 6; + void clear_gimbal_device_id() ; + ::int32_t gimbal_device_id() const; + void set_gimbal_device_id(::int32_t value); + + private: + ::int32_t _internal_gimbal_device_id() const; + void _internal_set_gimbal_device_id(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.GimbalItem) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 0, - 0, 2> + 3, 6, 0, + 69, 2> _table_; friend class ::google::protobuf::MessageLite; friend class ::google::protobuf::Arena; @@ -2122,9 +2420,12 @@ class EulerAngle final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float roll_deg_; - float pitch_deg_; - float yaw_deg_; + ::google::protobuf::internal::ArenaStringPtr vendor_name_; + ::google::protobuf::internal::ArenaStringPtr model_name_; + ::google::protobuf::internal::ArenaStringPtr custom_name_; + ::int32_t gimbal_id_; + ::int32_t gimbal_manager_component_id_; + ::int32_t gimbal_device_id_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -2132,26 +2433,26 @@ class EulerAngle final : friend struct ::TableStruct_gimbal_2fgimbal_2eproto; };// ------------------------------------------------------------------- -class ControlStatus final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.ControlStatus) */ { +class GetControlStatusRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.GetControlStatusRequest) */ { public: - inline ControlStatus() : ControlStatus(nullptr) {} - ~ControlStatus() override; + inline GetControlStatusRequest() : GetControlStatusRequest(nullptr) {} + ~GetControlStatusRequest() override; template - explicit PROTOBUF_CONSTEXPR ControlStatus(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR GetControlStatusRequest(::google::protobuf::internal::ConstantInitialized); - inline ControlStatus(const ControlStatus& from) - : ControlStatus(nullptr, from) {} - ControlStatus(ControlStatus&& from) noexcept - : ControlStatus() { + inline GetControlStatusRequest(const GetControlStatusRequest& from) + : GetControlStatusRequest(nullptr, from) {} + GetControlStatusRequest(GetControlStatusRequest&& from) noexcept + : GetControlStatusRequest() { *this = ::std::move(from); } - inline ControlStatus& operator=(const ControlStatus& from) { + inline GetControlStatusRequest& operator=(const GetControlStatusRequest& from) { CopyFrom(from); return *this; } - inline ControlStatus& operator=(ControlStatus&& from) noexcept { + inline GetControlStatusRequest& operator=(GetControlStatusRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2183,20 +2484,20 @@ class ControlStatus final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const ControlStatus& default_instance() { + static const GetControlStatusRequest& default_instance() { return *internal_default_instance(); } - static inline const ControlStatus* internal_default_instance() { - return reinterpret_cast( - &_ControlStatus_default_instance_); + static inline const GetControlStatusRequest* internal_default_instance() { + return reinterpret_cast( + &_GetControlStatusRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 18; + 12; - friend void swap(ControlStatus& a, ControlStatus& b) { + friend void swap(GetControlStatusRequest& a, GetControlStatusRequest& b) { a.Swap(&b); } - inline void Swap(ControlStatus* other) { + inline void Swap(GetControlStatusRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2209,7 +2510,7 @@ class ControlStatus final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(ControlStatus* other) { + void UnsafeArenaSwap(GetControlStatusRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2217,14 +2518,14 @@ class ControlStatus final : // implements Message ---------------------------------------------- - ControlStatus* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + GetControlStatusRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const ControlStatus& from); + void CopyFrom(const GetControlStatusRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const ControlStatus& from) { - ControlStatus::MergeImpl(*this, from); + void MergeFrom( const GetControlStatusRequest& from) { + GetControlStatusRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -2242,16 +2543,16 @@ class ControlStatus final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(ControlStatus* other); + void InternalSwap(GetControlStatusRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.gimbal.ControlStatus"; + return "mavsdk.rpc.gimbal.GetControlStatusRequest"; } protected: - explicit ControlStatus(::google::protobuf::Arena* arena); - ControlStatus(::google::protobuf::Arena* arena, const ControlStatus& from); + explicit GetControlStatusRequest(::google::protobuf::Arena* arena); + GetControlStatusRequest(::google::protobuf::Arena* arena, const GetControlStatusRequest& from); public: static const ClassData _class_data_; @@ -2264,69 +2565,25 @@ class ControlStatus final : // accessors ------------------------------------------------------- enum : int { - kControlModeFieldNumber = 1, - kSysidPrimaryControlFieldNumber = 2, - kCompidPrimaryControlFieldNumber = 3, - kSysidSecondaryControlFieldNumber = 4, - kCompidSecondaryControlFieldNumber = 5, + kGimbalIdFieldNumber = 1, }; - // .mavsdk.rpc.gimbal.ControlMode control_mode = 1; - void clear_control_mode() ; - ::mavsdk::rpc::gimbal::ControlMode control_mode() const; - void set_control_mode(::mavsdk::rpc::gimbal::ControlMode value); - - private: - ::mavsdk::rpc::gimbal::ControlMode _internal_control_mode() const; - void _internal_set_control_mode(::mavsdk::rpc::gimbal::ControlMode value); - - public: - // int32 sysid_primary_control = 2; - void clear_sysid_primary_control() ; - ::int32_t sysid_primary_control() const; - void set_sysid_primary_control(::int32_t value); - - private: - ::int32_t _internal_sysid_primary_control() const; - void _internal_set_sysid_primary_control(::int32_t value); - - public: - // int32 compid_primary_control = 3; - void clear_compid_primary_control() ; - ::int32_t compid_primary_control() const; - void set_compid_primary_control(::int32_t value); - - private: - ::int32_t _internal_compid_primary_control() const; - void _internal_set_compid_primary_control(::int32_t value); - - public: - // int32 sysid_secondary_control = 4; - void clear_sysid_secondary_control() ; - ::int32_t sysid_secondary_control() const; - void set_sysid_secondary_control(::int32_t value); + // int32 gimbal_id = 1; + void clear_gimbal_id() ; + ::int32_t gimbal_id() const; + void set_gimbal_id(::int32_t value); private: - ::int32_t _internal_sysid_secondary_control() const; - void _internal_set_sysid_secondary_control(::int32_t value); - - public: - // int32 compid_secondary_control = 5; - void clear_compid_secondary_control() ; - ::int32_t compid_secondary_control() const; - void set_compid_secondary_control(::int32_t value); - - private: - ::int32_t _internal_compid_secondary_control() const; - void _internal_set_compid_secondary_control(::int32_t value); + ::int32_t _internal_gimbal_id() const; + void _internal_set_gimbal_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.ControlStatus) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.GetControlStatusRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 3, 5, 0, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -2343,11 +2600,7 @@ class ControlStatus final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - int control_mode_; - ::int32_t sysid_primary_control_; - ::int32_t compid_primary_control_; - ::int32_t sysid_secondary_control_; - ::int32_t compid_secondary_control_; + ::int32_t gimbal_id_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -2355,26 +2608,26 @@ class ControlStatus final : friend struct ::TableStruct_gimbal_2fgimbal_2eproto; };// ------------------------------------------------------------------- -class AngularVelocityBody final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.AngularVelocityBody) */ { +class GetAttitudeRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.GetAttitudeRequest) */ { public: - inline AngularVelocityBody() : AngularVelocityBody(nullptr) {} - ~AngularVelocityBody() override; + inline GetAttitudeRequest() : GetAttitudeRequest(nullptr) {} + ~GetAttitudeRequest() override; template - explicit PROTOBUF_CONSTEXPR AngularVelocityBody(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR GetAttitudeRequest(::google::protobuf::internal::ConstantInitialized); - inline AngularVelocityBody(const AngularVelocityBody& from) - : AngularVelocityBody(nullptr, from) {} - AngularVelocityBody(AngularVelocityBody&& from) noexcept - : AngularVelocityBody() { + inline GetAttitudeRequest(const GetAttitudeRequest& from) + : GetAttitudeRequest(nullptr, from) {} + GetAttitudeRequest(GetAttitudeRequest&& from) noexcept + : GetAttitudeRequest() { *this = ::std::move(from); } - inline AngularVelocityBody& operator=(const AngularVelocityBody& from) { + inline GetAttitudeRequest& operator=(const GetAttitudeRequest& from) { CopyFrom(from); return *this; } - inline AngularVelocityBody& operator=(AngularVelocityBody&& from) noexcept { + inline GetAttitudeRequest& operator=(GetAttitudeRequest&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2406,20 +2659,20 @@ class AngularVelocityBody final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const AngularVelocityBody& default_instance() { + static const GetAttitudeRequest& default_instance() { return *internal_default_instance(); } - static inline const AngularVelocityBody* internal_default_instance() { - return reinterpret_cast( - &_AngularVelocityBody_default_instance_); + static inline const GetAttitudeRequest* internal_default_instance() { + return reinterpret_cast( + &_GetAttitudeRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 14; + 20; - friend void swap(AngularVelocityBody& a, AngularVelocityBody& b) { + friend void swap(GetAttitudeRequest& a, GetAttitudeRequest& b) { a.Swap(&b); } - inline void Swap(AngularVelocityBody* other) { + inline void Swap(GetAttitudeRequest* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2432,7 +2685,7 @@ class AngularVelocityBody final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(AngularVelocityBody* other) { + void UnsafeArenaSwap(GetAttitudeRequest* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2440,14 +2693,14 @@ class AngularVelocityBody final : // implements Message ---------------------------------------------- - AngularVelocityBody* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + GetAttitudeRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const AngularVelocityBody& from); + void CopyFrom(const GetAttitudeRequest& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const AngularVelocityBody& from) { - AngularVelocityBody::MergeImpl(*this, from); + void MergeFrom( const GetAttitudeRequest& from) { + GetAttitudeRequest::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -2465,16 +2718,16 @@ class AngularVelocityBody final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(AngularVelocityBody* other); + void InternalSwap(GetAttitudeRequest* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.gimbal.AngularVelocityBody"; + return "mavsdk.rpc.gimbal.GetAttitudeRequest"; } protected: - explicit AngularVelocityBody(::google::protobuf::Arena* arena); - AngularVelocityBody(::google::protobuf::Arena* arena, const AngularVelocityBody& from); + explicit GetAttitudeRequest(::google::protobuf::Arena* arena); + GetAttitudeRequest(::google::protobuf::Arena* arena, const GetAttitudeRequest& from); public: static const ClassData _class_data_; @@ -2487,47 +2740,25 @@ class AngularVelocityBody final : // accessors ------------------------------------------------------- enum : int { - kRollRadSFieldNumber = 1, - kPitchRadSFieldNumber = 2, - kYawRadSFieldNumber = 3, + kGimbalIdFieldNumber = 1, }; - // float roll_rad_s = 1 [(.mavsdk.options.default_value) = "NaN"]; - void clear_roll_rad_s() ; - float roll_rad_s() const; - void set_roll_rad_s(float value); - - private: - float _internal_roll_rad_s() const; - void _internal_set_roll_rad_s(float value); - - public: - // float pitch_rad_s = 2 [(.mavsdk.options.default_value) = "NaN"]; - void clear_pitch_rad_s() ; - float pitch_rad_s() const; - void set_pitch_rad_s(float value); - - private: - float _internal_pitch_rad_s() const; - void _internal_set_pitch_rad_s(float value); - - public: - // float yaw_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; - void clear_yaw_rad_s() ; - float yaw_rad_s() const; - void set_yaw_rad_s(float value); + // int32 gimbal_id = 1; + void clear_gimbal_id() ; + ::int32_t gimbal_id() const; + void set_gimbal_id(::int32_t value); private: - float _internal_yaw_rad_s() const; - void _internal_set_yaw_rad_s(float value); + ::int32_t _internal_gimbal_id() const; + void _internal_set_gimbal_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.AngularVelocityBody) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.GetAttitudeRequest) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 2, 3, 0, + 0, 1, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -2544,9 +2775,7 @@ class AngularVelocityBody final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - float roll_rad_s_; - float pitch_rad_s_; - float yaw_rad_s_; + ::int32_t gimbal_id_; mutable ::google::protobuf::internal::CachedSize _cached_size_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -2554,26 +2783,26 @@ class AngularVelocityBody final : friend struct ::TableStruct_gimbal_2fgimbal_2eproto; };// ------------------------------------------------------------------- -class TakeControlResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.TakeControlResponse) */ { +class EulerAngle final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.EulerAngle) */ { public: - inline TakeControlResponse() : TakeControlResponse(nullptr) {} - ~TakeControlResponse() override; + inline EulerAngle() : EulerAngle(nullptr) {} + ~EulerAngle() override; template - explicit PROTOBUF_CONSTEXPR TakeControlResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR EulerAngle(::google::protobuf::internal::ConstantInitialized); - inline TakeControlResponse(const TakeControlResponse& from) - : TakeControlResponse(nullptr, from) {} - TakeControlResponse(TakeControlResponse&& from) noexcept - : TakeControlResponse() { + inline EulerAngle(const EulerAngle& from) + : EulerAngle(nullptr, from) {} + EulerAngle(EulerAngle&& from) noexcept + : EulerAngle() { *this = ::std::move(from); } - inline TakeControlResponse& operator=(const TakeControlResponse& from) { + inline EulerAngle& operator=(const EulerAngle& from) { CopyFrom(from); return *this; } - inline TakeControlResponse& operator=(TakeControlResponse&& from) noexcept { + inline EulerAngle& operator=(EulerAngle&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2605,20 +2834,20 @@ class TakeControlResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const TakeControlResponse& default_instance() { + static const EulerAngle& default_instance() { return *internal_default_instance(); } - static inline const TakeControlResponse* internal_default_instance() { - return reinterpret_cast( - &_TakeControlResponse_default_instance_); + static inline const EulerAngle* internal_default_instance() { + return reinterpret_cast( + &_EulerAngle_default_instance_); } static constexpr int kIndexInFileMessages = - 7; + 15; - friend void swap(TakeControlResponse& a, TakeControlResponse& b) { + friend void swap(EulerAngle& a, EulerAngle& b) { a.Swap(&b); } - inline void Swap(TakeControlResponse* other) { + inline void Swap(EulerAngle* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2631,7 +2860,7 @@ class TakeControlResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(TakeControlResponse* other) { + void UnsafeArenaSwap(EulerAngle* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2639,14 +2868,14 @@ class TakeControlResponse final : // implements Message ---------------------------------------------- - TakeControlResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + EulerAngle* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const TakeControlResponse& from); + void CopyFrom(const EulerAngle& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const TakeControlResponse& from) { - TakeControlResponse::MergeImpl(*this, from); + void MergeFrom( const EulerAngle& from) { + EulerAngle::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -2664,16 +2893,16 @@ class TakeControlResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(TakeControlResponse* other); + void InternalSwap(EulerAngle* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.gimbal.TakeControlResponse"; + return "mavsdk.rpc.gimbal.EulerAngle"; } protected: - explicit TakeControlResponse(::google::protobuf::Arena* arena); - TakeControlResponse(::google::protobuf::Arena* arena, const TakeControlResponse& from); + explicit EulerAngle(::google::protobuf::Arena* arena); + EulerAngle(::google::protobuf::Arena* arena, const EulerAngle& from); public: static const ClassData _class_data_; @@ -2686,30 +2915,47 @@ class TakeControlResponse final : // accessors ------------------------------------------------------- enum : int { - kGimbalResultFieldNumber = 1, + kRollDegFieldNumber = 1, + kPitchDegFieldNumber = 2, + kYawDegFieldNumber = 3, }; - // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; - bool has_gimbal_result() const; - void clear_gimbal_result() ; - const ::mavsdk::rpc::gimbal::GimbalResult& gimbal_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::GimbalResult* release_gimbal_result(); - ::mavsdk::rpc::gimbal::GimbalResult* mutable_gimbal_result(); - void set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); - void unsafe_arena_set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); - ::mavsdk::rpc::gimbal::GimbalResult* unsafe_arena_release_gimbal_result(); + // float roll_deg = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_roll_deg() ; + float roll_deg() const; + void set_roll_deg(float value); private: - const ::mavsdk::rpc::gimbal::GimbalResult& _internal_gimbal_result() const; - ::mavsdk::rpc::gimbal::GimbalResult* _internal_mutable_gimbal_result(); + float _internal_roll_deg() const; + void _internal_set_roll_deg(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.TakeControlResponse) + // float pitch_deg = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_pitch_deg() ; + float pitch_deg() const; + void set_pitch_deg(float value); + + private: + float _internal_pitch_deg() const; + void _internal_set_pitch_deg(float value); + + public: + // float yaw_deg = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_yaw_deg() ; + float yaw_deg() const; + void set_yaw_deg(float value); + + private: + float _internal_yaw_deg() const; + void _internal_set_yaw_deg(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.EulerAngle) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 2, 3, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -2726,35 +2972,36 @@ class TakeControlResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::HasBits<1> _has_bits_; + float roll_deg_; + float pitch_deg_; + float yaw_deg_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::gimbal::GimbalResult* gimbal_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_gimbal_2fgimbal_2eproto; };// ------------------------------------------------------------------- -class SetRoiLocationResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.SetRoiLocationResponse) */ { +class ControlStatus final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.ControlStatus) */ { public: - inline SetRoiLocationResponse() : SetRoiLocationResponse(nullptr) {} - ~SetRoiLocationResponse() override; + inline ControlStatus() : ControlStatus(nullptr) {} + ~ControlStatus() override; template - explicit PROTOBUF_CONSTEXPR SetRoiLocationResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR ControlStatus(::google::protobuf::internal::ConstantInitialized); - inline SetRoiLocationResponse(const SetRoiLocationResponse& from) - : SetRoiLocationResponse(nullptr, from) {} - SetRoiLocationResponse(SetRoiLocationResponse&& from) noexcept - : SetRoiLocationResponse() { + inline ControlStatus(const ControlStatus& from) + : ControlStatus(nullptr, from) {} + ControlStatus(ControlStatus&& from) noexcept + : ControlStatus() { *this = ::std::move(from); } - inline SetRoiLocationResponse& operator=(const SetRoiLocationResponse& from) { + inline ControlStatus& operator=(const ControlStatus& from) { CopyFrom(from); return *this; } - inline SetRoiLocationResponse& operator=(SetRoiLocationResponse&& from) noexcept { + inline ControlStatus& operator=(ControlStatus&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2786,20 +3033,20 @@ class SetRoiLocationResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetRoiLocationResponse& default_instance() { + static const ControlStatus& default_instance() { return *internal_default_instance(); } - static inline const SetRoiLocationResponse* internal_default_instance() { - return reinterpret_cast( - &_SetRoiLocationResponse_default_instance_); + static inline const ControlStatus* internal_default_instance() { + return reinterpret_cast( + &_ControlStatus_default_instance_); } static constexpr int kIndexInFileMessages = - 5; + 26; - friend void swap(SetRoiLocationResponse& a, SetRoiLocationResponse& b) { + friend void swap(ControlStatus& a, ControlStatus& b) { a.Swap(&b); } - inline void Swap(SetRoiLocationResponse* other) { + inline void Swap(ControlStatus* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2812,7 +3059,7 @@ class SetRoiLocationResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetRoiLocationResponse* other) { + void UnsafeArenaSwap(ControlStatus* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -2820,14 +3067,14 @@ class SetRoiLocationResponse final : // implements Message ---------------------------------------------- - SetRoiLocationResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + ControlStatus* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetRoiLocationResponse& from); + void CopyFrom(const ControlStatus& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetRoiLocationResponse& from) { - SetRoiLocationResponse::MergeImpl(*this, from); + void MergeFrom( const ControlStatus& from) { + ControlStatus::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -2845,16 +3092,16 @@ class SetRoiLocationResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetRoiLocationResponse* other); + void InternalSwap(ControlStatus* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.gimbal.SetRoiLocationResponse"; + return "mavsdk.rpc.gimbal.ControlStatus"; } protected: - explicit SetRoiLocationResponse(::google::protobuf::Arena* arena); - SetRoiLocationResponse(::google::protobuf::Arena* arena, const SetRoiLocationResponse& from); + explicit ControlStatus(::google::protobuf::Arena* arena); + ControlStatus(::google::protobuf::Arena* arena, const ControlStatus& from); public: static const ClassData _class_data_; @@ -2867,30 +3114,80 @@ class SetRoiLocationResponse final : // accessors ------------------------------------------------------- enum : int { - kGimbalResultFieldNumber = 1, + kGimbalIdFieldNumber = 1, + kControlModeFieldNumber = 2, + kSysidPrimaryControlFieldNumber = 3, + kCompidPrimaryControlFieldNumber = 4, + kSysidSecondaryControlFieldNumber = 5, + kCompidSecondaryControlFieldNumber = 6, }; - // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; - bool has_gimbal_result() const; - void clear_gimbal_result() ; - const ::mavsdk::rpc::gimbal::GimbalResult& gimbal_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::GimbalResult* release_gimbal_result(); - ::mavsdk::rpc::gimbal::GimbalResult* mutable_gimbal_result(); - void set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); - void unsafe_arena_set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); - ::mavsdk::rpc::gimbal::GimbalResult* unsafe_arena_release_gimbal_result(); + // int32 gimbal_id = 1; + void clear_gimbal_id() ; + ::int32_t gimbal_id() const; + void set_gimbal_id(::int32_t value); private: - const ::mavsdk::rpc::gimbal::GimbalResult& _internal_gimbal_result() const; - ::mavsdk::rpc::gimbal::GimbalResult* _internal_mutable_gimbal_result(); + ::int32_t _internal_gimbal_id() const; + void _internal_set_gimbal_id(::int32_t value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.SetRoiLocationResponse) + // .mavsdk.rpc.gimbal.ControlMode control_mode = 2; + void clear_control_mode() ; + ::mavsdk::rpc::gimbal::ControlMode control_mode() const; + void set_control_mode(::mavsdk::rpc::gimbal::ControlMode value); + + private: + ::mavsdk::rpc::gimbal::ControlMode _internal_control_mode() const; + void _internal_set_control_mode(::mavsdk::rpc::gimbal::ControlMode value); + + public: + // int32 sysid_primary_control = 3; + void clear_sysid_primary_control() ; + ::int32_t sysid_primary_control() const; + void set_sysid_primary_control(::int32_t value); + + private: + ::int32_t _internal_sysid_primary_control() const; + void _internal_set_sysid_primary_control(::int32_t value); + + public: + // int32 compid_primary_control = 4; + void clear_compid_primary_control() ; + ::int32_t compid_primary_control() const; + void set_compid_primary_control(::int32_t value); + + private: + ::int32_t _internal_compid_primary_control() const; + void _internal_set_compid_primary_control(::int32_t value); + + public: + // int32 sysid_secondary_control = 5; + void clear_sysid_secondary_control() ; + ::int32_t sysid_secondary_control() const; + void set_sysid_secondary_control(::int32_t value); + + private: + ::int32_t _internal_sysid_secondary_control() const; + void _internal_set_sysid_secondary_control(::int32_t value); + + public: + // int32 compid_secondary_control = 6; + void clear_compid_secondary_control() ; + ::int32_t compid_secondary_control() const; + void set_compid_secondary_control(::int32_t value); + + private: + ::int32_t _internal_compid_secondary_control() const; + void _internal_set_compid_secondary_control(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.ControlStatus) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 3, 6, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -2907,35 +3204,39 @@ class SetRoiLocationResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::HasBits<1> _has_bits_; + ::int32_t gimbal_id_; + int control_mode_; + ::int32_t sysid_primary_control_; + ::int32_t compid_primary_control_; + ::int32_t sysid_secondary_control_; + ::int32_t compid_secondary_control_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::gimbal::GimbalResult* gimbal_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_gimbal_2fgimbal_2eproto; };// ------------------------------------------------------------------- -class SetAngularRatesResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.SetAngularRatesResponse) */ { +class AngularVelocityBody final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.AngularVelocityBody) */ { public: - inline SetAngularRatesResponse() : SetAngularRatesResponse(nullptr) {} - ~SetAngularRatesResponse() override; + inline AngularVelocityBody() : AngularVelocityBody(nullptr) {} + ~AngularVelocityBody() override; template - explicit PROTOBUF_CONSTEXPR SetAngularRatesResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR AngularVelocityBody(::google::protobuf::internal::ConstantInitialized); - inline SetAngularRatesResponse(const SetAngularRatesResponse& from) - : SetAngularRatesResponse(nullptr, from) {} - SetAngularRatesResponse(SetAngularRatesResponse&& from) noexcept - : SetAngularRatesResponse() { + inline AngularVelocityBody(const AngularVelocityBody& from) + : AngularVelocityBody(nullptr, from) {} + AngularVelocityBody(AngularVelocityBody&& from) noexcept + : AngularVelocityBody() { *this = ::std::move(from); } - inline SetAngularRatesResponse& operator=(const SetAngularRatesResponse& from) { + inline AngularVelocityBody& operator=(const AngularVelocityBody& from) { CopyFrom(from); return *this; } - inline SetAngularRatesResponse& operator=(SetAngularRatesResponse&& from) noexcept { + inline AngularVelocityBody& operator=(AngularVelocityBody&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -2967,20 +3268,20 @@ class SetAngularRatesResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetAngularRatesResponse& default_instance() { + static const AngularVelocityBody& default_instance() { return *internal_default_instance(); } - static inline const SetAngularRatesResponse* internal_default_instance() { - return reinterpret_cast( - &_SetAngularRatesResponse_default_instance_); + static inline const AngularVelocityBody* internal_default_instance() { + return reinterpret_cast( + &_AngularVelocityBody_default_instance_); } static constexpr int kIndexInFileMessages = - 3; + 16; - friend void swap(SetAngularRatesResponse& a, SetAngularRatesResponse& b) { + friend void swap(AngularVelocityBody& a, AngularVelocityBody& b) { a.Swap(&b); } - inline void Swap(SetAngularRatesResponse* other) { + inline void Swap(AngularVelocityBody* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -2993,7 +3294,7 @@ class SetAngularRatesResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetAngularRatesResponse* other) { + void UnsafeArenaSwap(AngularVelocityBody* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3001,14 +3302,14 @@ class SetAngularRatesResponse final : // implements Message ---------------------------------------------- - SetAngularRatesResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + AngularVelocityBody* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetAngularRatesResponse& from); + void CopyFrom(const AngularVelocityBody& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetAngularRatesResponse& from) { - SetAngularRatesResponse::MergeImpl(*this, from); + void MergeFrom( const AngularVelocityBody& from) { + AngularVelocityBody::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -3026,16 +3327,16 @@ class SetAngularRatesResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetAngularRatesResponse* other); + void InternalSwap(AngularVelocityBody* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.gimbal.SetAngularRatesResponse"; + return "mavsdk.rpc.gimbal.AngularVelocityBody"; } protected: - explicit SetAngularRatesResponse(::google::protobuf::Arena* arena); - SetAngularRatesResponse(::google::protobuf::Arena* arena, const SetAngularRatesResponse& from); + explicit AngularVelocityBody(::google::protobuf::Arena* arena); + AngularVelocityBody(::google::protobuf::Arena* arena, const AngularVelocityBody& from); public: static const ClassData _class_data_; @@ -3048,30 +3349,47 @@ class SetAngularRatesResponse final : // accessors ------------------------------------------------------- enum : int { - kGimbalResultFieldNumber = 1, + kRollRadSFieldNumber = 1, + kPitchRadSFieldNumber = 2, + kYawRadSFieldNumber = 3, }; - // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; - bool has_gimbal_result() const; - void clear_gimbal_result() ; - const ::mavsdk::rpc::gimbal::GimbalResult& gimbal_result() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::GimbalResult* release_gimbal_result(); - ::mavsdk::rpc::gimbal::GimbalResult* mutable_gimbal_result(); - void set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); - void unsafe_arena_set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); - ::mavsdk::rpc::gimbal::GimbalResult* unsafe_arena_release_gimbal_result(); + // float roll_rad_s = 1 [(.mavsdk.options.default_value) = "NaN"]; + void clear_roll_rad_s() ; + float roll_rad_s() const; + void set_roll_rad_s(float value); private: - const ::mavsdk::rpc::gimbal::GimbalResult& _internal_gimbal_result() const; - ::mavsdk::rpc::gimbal::GimbalResult* _internal_mutable_gimbal_result(); + float _internal_roll_rad_s() const; + void _internal_set_roll_rad_s(float value); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.SetAngularRatesResponse) + // float pitch_rad_s = 2 [(.mavsdk.options.default_value) = "NaN"]; + void clear_pitch_rad_s() ; + float pitch_rad_s() const; + void set_pitch_rad_s(float value); + + private: + float _internal_pitch_rad_s() const; + void _internal_set_pitch_rad_s(float value); + + public: + // float yaw_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; + void clear_yaw_rad_s() ; + float yaw_rad_s() const; + void set_yaw_rad_s(float value); + + private: + float _internal_yaw_rad_s() const; + void _internal_set_yaw_rad_s(float value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.AngularVelocityBody) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 0, 1, 1, + 2, 3, 0, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -3088,35 +3406,36 @@ class SetAngularRatesResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::HasBits<1> _has_bits_; + float roll_rad_s_; + float pitch_rad_s_; + float yaw_rad_s_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::gimbal::GimbalResult* gimbal_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_gimbal_2fgimbal_2eproto; };// ------------------------------------------------------------------- -class SetAnglesResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.SetAnglesResponse) */ { +class TakeControlResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.TakeControlResponse) */ { public: - inline SetAnglesResponse() : SetAnglesResponse(nullptr) {} - ~SetAnglesResponse() override; + inline TakeControlResponse() : TakeControlResponse(nullptr) {} + ~TakeControlResponse() override; template - explicit PROTOBUF_CONSTEXPR SetAnglesResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR TakeControlResponse(::google::protobuf::internal::ConstantInitialized); - inline SetAnglesResponse(const SetAnglesResponse& from) - : SetAnglesResponse(nullptr, from) {} - SetAnglesResponse(SetAnglesResponse&& from) noexcept - : SetAnglesResponse() { + inline TakeControlResponse(const TakeControlResponse& from) + : TakeControlResponse(nullptr, from) {} + TakeControlResponse(TakeControlResponse&& from) noexcept + : TakeControlResponse() { *this = ::std::move(from); } - inline SetAnglesResponse& operator=(const SetAnglesResponse& from) { + inline TakeControlResponse& operator=(const TakeControlResponse& from) { CopyFrom(from); return *this; } - inline SetAnglesResponse& operator=(SetAnglesResponse&& from) noexcept { + inline TakeControlResponse& operator=(TakeControlResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3148,20 +3467,20 @@ class SetAnglesResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const SetAnglesResponse& default_instance() { + static const TakeControlResponse& default_instance() { return *internal_default_instance(); } - static inline const SetAnglesResponse* internal_default_instance() { - return reinterpret_cast( - &_SetAnglesResponse_default_instance_); + static inline const TakeControlResponse* internal_default_instance() { + return reinterpret_cast( + &_TakeControlResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 1; + 7; - friend void swap(SetAnglesResponse& a, SetAnglesResponse& b) { + friend void swap(TakeControlResponse& a, TakeControlResponse& b) { a.Swap(&b); } - inline void Swap(SetAnglesResponse* other) { + inline void Swap(TakeControlResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3174,7 +3493,7 @@ class SetAnglesResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(SetAnglesResponse* other) { + void UnsafeArenaSwap(TakeControlResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3182,14 +3501,14 @@ class SetAnglesResponse final : // implements Message ---------------------------------------------- - SetAnglesResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + TakeControlResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const SetAnglesResponse& from); + void CopyFrom(const TakeControlResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const SetAnglesResponse& from) { - SetAnglesResponse::MergeImpl(*this, from); + void MergeFrom( const TakeControlResponse& from) { + TakeControlResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -3207,16 +3526,16 @@ class SetAnglesResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(SetAnglesResponse* other); + void InternalSwap(TakeControlResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.gimbal.SetAnglesResponse"; + return "mavsdk.rpc.gimbal.TakeControlResponse"; } protected: - explicit SetAnglesResponse(::google::protobuf::Arena* arena); - SetAnglesResponse(::google::protobuf::Arena* arena, const SetAnglesResponse& from); + explicit TakeControlResponse(::google::protobuf::Arena* arena); + TakeControlResponse(::google::protobuf::Arena* arena, const TakeControlResponse& from); public: static const ClassData _class_data_; @@ -3246,7 +3565,7 @@ class SetAnglesResponse final : ::mavsdk::rpc::gimbal::GimbalResult* _internal_mutable_gimbal_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.SetAnglesResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.TakeControlResponse) private: class _Internal; @@ -3278,26 +3597,26 @@ class SetAnglesResponse final : friend struct ::TableStruct_gimbal_2fgimbal_2eproto; };// ------------------------------------------------------------------- -class ReleaseControlResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.ReleaseControlResponse) */ { +class SetRoiLocationResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.SetRoiLocationResponse) */ { public: - inline ReleaseControlResponse() : ReleaseControlResponse(nullptr) {} - ~ReleaseControlResponse() override; + inline SetRoiLocationResponse() : SetRoiLocationResponse(nullptr) {} + ~SetRoiLocationResponse() override; template - explicit PROTOBUF_CONSTEXPR ReleaseControlResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetRoiLocationResponse(::google::protobuf::internal::ConstantInitialized); - inline ReleaseControlResponse(const ReleaseControlResponse& from) - : ReleaseControlResponse(nullptr, from) {} - ReleaseControlResponse(ReleaseControlResponse&& from) noexcept - : ReleaseControlResponse() { + inline SetRoiLocationResponse(const SetRoiLocationResponse& from) + : SetRoiLocationResponse(nullptr, from) {} + SetRoiLocationResponse(SetRoiLocationResponse&& from) noexcept + : SetRoiLocationResponse() { *this = ::std::move(from); } - inline ReleaseControlResponse& operator=(const ReleaseControlResponse& from) { + inline SetRoiLocationResponse& operator=(const SetRoiLocationResponse& from) { CopyFrom(from); return *this; } - inline ReleaseControlResponse& operator=(ReleaseControlResponse&& from) noexcept { + inline SetRoiLocationResponse& operator=(SetRoiLocationResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3329,20 +3648,20 @@ class ReleaseControlResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const ReleaseControlResponse& default_instance() { + static const SetRoiLocationResponse& default_instance() { return *internal_default_instance(); } - static inline const ReleaseControlResponse* internal_default_instance() { - return reinterpret_cast( - &_ReleaseControlResponse_default_instance_); + static inline const SetRoiLocationResponse* internal_default_instance() { + return reinterpret_cast( + &_SetRoiLocationResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 9; + 5; - friend void swap(ReleaseControlResponse& a, ReleaseControlResponse& b) { + friend void swap(SetRoiLocationResponse& a, SetRoiLocationResponse& b) { a.Swap(&b); } - inline void Swap(ReleaseControlResponse* other) { + inline void Swap(SetRoiLocationResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3355,7 +3674,7 @@ class ReleaseControlResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(ReleaseControlResponse* other) { + void UnsafeArenaSwap(SetRoiLocationResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3363,14 +3682,14 @@ class ReleaseControlResponse final : // implements Message ---------------------------------------------- - ReleaseControlResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetRoiLocationResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const ReleaseControlResponse& from); + void CopyFrom(const SetRoiLocationResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const ReleaseControlResponse& from) { - ReleaseControlResponse::MergeImpl(*this, from); + void MergeFrom( const SetRoiLocationResponse& from) { + SetRoiLocationResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -3388,16 +3707,16 @@ class ReleaseControlResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(ReleaseControlResponse* other); + void InternalSwap(SetRoiLocationResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.gimbal.ReleaseControlResponse"; + return "mavsdk.rpc.gimbal.SetRoiLocationResponse"; } protected: - explicit ReleaseControlResponse(::google::protobuf::Arena* arena); - ReleaseControlResponse(::google::protobuf::Arena* arena, const ReleaseControlResponse& from); + explicit SetRoiLocationResponse(::google::protobuf::Arena* arena); + SetRoiLocationResponse(::google::protobuf::Arena* arena, const SetRoiLocationResponse& from); public: static const ClassData _class_data_; @@ -3427,7 +3746,7 @@ class ReleaseControlResponse final : ::mavsdk::rpc::gimbal::GimbalResult* _internal_mutable_gimbal_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.ReleaseControlResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.SetRoiLocationResponse) private: class _Internal; @@ -3459,26 +3778,26 @@ class ReleaseControlResponse final : friend struct ::TableStruct_gimbal_2fgimbal_2eproto; };// ------------------------------------------------------------------- -class ControlResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.ControlResponse) */ { +class SetAngularRatesResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.SetAngularRatesResponse) */ { public: - inline ControlResponse() : ControlResponse(nullptr) {} - ~ControlResponse() override; + inline SetAngularRatesResponse() : SetAngularRatesResponse(nullptr) {} + ~SetAngularRatesResponse() override; template - explicit PROTOBUF_CONSTEXPR ControlResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetAngularRatesResponse(::google::protobuf::internal::ConstantInitialized); - inline ControlResponse(const ControlResponse& from) - : ControlResponse(nullptr, from) {} - ControlResponse(ControlResponse&& from) noexcept - : ControlResponse() { + inline SetAngularRatesResponse(const SetAngularRatesResponse& from) + : SetAngularRatesResponse(nullptr, from) {} + SetAngularRatesResponse(SetAngularRatesResponse&& from) noexcept + : SetAngularRatesResponse() { *this = ::std::move(from); } - inline ControlResponse& operator=(const ControlResponse& from) { + inline SetAngularRatesResponse& operator=(const SetAngularRatesResponse& from) { CopyFrom(from); return *this; } - inline ControlResponse& operator=(ControlResponse&& from) noexcept { + inline SetAngularRatesResponse& operator=(SetAngularRatesResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3510,20 +3829,20 @@ class ControlResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const ControlResponse& default_instance() { + static const SetAngularRatesResponse& default_instance() { return *internal_default_instance(); } - static inline const ControlResponse* internal_default_instance() { - return reinterpret_cast( - &_ControlResponse_default_instance_); + static inline const SetAngularRatesResponse* internal_default_instance() { + return reinterpret_cast( + &_SetAngularRatesResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 11; + 3; - friend void swap(ControlResponse& a, ControlResponse& b) { + friend void swap(SetAngularRatesResponse& a, SetAngularRatesResponse& b) { a.Swap(&b); } - inline void Swap(ControlResponse* other) { + inline void Swap(SetAngularRatesResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3536,7 +3855,7 @@ class ControlResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(ControlResponse* other) { + void UnsafeArenaSwap(SetAngularRatesResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3544,14 +3863,14 @@ class ControlResponse final : // implements Message ---------------------------------------------- - ControlResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetAngularRatesResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const ControlResponse& from); + void CopyFrom(const SetAngularRatesResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const ControlResponse& from) { - ControlResponse::MergeImpl(*this, from); + void MergeFrom( const SetAngularRatesResponse& from) { + SetAngularRatesResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -3569,16 +3888,16 @@ class ControlResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(ControlResponse* other); + void InternalSwap(SetAngularRatesResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.gimbal.ControlResponse"; + return "mavsdk.rpc.gimbal.SetAngularRatesResponse"; } protected: - explicit ControlResponse(::google::protobuf::Arena* arena); - ControlResponse(::google::protobuf::Arena* arena, const ControlResponse& from); + explicit SetAngularRatesResponse(::google::protobuf::Arena* arena); + SetAngularRatesResponse(::google::protobuf::Arena* arena, const SetAngularRatesResponse& from); public: static const ClassData _class_data_; @@ -3591,24 +3910,24 @@ class ControlResponse final : // accessors ------------------------------------------------------- enum : int { - kControlStatusFieldNumber = 1, + kGimbalResultFieldNumber = 1, }; - // .mavsdk.rpc.gimbal.ControlStatus control_status = 1; - bool has_control_status() const; - void clear_control_status() ; - const ::mavsdk::rpc::gimbal::ControlStatus& control_status() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::ControlStatus* release_control_status(); - ::mavsdk::rpc::gimbal::ControlStatus* mutable_control_status(); - void set_allocated_control_status(::mavsdk::rpc::gimbal::ControlStatus* value); - void unsafe_arena_set_allocated_control_status(::mavsdk::rpc::gimbal::ControlStatus* value); - ::mavsdk::rpc::gimbal::ControlStatus* unsafe_arena_release_control_status(); + // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; + bool has_gimbal_result() const; + void clear_gimbal_result() ; + const ::mavsdk::rpc::gimbal::GimbalResult& gimbal_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::GimbalResult* release_gimbal_result(); + ::mavsdk::rpc::gimbal::GimbalResult* mutable_gimbal_result(); + void set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); + void unsafe_arena_set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); + ::mavsdk::rpc::gimbal::GimbalResult* unsafe_arena_release_gimbal_result(); private: - const ::mavsdk::rpc::gimbal::ControlStatus& _internal_control_status() const; - ::mavsdk::rpc::gimbal::ControlStatus* _internal_mutable_control_status(); + const ::mavsdk::rpc::gimbal::GimbalResult& _internal_gimbal_result() const; + ::mavsdk::rpc::gimbal::GimbalResult* _internal_mutable_gimbal_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.ControlResponse) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.SetAngularRatesResponse) private: class _Internal; @@ -3633,33 +3952,33 @@ class ControlResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::gimbal::ControlStatus* control_status_; + ::mavsdk::rpc::gimbal::GimbalResult* gimbal_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_gimbal_2fgimbal_2eproto; };// ------------------------------------------------------------------- -class Attitude final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.Attitude) */ { +class SetAnglesResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.SetAnglesResponse) */ { public: - inline Attitude() : Attitude(nullptr) {} - ~Attitude() override; + inline SetAnglesResponse() : SetAnglesResponse(nullptr) {} + ~SetAnglesResponse() override; template - explicit PROTOBUF_CONSTEXPR Attitude(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR SetAnglesResponse(::google::protobuf::internal::ConstantInitialized); - inline Attitude(const Attitude& from) - : Attitude(nullptr, from) {} - Attitude(Attitude&& from) noexcept - : Attitude() { + inline SetAnglesResponse(const SetAnglesResponse& from) + : SetAnglesResponse(nullptr, from) {} + SetAnglesResponse(SetAnglesResponse&& from) noexcept + : SetAnglesResponse() { *this = ::std::move(from); } - inline Attitude& operator=(const Attitude& from) { + inline SetAnglesResponse& operator=(const SetAnglesResponse& from) { CopyFrom(from); return *this; } - inline Attitude& operator=(Attitude&& from) noexcept { + inline SetAnglesResponse& operator=(SetAnglesResponse&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3691,20 +4010,20 @@ class Attitude final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const Attitude& default_instance() { + static const SetAnglesResponse& default_instance() { return *internal_default_instance(); } - static inline const Attitude* internal_default_instance() { - return reinterpret_cast( - &_Attitude_default_instance_); + static inline const SetAnglesResponse* internal_default_instance() { + return reinterpret_cast( + &_SetAnglesResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 15; + 1; - friend void swap(Attitude& a, Attitude& b) { + friend void swap(SetAnglesResponse& a, SetAnglesResponse& b) { a.Swap(&b); } - inline void Swap(Attitude* other) { + inline void Swap(SetAnglesResponse* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3717,7 +4036,7 @@ class Attitude final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(Attitude* other) { + void UnsafeArenaSwap(SetAnglesResponse* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3725,14 +4044,14 @@ class Attitude final : // implements Message ---------------------------------------------- - Attitude* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + SetAnglesResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const Attitude& from); + void CopyFrom(const SetAnglesResponse& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const Attitude& from) { - Attitude::MergeImpl(*this, from); + void MergeFrom( const SetAnglesResponse& from) { + SetAnglesResponse::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -3750,16 +4069,16 @@ class Attitude final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(Attitude* other); + void InternalSwap(SetAnglesResponse* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.gimbal.Attitude"; + return "mavsdk.rpc.gimbal.SetAnglesResponse"; } protected: - explicit Attitude(::google::protobuf::Arena* arena); - Attitude(::google::protobuf::Arena* arena, const Attitude& from); + explicit SetAnglesResponse(::google::protobuf::Arena* arena); + SetAnglesResponse(::google::protobuf::Arena* arena, const SetAnglesResponse& from); public: static const ClassData _class_data_; @@ -3772,105 +4091,211 @@ class Attitude final : // accessors ------------------------------------------------------- enum : int { - kEulerAngleForwardFieldNumber = 1, - kQuaternionForwardFieldNumber = 2, - kEulerAngleNorthFieldNumber = 3, - kQuaternionNorthFieldNumber = 4, - kAngularVelocityFieldNumber = 5, - kTimestampUsFieldNumber = 6, + kGimbalResultFieldNumber = 1, }; - // .mavsdk.rpc.gimbal.EulerAngle euler_angle_forward = 1; - bool has_euler_angle_forward() const; - void clear_euler_angle_forward() ; - const ::mavsdk::rpc::gimbal::EulerAngle& euler_angle_forward() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::EulerAngle* release_euler_angle_forward(); - ::mavsdk::rpc::gimbal::EulerAngle* mutable_euler_angle_forward(); - void set_allocated_euler_angle_forward(::mavsdk::rpc::gimbal::EulerAngle* value); - void unsafe_arena_set_allocated_euler_angle_forward(::mavsdk::rpc::gimbal::EulerAngle* value); - ::mavsdk::rpc::gimbal::EulerAngle* unsafe_arena_release_euler_angle_forward(); + // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; + bool has_gimbal_result() const; + void clear_gimbal_result() ; + const ::mavsdk::rpc::gimbal::GimbalResult& gimbal_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::GimbalResult* release_gimbal_result(); + ::mavsdk::rpc::gimbal::GimbalResult* mutable_gimbal_result(); + void set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); + void unsafe_arena_set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); + ::mavsdk::rpc::gimbal::GimbalResult* unsafe_arena_release_gimbal_result(); private: - const ::mavsdk::rpc::gimbal::EulerAngle& _internal_euler_angle_forward() const; - ::mavsdk::rpc::gimbal::EulerAngle* _internal_mutable_euler_angle_forward(); + const ::mavsdk::rpc::gimbal::GimbalResult& _internal_gimbal_result() const; + ::mavsdk::rpc::gimbal::GimbalResult* _internal_mutable_gimbal_result(); public: - // .mavsdk.rpc.gimbal.Quaternion quaternion_forward = 2; - bool has_quaternion_forward() const; - void clear_quaternion_forward() ; - const ::mavsdk::rpc::gimbal::Quaternion& quaternion_forward() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::Quaternion* release_quaternion_forward(); - ::mavsdk::rpc::gimbal::Quaternion* mutable_quaternion_forward(); - void set_allocated_quaternion_forward(::mavsdk::rpc::gimbal::Quaternion* value); - void unsafe_arena_set_allocated_quaternion_forward(::mavsdk::rpc::gimbal::Quaternion* value); - ::mavsdk::rpc::gimbal::Quaternion* unsafe_arena_release_quaternion_forward(); - - private: - const ::mavsdk::rpc::gimbal::Quaternion& _internal_quaternion_forward() const; - ::mavsdk::rpc::gimbal::Quaternion* _internal_mutable_quaternion_forward(); + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.SetAnglesResponse) + private: + class _Internal; - public: - // .mavsdk.rpc.gimbal.EulerAngle euler_angle_north = 3; - bool has_euler_angle_north() const; - void clear_euler_angle_north() ; - const ::mavsdk::rpc::gimbal::EulerAngle& euler_angle_north() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::EulerAngle* release_euler_angle_north(); - ::mavsdk::rpc::gimbal::EulerAngle* mutable_euler_angle_north(); - void set_allocated_euler_angle_north(::mavsdk::rpc::gimbal::EulerAngle* value); - void unsafe_arena_set_allocated_euler_angle_north(::mavsdk::rpc::gimbal::EulerAngle* value); - ::mavsdk::rpc::gimbal::EulerAngle* unsafe_arena_release_euler_angle_north(); + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 1, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { - private: - const ::mavsdk::rpc::gimbal::EulerAngle& _internal_euler_angle_north() const; - ::mavsdk::rpc::gimbal::EulerAngle* _internal_mutable_euler_angle_north(); + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::gimbal::GimbalResult* gimbal_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_gimbal_2fgimbal_2eproto; +};// ------------------------------------------------------------------- - public: - // .mavsdk.rpc.gimbal.Quaternion quaternion_north = 4; - bool has_quaternion_north() const; - void clear_quaternion_north() ; - const ::mavsdk::rpc::gimbal::Quaternion& quaternion_north() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::Quaternion* release_quaternion_north(); - ::mavsdk::rpc::gimbal::Quaternion* mutable_quaternion_north(); - void set_allocated_quaternion_north(::mavsdk::rpc::gimbal::Quaternion* value); - void unsafe_arena_set_allocated_quaternion_north(::mavsdk::rpc::gimbal::Quaternion* value); - ::mavsdk::rpc::gimbal::Quaternion* unsafe_arena_release_quaternion_north(); +class ReleaseControlResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.ReleaseControlResponse) */ { + public: + inline ReleaseControlResponse() : ReleaseControlResponse(nullptr) {} + ~ReleaseControlResponse() override; + template + explicit PROTOBUF_CONSTEXPR ReleaseControlResponse(::google::protobuf::internal::ConstantInitialized); - private: - const ::mavsdk::rpc::gimbal::Quaternion& _internal_quaternion_north() const; - ::mavsdk::rpc::gimbal::Quaternion* _internal_mutable_quaternion_north(); + inline ReleaseControlResponse(const ReleaseControlResponse& from) + : ReleaseControlResponse(nullptr, from) {} + ReleaseControlResponse(ReleaseControlResponse&& from) noexcept + : ReleaseControlResponse() { + *this = ::std::move(from); + } + + inline ReleaseControlResponse& operator=(const ReleaseControlResponse& from) { + CopyFrom(from); + return *this; + } + inline ReleaseControlResponse& operator=(ReleaseControlResponse&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const ReleaseControlResponse& default_instance() { + return *internal_default_instance(); + } + static inline const ReleaseControlResponse* internal_default_instance() { + return reinterpret_cast( + &_ReleaseControlResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 9; + + friend void swap(ReleaseControlResponse& a, ReleaseControlResponse& b) { + a.Swap(&b); + } + inline void Swap(ReleaseControlResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(ReleaseControlResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + ReleaseControlResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const ReleaseControlResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const ReleaseControlResponse& from) { + ReleaseControlResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); public: - // .mavsdk.rpc.gimbal.AngularVelocityBody angular_velocity = 5; - bool has_angular_velocity() const; - void clear_angular_velocity() ; - const ::mavsdk::rpc::gimbal::AngularVelocityBody& angular_velocity() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::AngularVelocityBody* release_angular_velocity(); - ::mavsdk::rpc::gimbal::AngularVelocityBody* mutable_angular_velocity(); - void set_allocated_angular_velocity(::mavsdk::rpc::gimbal::AngularVelocityBody* value); - void unsafe_arena_set_allocated_angular_velocity(::mavsdk::rpc::gimbal::AngularVelocityBody* value); - ::mavsdk::rpc::gimbal::AngularVelocityBody* unsafe_arena_release_angular_velocity(); + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } private: - const ::mavsdk::rpc::gimbal::AngularVelocityBody& _internal_angular_velocity() const; - ::mavsdk::rpc::gimbal::AngularVelocityBody* _internal_mutable_angular_velocity(); + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(ReleaseControlResponse* other); + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.gimbal.ReleaseControlResponse"; + } + protected: + explicit ReleaseControlResponse(::google::protobuf::Arena* arena); + ReleaseControlResponse(::google::protobuf::Arena* arena, const ReleaseControlResponse& from); public: - // uint64 timestamp_us = 6; - void clear_timestamp_us() ; - ::uint64_t timestamp_us() const; - void set_timestamp_us(::uint64_t value); + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kGimbalResultFieldNumber = 1, + }; + // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; + bool has_gimbal_result() const; + void clear_gimbal_result() ; + const ::mavsdk::rpc::gimbal::GimbalResult& gimbal_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::GimbalResult* release_gimbal_result(); + ::mavsdk::rpc::gimbal::GimbalResult* mutable_gimbal_result(); + void set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); + void unsafe_arena_set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); + ::mavsdk::rpc::gimbal::GimbalResult* unsafe_arena_release_gimbal_result(); private: - ::uint64_t _internal_timestamp_us() const; - void _internal_set_timestamp_us(::uint64_t value); + const ::mavsdk::rpc::gimbal::GimbalResult& _internal_gimbal_result() const; + ::mavsdk::rpc::gimbal::GimbalResult* _internal_mutable_gimbal_result(); public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.Attitude) + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.ReleaseControlResponse) private: class _Internal; friend class ::google::protobuf::internal::TcParser; static const ::google::protobuf::internal::TcParseTable< - 3, 6, 5, + 0, 1, 1, 0, 2> _table_; friend class ::google::protobuf::MessageLite; @@ -3889,38 +4314,33 @@ class Attitude final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::gimbal::EulerAngle* euler_angle_forward_; - ::mavsdk::rpc::gimbal::Quaternion* quaternion_forward_; - ::mavsdk::rpc::gimbal::EulerAngle* euler_angle_north_; - ::mavsdk::rpc::gimbal::Quaternion* quaternion_north_; - ::mavsdk::rpc::gimbal::AngularVelocityBody* angular_velocity_; - ::uint64_t timestamp_us_; + ::mavsdk::rpc::gimbal::GimbalResult* gimbal_result_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_gimbal_2fgimbal_2eproto; };// ------------------------------------------------------------------- -class AttitudeResponse final : - public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.AttitudeResponse) */ { +class GimbalList final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.GimbalList) */ { public: - inline AttitudeResponse() : AttitudeResponse(nullptr) {} - ~AttitudeResponse() override; + inline GimbalList() : GimbalList(nullptr) {} + ~GimbalList() override; template - explicit PROTOBUF_CONSTEXPR AttitudeResponse(::google::protobuf::internal::ConstantInitialized); + explicit PROTOBUF_CONSTEXPR GimbalList(::google::protobuf::internal::ConstantInitialized); - inline AttitudeResponse(const AttitudeResponse& from) - : AttitudeResponse(nullptr, from) {} - AttitudeResponse(AttitudeResponse&& from) noexcept - : AttitudeResponse() { + inline GimbalList(const GimbalList& from) + : GimbalList(nullptr, from) {} + GimbalList(GimbalList&& from) noexcept + : GimbalList() { *this = ::std::move(from); } - inline AttitudeResponse& operator=(const AttitudeResponse& from) { + inline GimbalList& operator=(const GimbalList& from) { CopyFrom(from); return *this; } - inline AttitudeResponse& operator=(AttitudeResponse&& from) noexcept { + inline GimbalList& operator=(GimbalList&& from) noexcept { if (this == &from) return *this; if (GetArena() == from.GetArena() #ifdef PROTOBUF_FORCE_COPY_IN_MOVE @@ -3952,20 +4372,20 @@ class AttitudeResponse final : static const ::google::protobuf::Reflection* GetReflection() { return default_instance().GetMetadata().reflection; } - static const AttitudeResponse& default_instance() { + static const GimbalList& default_instance() { return *internal_default_instance(); } - static inline const AttitudeResponse* internal_default_instance() { - return reinterpret_cast( - &_AttitudeResponse_default_instance_); + static inline const GimbalList* internal_default_instance() { + return reinterpret_cast( + &_GimbalList_default_instance_); } static constexpr int kIndexInFileMessages = - 17; + 25; - friend void swap(AttitudeResponse& a, AttitudeResponse& b) { + friend void swap(GimbalList& a, GimbalList& b) { a.Swap(&b); } - inline void Swap(AttitudeResponse* other) { + inline void Swap(GimbalList* other) { if (other == this) return; #ifdef PROTOBUF_FORCE_COPY_IN_SWAP if (GetArena() != nullptr && @@ -3978,7 +4398,7 @@ class AttitudeResponse final : ::google::protobuf::internal::GenericSwap(this, other); } } - void UnsafeArenaSwap(AttitudeResponse* other) { + void UnsafeArenaSwap(GimbalList* other) { if (other == this) return; ABSL_DCHECK(GetArena() == other->GetArena()); InternalSwap(other); @@ -3986,14 +4406,14 @@ class AttitudeResponse final : // implements Message ---------------------------------------------- - AttitudeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { - return CreateMaybeMessage(arena); + GimbalList* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); } using ::google::protobuf::Message::CopyFrom; - void CopyFrom(const AttitudeResponse& from); + void CopyFrom(const GimbalList& from); using ::google::protobuf::Message::MergeFrom; - void MergeFrom( const AttitudeResponse& from) { - AttitudeResponse::MergeImpl(*this, from); + void MergeFrom( const GimbalList& from) { + GimbalList::MergeImpl(*this, from); } private: static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); @@ -4011,16 +4431,16 @@ class AttitudeResponse final : ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; void SharedCtor(::google::protobuf::Arena* arena); void SharedDtor(); - void InternalSwap(AttitudeResponse* other); + void InternalSwap(GimbalList* other); private: friend class ::google::protobuf::internal::AnyMetadata; static ::absl::string_view FullMessageName() { - return "mavsdk.rpc.gimbal.AttitudeResponse"; + return "mavsdk.rpc.gimbal.GimbalList"; } protected: - explicit AttitudeResponse(::google::protobuf::Arena* arena); - AttitudeResponse(::google::protobuf::Arena* arena, const AttitudeResponse& from); + explicit GimbalList(::google::protobuf::Arena* arena); + GimbalList(::google::protobuf::Arena* arena, const GimbalList& from); public: static const ClassData _class_data_; @@ -4033,24 +4453,27 @@ class AttitudeResponse final : // accessors ------------------------------------------------------- enum : int { - kAttitudeFieldNumber = 1, + kGimbalsFieldNumber = 1, }; - // .mavsdk.rpc.gimbal.Attitude attitude = 1; - bool has_attitude() const; - void clear_attitude() ; - const ::mavsdk::rpc::gimbal::Attitude& attitude() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::Attitude* release_attitude(); - ::mavsdk::rpc::gimbal::Attitude* mutable_attitude(); - void set_allocated_attitude(::mavsdk::rpc::gimbal::Attitude* value); - void unsafe_arena_set_allocated_attitude(::mavsdk::rpc::gimbal::Attitude* value); - ::mavsdk::rpc::gimbal::Attitude* unsafe_arena_release_attitude(); - + // repeated .mavsdk.rpc.gimbal.GimbalItem gimbals = 1; + int gimbals_size() const; private: - const ::mavsdk::rpc::gimbal::Attitude& _internal_attitude() const; - ::mavsdk::rpc::gimbal::Attitude* _internal_mutable_attitude(); + int _internal_gimbals_size() const; public: - // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.AttitudeResponse) + void clear_gimbals() ; + ::mavsdk::rpc::gimbal::GimbalItem* mutable_gimbals(int index); + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::gimbal::GimbalItem >* + mutable_gimbals(); + private: + const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::gimbal::GimbalItem>& _internal_gimbals() const; + ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::gimbal::GimbalItem>* _internal_mutable_gimbals(); + public: + const ::mavsdk::rpc::gimbal::GimbalItem& gimbals(int index) const; + ::mavsdk::rpc::gimbal::GimbalItem* add_gimbals(); + const ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::gimbal::GimbalItem >& + gimbals() const; + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.GimbalList) private: class _Internal; @@ -4073,33 +4496,1267 @@ class AttitudeResponse final : ::google::protobuf::Arena* arena); inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, const Impl_& from); - ::google::protobuf::internal::HasBits<1> _has_bits_; + ::google::protobuf::RepeatedPtrField< ::mavsdk::rpc::gimbal::GimbalItem > gimbals_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::gimbal::Attitude* attitude_; PROTOBUF_TSAN_DECLARE_MEMBER }; union { Impl_ _impl_; }; friend struct ::TableStruct_gimbal_2fgimbal_2eproto; -}; - -// =================================================================== - - - - -// =================================================================== - +};// ------------------------------------------------------------------- -#ifdef __GNUC__ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wstrict-aliasing" -#endif // __GNUC__ -// ------------------------------------------------------------------- +class GetControlStatusResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.GetControlStatusResponse) */ { + public: + inline GetControlStatusResponse() : GetControlStatusResponse(nullptr) {} + ~GetControlStatusResponse() override; + template + explicit PROTOBUF_CONSTEXPR GetControlStatusResponse(::google::protobuf::internal::ConstantInitialized); -// SetAnglesRequest + inline GetControlStatusResponse(const GetControlStatusResponse& from) + : GetControlStatusResponse(nullptr, from) {} + GetControlStatusResponse(GetControlStatusResponse&& from) noexcept + : GetControlStatusResponse() { + *this = ::std::move(from); + } -// float roll_deg = 1; -inline void SetAnglesRequest::clear_roll_deg() { + inline GetControlStatusResponse& operator=(const GetControlStatusResponse& from) { + CopyFrom(from); + return *this; + } + inline GetControlStatusResponse& operator=(GetControlStatusResponse&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const GetControlStatusResponse& default_instance() { + return *internal_default_instance(); + } + static inline const GetControlStatusResponse* internal_default_instance() { + return reinterpret_cast( + &_GetControlStatusResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 13; + + friend void swap(GetControlStatusResponse& a, GetControlStatusResponse& b) { + a.Swap(&b); + } + inline void Swap(GetControlStatusResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(GetControlStatusResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + GetControlStatusResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const GetControlStatusResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const GetControlStatusResponse& from) { + GetControlStatusResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(GetControlStatusResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.gimbal.GetControlStatusResponse"; + } + protected: + explicit GetControlStatusResponse(::google::protobuf::Arena* arena); + GetControlStatusResponse(::google::protobuf::Arena* arena, const GetControlStatusResponse& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kGimbalResultFieldNumber = 1, + kControlStatusFieldNumber = 2, + }; + // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; + bool has_gimbal_result() const; + void clear_gimbal_result() ; + const ::mavsdk::rpc::gimbal::GimbalResult& gimbal_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::GimbalResult* release_gimbal_result(); + ::mavsdk::rpc::gimbal::GimbalResult* mutable_gimbal_result(); + void set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); + void unsafe_arena_set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); + ::mavsdk::rpc::gimbal::GimbalResult* unsafe_arena_release_gimbal_result(); + + private: + const ::mavsdk::rpc::gimbal::GimbalResult& _internal_gimbal_result() const; + ::mavsdk::rpc::gimbal::GimbalResult* _internal_mutable_gimbal_result(); + + public: + // .mavsdk.rpc.gimbal.ControlStatus control_status = 2; + bool has_control_status() const; + void clear_control_status() ; + const ::mavsdk::rpc::gimbal::ControlStatus& control_status() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::ControlStatus* release_control_status(); + ::mavsdk::rpc::gimbal::ControlStatus* mutable_control_status(); + void set_allocated_control_status(::mavsdk::rpc::gimbal::ControlStatus* value); + void unsafe_arena_set_allocated_control_status(::mavsdk::rpc::gimbal::ControlStatus* value); + ::mavsdk::rpc::gimbal::ControlStatus* unsafe_arena_release_control_status(); + + private: + const ::mavsdk::rpc::gimbal::ControlStatus& _internal_control_status() const; + ::mavsdk::rpc::gimbal::ControlStatus* _internal_mutable_control_status(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.GetControlStatusResponse) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 1, 2, 2, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::gimbal::GimbalResult* gimbal_result_; + ::mavsdk::rpc::gimbal::ControlStatus* control_status_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_gimbal_2fgimbal_2eproto; +};// ------------------------------------------------------------------- + +class ControlStatusResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.ControlStatusResponse) */ { + public: + inline ControlStatusResponse() : ControlStatusResponse(nullptr) {} + ~ControlStatusResponse() override; + template + explicit PROTOBUF_CONSTEXPR ControlStatusResponse(::google::protobuf::internal::ConstantInitialized); + + inline ControlStatusResponse(const ControlStatusResponse& from) + : ControlStatusResponse(nullptr, from) {} + ControlStatusResponse(ControlStatusResponse&& from) noexcept + : ControlStatusResponse() { + *this = ::std::move(from); + } + + inline ControlStatusResponse& operator=(const ControlStatusResponse& from) { + CopyFrom(from); + return *this; + } + inline ControlStatusResponse& operator=(ControlStatusResponse&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const ControlStatusResponse& default_instance() { + return *internal_default_instance(); + } + static inline const ControlStatusResponse* internal_default_instance() { + return reinterpret_cast( + &_ControlStatusResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 11; + + friend void swap(ControlStatusResponse& a, ControlStatusResponse& b) { + a.Swap(&b); + } + inline void Swap(ControlStatusResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(ControlStatusResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + ControlStatusResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const ControlStatusResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const ControlStatusResponse& from) { + ControlStatusResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(ControlStatusResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.gimbal.ControlStatusResponse"; + } + protected: + explicit ControlStatusResponse(::google::protobuf::Arena* arena); + ControlStatusResponse(::google::protobuf::Arena* arena, const ControlStatusResponse& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kControlStatusFieldNumber = 1, + }; + // .mavsdk.rpc.gimbal.ControlStatus control_status = 1; + bool has_control_status() const; + void clear_control_status() ; + const ::mavsdk::rpc::gimbal::ControlStatus& control_status() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::ControlStatus* release_control_status(); + ::mavsdk::rpc::gimbal::ControlStatus* mutable_control_status(); + void set_allocated_control_status(::mavsdk::rpc::gimbal::ControlStatus* value); + void unsafe_arena_set_allocated_control_status(::mavsdk::rpc::gimbal::ControlStatus* value); + ::mavsdk::rpc::gimbal::ControlStatus* unsafe_arena_release_control_status(); + + private: + const ::mavsdk::rpc::gimbal::ControlStatus& _internal_control_status() const; + ::mavsdk::rpc::gimbal::ControlStatus* _internal_mutable_control_status(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.ControlStatusResponse) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 1, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::gimbal::ControlStatus* control_status_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_gimbal_2fgimbal_2eproto; +};// ------------------------------------------------------------------- + +class Attitude final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.Attitude) */ { + public: + inline Attitude() : Attitude(nullptr) {} + ~Attitude() override; + template + explicit PROTOBUF_CONSTEXPR Attitude(::google::protobuf::internal::ConstantInitialized); + + inline Attitude(const Attitude& from) + : Attitude(nullptr, from) {} + Attitude(Attitude&& from) noexcept + : Attitude() { + *this = ::std::move(from); + } + + inline Attitude& operator=(const Attitude& from) { + CopyFrom(from); + return *this; + } + inline Attitude& operator=(Attitude&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const Attitude& default_instance() { + return *internal_default_instance(); + } + static inline const Attitude* internal_default_instance() { + return reinterpret_cast( + &_Attitude_default_instance_); + } + static constexpr int kIndexInFileMessages = + 17; + + friend void swap(Attitude& a, Attitude& b) { + a.Swap(&b); + } + inline void Swap(Attitude* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(Attitude* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + Attitude* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const Attitude& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const Attitude& from) { + Attitude::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(Attitude* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.gimbal.Attitude"; + } + protected: + explicit Attitude(::google::protobuf::Arena* arena); + Attitude(::google::protobuf::Arena* arena, const Attitude& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kEulerAngleForwardFieldNumber = 2, + kQuaternionForwardFieldNumber = 3, + kEulerAngleNorthFieldNumber = 4, + kQuaternionNorthFieldNumber = 5, + kAngularVelocityFieldNumber = 6, + kTimestampUsFieldNumber = 7, + kGimbalIdFieldNumber = 1, + }; + // .mavsdk.rpc.gimbal.EulerAngle euler_angle_forward = 2; + bool has_euler_angle_forward() const; + void clear_euler_angle_forward() ; + const ::mavsdk::rpc::gimbal::EulerAngle& euler_angle_forward() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::EulerAngle* release_euler_angle_forward(); + ::mavsdk::rpc::gimbal::EulerAngle* mutable_euler_angle_forward(); + void set_allocated_euler_angle_forward(::mavsdk::rpc::gimbal::EulerAngle* value); + void unsafe_arena_set_allocated_euler_angle_forward(::mavsdk::rpc::gimbal::EulerAngle* value); + ::mavsdk::rpc::gimbal::EulerAngle* unsafe_arena_release_euler_angle_forward(); + + private: + const ::mavsdk::rpc::gimbal::EulerAngle& _internal_euler_angle_forward() const; + ::mavsdk::rpc::gimbal::EulerAngle* _internal_mutable_euler_angle_forward(); + + public: + // .mavsdk.rpc.gimbal.Quaternion quaternion_forward = 3; + bool has_quaternion_forward() const; + void clear_quaternion_forward() ; + const ::mavsdk::rpc::gimbal::Quaternion& quaternion_forward() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::Quaternion* release_quaternion_forward(); + ::mavsdk::rpc::gimbal::Quaternion* mutable_quaternion_forward(); + void set_allocated_quaternion_forward(::mavsdk::rpc::gimbal::Quaternion* value); + void unsafe_arena_set_allocated_quaternion_forward(::mavsdk::rpc::gimbal::Quaternion* value); + ::mavsdk::rpc::gimbal::Quaternion* unsafe_arena_release_quaternion_forward(); + + private: + const ::mavsdk::rpc::gimbal::Quaternion& _internal_quaternion_forward() const; + ::mavsdk::rpc::gimbal::Quaternion* _internal_mutable_quaternion_forward(); + + public: + // .mavsdk.rpc.gimbal.EulerAngle euler_angle_north = 4; + bool has_euler_angle_north() const; + void clear_euler_angle_north() ; + const ::mavsdk::rpc::gimbal::EulerAngle& euler_angle_north() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::EulerAngle* release_euler_angle_north(); + ::mavsdk::rpc::gimbal::EulerAngle* mutable_euler_angle_north(); + void set_allocated_euler_angle_north(::mavsdk::rpc::gimbal::EulerAngle* value); + void unsafe_arena_set_allocated_euler_angle_north(::mavsdk::rpc::gimbal::EulerAngle* value); + ::mavsdk::rpc::gimbal::EulerAngle* unsafe_arena_release_euler_angle_north(); + + private: + const ::mavsdk::rpc::gimbal::EulerAngle& _internal_euler_angle_north() const; + ::mavsdk::rpc::gimbal::EulerAngle* _internal_mutable_euler_angle_north(); + + public: + // .mavsdk.rpc.gimbal.Quaternion quaternion_north = 5; + bool has_quaternion_north() const; + void clear_quaternion_north() ; + const ::mavsdk::rpc::gimbal::Quaternion& quaternion_north() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::Quaternion* release_quaternion_north(); + ::mavsdk::rpc::gimbal::Quaternion* mutable_quaternion_north(); + void set_allocated_quaternion_north(::mavsdk::rpc::gimbal::Quaternion* value); + void unsafe_arena_set_allocated_quaternion_north(::mavsdk::rpc::gimbal::Quaternion* value); + ::mavsdk::rpc::gimbal::Quaternion* unsafe_arena_release_quaternion_north(); + + private: + const ::mavsdk::rpc::gimbal::Quaternion& _internal_quaternion_north() const; + ::mavsdk::rpc::gimbal::Quaternion* _internal_mutable_quaternion_north(); + + public: + // .mavsdk.rpc.gimbal.AngularVelocityBody angular_velocity = 6; + bool has_angular_velocity() const; + void clear_angular_velocity() ; + const ::mavsdk::rpc::gimbal::AngularVelocityBody& angular_velocity() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::AngularVelocityBody* release_angular_velocity(); + ::mavsdk::rpc::gimbal::AngularVelocityBody* mutable_angular_velocity(); + void set_allocated_angular_velocity(::mavsdk::rpc::gimbal::AngularVelocityBody* value); + void unsafe_arena_set_allocated_angular_velocity(::mavsdk::rpc::gimbal::AngularVelocityBody* value); + ::mavsdk::rpc::gimbal::AngularVelocityBody* unsafe_arena_release_angular_velocity(); + + private: + const ::mavsdk::rpc::gimbal::AngularVelocityBody& _internal_angular_velocity() const; + ::mavsdk::rpc::gimbal::AngularVelocityBody* _internal_mutable_angular_velocity(); + + public: + // uint64 timestamp_us = 7; + void clear_timestamp_us() ; + ::uint64_t timestamp_us() const; + void set_timestamp_us(::uint64_t value); + + private: + ::uint64_t _internal_timestamp_us() const; + void _internal_set_timestamp_us(::uint64_t value); + + public: + // int32 gimbal_id = 1; + void clear_gimbal_id() ; + ::int32_t gimbal_id() const; + void set_gimbal_id(::int32_t value); + + private: + ::int32_t _internal_gimbal_id() const; + void _internal_set_gimbal_id(::int32_t value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.Attitude) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 3, 7, 5, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::gimbal::EulerAngle* euler_angle_forward_; + ::mavsdk::rpc::gimbal::Quaternion* quaternion_forward_; + ::mavsdk::rpc::gimbal::EulerAngle* euler_angle_north_; + ::mavsdk::rpc::gimbal::Quaternion* quaternion_north_; + ::mavsdk::rpc::gimbal::AngularVelocityBody* angular_velocity_; + ::uint64_t timestamp_us_; + ::int32_t gimbal_id_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_gimbal_2fgimbal_2eproto; +};// ------------------------------------------------------------------- + +class GimbalListResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.GimbalListResponse) */ { + public: + inline GimbalListResponse() : GimbalListResponse(nullptr) {} + ~GimbalListResponse() override; + template + explicit PROTOBUF_CONSTEXPR GimbalListResponse(::google::protobuf::internal::ConstantInitialized); + + inline GimbalListResponse(const GimbalListResponse& from) + : GimbalListResponse(nullptr, from) {} + GimbalListResponse(GimbalListResponse&& from) noexcept + : GimbalListResponse() { + *this = ::std::move(from); + } + + inline GimbalListResponse& operator=(const GimbalListResponse& from) { + CopyFrom(from); + return *this; + } + inline GimbalListResponse& operator=(GimbalListResponse&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const GimbalListResponse& default_instance() { + return *internal_default_instance(); + } + static inline const GimbalListResponse* internal_default_instance() { + return reinterpret_cast( + &_GimbalListResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 23; + + friend void swap(GimbalListResponse& a, GimbalListResponse& b) { + a.Swap(&b); + } + inline void Swap(GimbalListResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(GimbalListResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + GimbalListResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const GimbalListResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const GimbalListResponse& from) { + GimbalListResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(GimbalListResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.gimbal.GimbalListResponse"; + } + protected: + explicit GimbalListResponse(::google::protobuf::Arena* arena); + GimbalListResponse(::google::protobuf::Arena* arena, const GimbalListResponse& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kGimbalListFieldNumber = 1, + }; + // .mavsdk.rpc.gimbal.GimbalList gimbal_list = 1; + bool has_gimbal_list() const; + void clear_gimbal_list() ; + const ::mavsdk::rpc::gimbal::GimbalList& gimbal_list() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::GimbalList* release_gimbal_list(); + ::mavsdk::rpc::gimbal::GimbalList* mutable_gimbal_list(); + void set_allocated_gimbal_list(::mavsdk::rpc::gimbal::GimbalList* value); + void unsafe_arena_set_allocated_gimbal_list(::mavsdk::rpc::gimbal::GimbalList* value); + ::mavsdk::rpc::gimbal::GimbalList* unsafe_arena_release_gimbal_list(); + + private: + const ::mavsdk::rpc::gimbal::GimbalList& _internal_gimbal_list() const; + ::mavsdk::rpc::gimbal::GimbalList* _internal_mutable_gimbal_list(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.GimbalListResponse) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 1, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::gimbal::GimbalList* gimbal_list_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_gimbal_2fgimbal_2eproto; +};// ------------------------------------------------------------------- + +class GetAttitudeResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.GetAttitudeResponse) */ { + public: + inline GetAttitudeResponse() : GetAttitudeResponse(nullptr) {} + ~GetAttitudeResponse() override; + template + explicit PROTOBUF_CONSTEXPR GetAttitudeResponse(::google::protobuf::internal::ConstantInitialized); + + inline GetAttitudeResponse(const GetAttitudeResponse& from) + : GetAttitudeResponse(nullptr, from) {} + GetAttitudeResponse(GetAttitudeResponse&& from) noexcept + : GetAttitudeResponse() { + *this = ::std::move(from); + } + + inline GetAttitudeResponse& operator=(const GetAttitudeResponse& from) { + CopyFrom(from); + return *this; + } + inline GetAttitudeResponse& operator=(GetAttitudeResponse&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const GetAttitudeResponse& default_instance() { + return *internal_default_instance(); + } + static inline const GetAttitudeResponse* internal_default_instance() { + return reinterpret_cast( + &_GetAttitudeResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 21; + + friend void swap(GetAttitudeResponse& a, GetAttitudeResponse& b) { + a.Swap(&b); + } + inline void Swap(GetAttitudeResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(GetAttitudeResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + GetAttitudeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const GetAttitudeResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const GetAttitudeResponse& from) { + GetAttitudeResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(GetAttitudeResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.gimbal.GetAttitudeResponse"; + } + protected: + explicit GetAttitudeResponse(::google::protobuf::Arena* arena); + GetAttitudeResponse(::google::protobuf::Arena* arena, const GetAttitudeResponse& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kGimbalResultFieldNumber = 1, + kAttitudeFieldNumber = 2, + }; + // .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; + bool has_gimbal_result() const; + void clear_gimbal_result() ; + const ::mavsdk::rpc::gimbal::GimbalResult& gimbal_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::GimbalResult* release_gimbal_result(); + ::mavsdk::rpc::gimbal::GimbalResult* mutable_gimbal_result(); + void set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); + void unsafe_arena_set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value); + ::mavsdk::rpc::gimbal::GimbalResult* unsafe_arena_release_gimbal_result(); + + private: + const ::mavsdk::rpc::gimbal::GimbalResult& _internal_gimbal_result() const; + ::mavsdk::rpc::gimbal::GimbalResult* _internal_mutable_gimbal_result(); + + public: + // .mavsdk.rpc.gimbal.Attitude attitude = 2; + bool has_attitude() const; + void clear_attitude() ; + const ::mavsdk::rpc::gimbal::Attitude& attitude() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::Attitude* release_attitude(); + ::mavsdk::rpc::gimbal::Attitude* mutable_attitude(); + void set_allocated_attitude(::mavsdk::rpc::gimbal::Attitude* value); + void unsafe_arena_set_allocated_attitude(::mavsdk::rpc::gimbal::Attitude* value); + ::mavsdk::rpc::gimbal::Attitude* unsafe_arena_release_attitude(); + + private: + const ::mavsdk::rpc::gimbal::Attitude& _internal_attitude() const; + ::mavsdk::rpc::gimbal::Attitude* _internal_mutable_attitude(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.GetAttitudeResponse) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 1, 2, 2, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::gimbal::GimbalResult* gimbal_result_; + ::mavsdk::rpc::gimbal::Attitude* attitude_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_gimbal_2fgimbal_2eproto; +};// ------------------------------------------------------------------- + +class AttitudeResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.gimbal.AttitudeResponse) */ { + public: + inline AttitudeResponse() : AttitudeResponse(nullptr) {} + ~AttitudeResponse() override; + template + explicit PROTOBUF_CONSTEXPR AttitudeResponse(::google::protobuf::internal::ConstantInitialized); + + inline AttitudeResponse(const AttitudeResponse& from) + : AttitudeResponse(nullptr, from) {} + AttitudeResponse(AttitudeResponse&& from) noexcept + : AttitudeResponse() { + *this = ::std::move(from); + } + + inline AttitudeResponse& operator=(const AttitudeResponse& from) { + CopyFrom(from); + return *this; + } + inline AttitudeResponse& operator=(AttitudeResponse&& from) noexcept { + if (this == &from) return *this; + if (GetArena() == from.GetArena() + #ifdef PROTOBUF_FORCE_COPY_IN_MOVE + && GetArena() != nullptr + #endif // !PROTOBUF_FORCE_COPY_IN_MOVE + ) { + InternalSwap(&from); + } else { + CopyFrom(from); + } + return *this; + } + + inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.unknown_fields<::google::protobuf::UnknownFieldSet>(::google::protobuf::UnknownFieldSet::default_instance); + } + inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + return _internal_metadata_.mutable_unknown_fields<::google::protobuf::UnknownFieldSet>(); + } + + static const ::google::protobuf::Descriptor* descriptor() { + return GetDescriptor(); + } + static const ::google::protobuf::Descriptor* GetDescriptor() { + return default_instance().GetMetadata().descriptor; + } + static const ::google::protobuf::Reflection* GetReflection() { + return default_instance().GetMetadata().reflection; + } + static const AttitudeResponse& default_instance() { + return *internal_default_instance(); + } + static inline const AttitudeResponse* internal_default_instance() { + return reinterpret_cast( + &_AttitudeResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 19; + + friend void swap(AttitudeResponse& a, AttitudeResponse& b) { + a.Swap(&b); + } + inline void Swap(AttitudeResponse* other) { + if (other == this) return; + #ifdef PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() != nullptr && + GetArena() == other->GetArena()) { + #else // PROTOBUF_FORCE_COPY_IN_SWAP + if (GetArena() == other->GetArena()) { + #endif // !PROTOBUF_FORCE_COPY_IN_SWAP + InternalSwap(other); + } else { + ::google::protobuf::internal::GenericSwap(this, other); + } + } + void UnsafeArenaSwap(AttitudeResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + AttitudeResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const AttitudeResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const AttitudeResponse& from) { + AttitudeResponse::MergeImpl(*this, from); + } + private: + static void MergeImpl(::google::protobuf::Message& to_msg, const ::google::protobuf::Message& from_msg); + public: + PROTOBUF_ATTRIBUTE_REINITIALIZES void Clear() final; + bool IsInitialized() const final; + + ::size_t ByteSizeLong() const final; + const char* _InternalParse(const char* ptr, ::google::protobuf::internal::ParseContext* ctx) final; + ::uint8_t* _InternalSerialize( + ::uint8_t* target, ::google::protobuf::io::EpsCopyOutputStream* stream) const final; + int GetCachedSize() const { return _impl_._cached_size_.Get(); } + + private: + ::google::protobuf::internal::CachedSize* AccessCachedSize() const final; + void SharedCtor(::google::protobuf::Arena* arena); + void SharedDtor(); + void InternalSwap(AttitudeResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.gimbal.AttitudeResponse"; + } + protected: + explicit AttitudeResponse(::google::protobuf::Arena* arena); + AttitudeResponse(::google::protobuf::Arena* arena, const AttitudeResponse& from); + public: + + static const ClassData _class_data_; + const ::google::protobuf::Message::ClassData*GetClassData() const final; + + ::google::protobuf::Metadata GetMetadata() const final; + + // nested types ---------------------------------------------------- + + // accessors ------------------------------------------------------- + + enum : int { + kAttitudeFieldNumber = 1, + }; + // .mavsdk.rpc.gimbal.Attitude attitude = 1; + bool has_attitude() const; + void clear_attitude() ; + const ::mavsdk::rpc::gimbal::Attitude& attitude() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::gimbal::Attitude* release_attitude(); + ::mavsdk::rpc::gimbal::Attitude* mutable_attitude(); + void set_allocated_attitude(::mavsdk::rpc::gimbal::Attitude* value); + void unsafe_arena_set_allocated_attitude(::mavsdk::rpc::gimbal::Attitude* value); + ::mavsdk::rpc::gimbal::Attitude* unsafe_arena_release_attitude(); + + private: + const ::mavsdk::rpc::gimbal::Attitude& _internal_attitude() const; + ::mavsdk::rpc::gimbal::Attitude* _internal_mutable_attitude(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.gimbal.AttitudeResponse) + private: + class _Internal; + + friend class ::google::protobuf::internal::TcParser; + static const ::google::protobuf::internal::TcParseTable< + 0, 1, 1, + 0, 2> + _table_; + friend class ::google::protobuf::MessageLite; + friend class ::google::protobuf::Arena; + template + friend class ::google::protobuf::Arena::InternalHelper; + using InternalArenaConstructable_ = void; + using DestructorSkippable_ = void; + struct Impl_ { + + inline explicit constexpr Impl_( + ::google::protobuf::internal::ConstantInitialized) noexcept; + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena); + inline explicit Impl_(::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena, const Impl_& from); + ::google::protobuf::internal::HasBits<1> _has_bits_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + ::mavsdk::rpc::gimbal::Attitude* attitude_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_gimbal_2fgimbal_2eproto; +}; + +// =================================================================== + + + + +// =================================================================== + + +#ifdef __GNUC__ +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wstrict-aliasing" +#endif // __GNUC__ +// ------------------------------------------------------------------- + +// SetAnglesRequest + +// int32 gimbal_id = 1; +inline void SetAnglesRequest::clear_gimbal_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.gimbal_id_ = 0; +} +inline ::int32_t SetAnglesRequest::gimbal_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.SetAnglesRequest.gimbal_id) + return _internal_gimbal_id(); +} +inline void SetAnglesRequest::set_gimbal_id(::int32_t value) { + _internal_set_gimbal_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.SetAnglesRequest.gimbal_id) +} +inline ::int32_t SetAnglesRequest::_internal_gimbal_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.gimbal_id_; +} +inline void SetAnglesRequest::_internal_set_gimbal_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.gimbal_id_ = value; +} + +// float roll_deg = 2; +inline void SetAnglesRequest::clear_roll_deg() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.roll_deg_ = 0; } @@ -4121,7 +5778,7 @@ inline void SetAnglesRequest::_internal_set_roll_deg(float value) { _impl_.roll_deg_ = value; } -// float pitch_deg = 2; +// float pitch_deg = 3; inline void SetAnglesRequest::clear_pitch_deg() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.pitch_deg_ = 0; @@ -4144,7 +5801,7 @@ inline void SetAnglesRequest::_internal_set_pitch_deg(float value) { _impl_.pitch_deg_ = value; } -// float yaw_deg = 3; +// float yaw_deg = 4; inline void SetAnglesRequest::clear_yaw_deg() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.yaw_deg_ = 0; @@ -4167,7 +5824,7 @@ inline void SetAnglesRequest::_internal_set_yaw_deg(float value) { _impl_.yaw_deg_ = value; } -// .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 4; +// .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 5; inline void SetAnglesRequest::clear_gimbal_mode() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.gimbal_mode_ = 0; @@ -4190,7 +5847,7 @@ inline void SetAnglesRequest::_internal_set_gimbal_mode(::mavsdk::rpc::gimbal::G _impl_.gimbal_mode_ = value; } -// .mavsdk.rpc.gimbal.SendMode send_mode = 5; +// .mavsdk.rpc.gimbal.SendMode send_mode = 6; inline void SetAnglesRequest::clear_send_mode() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.send_mode_ = 0; @@ -4317,7 +5974,30 @@ inline void SetAnglesResponse::set_allocated_gimbal_result(::mavsdk::rpc::gimbal // SetAngularRatesRequest -// float roll_rate_deg_s = 1; +// int32 gimbal_id = 1; +inline void SetAngularRatesRequest::clear_gimbal_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.gimbal_id_ = 0; +} +inline ::int32_t SetAngularRatesRequest::gimbal_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.SetAngularRatesRequest.gimbal_id) + return _internal_gimbal_id(); +} +inline void SetAngularRatesRequest::set_gimbal_id(::int32_t value) { + _internal_set_gimbal_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.SetAngularRatesRequest.gimbal_id) +} +inline ::int32_t SetAngularRatesRequest::_internal_gimbal_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.gimbal_id_; +} +inline void SetAngularRatesRequest::_internal_set_gimbal_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.gimbal_id_ = value; +} + +// float roll_rate_deg_s = 2; inline void SetAngularRatesRequest::clear_roll_rate_deg_s() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.roll_rate_deg_s_ = 0; @@ -4340,7 +6020,7 @@ inline void SetAngularRatesRequest::_internal_set_roll_rate_deg_s(float value) { _impl_.roll_rate_deg_s_ = value; } -// float pitch_rate_deg_s = 2; +// float pitch_rate_deg_s = 3; inline void SetAngularRatesRequest::clear_pitch_rate_deg_s() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.pitch_rate_deg_s_ = 0; @@ -4363,7 +6043,7 @@ inline void SetAngularRatesRequest::_internal_set_pitch_rate_deg_s(float value) _impl_.pitch_rate_deg_s_ = value; } -// float yaw_rate_deg_s = 3; +// float yaw_rate_deg_s = 4; inline void SetAngularRatesRequest::clear_yaw_rate_deg_s() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.yaw_rate_deg_s_ = 0; @@ -4386,7 +6066,7 @@ inline void SetAngularRatesRequest::_internal_set_yaw_rate_deg_s(float value) { _impl_.yaw_rate_deg_s_ = value; } -// .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 4; +// .mavsdk.rpc.gimbal.GimbalMode gimbal_mode = 5; inline void SetAngularRatesRequest::clear_gimbal_mode() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.gimbal_mode_ = 0; @@ -4409,7 +6089,7 @@ inline void SetAngularRatesRequest::_internal_set_gimbal_mode(::mavsdk::rpc::gim _impl_.gimbal_mode_ = value; } -// .mavsdk.rpc.gimbal.SendMode send_mode = 5; +// .mavsdk.rpc.gimbal.SendMode send_mode = 6; inline void SetAngularRatesRequest::clear_send_mode() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.send_mode_ = 0; @@ -4536,7 +6216,30 @@ inline void SetAngularRatesResponse::set_allocated_gimbal_result(::mavsdk::rpc:: // SetRoiLocationRequest -// double latitude_deg = 1; +// int32 gimbal_id = 1; +inline void SetRoiLocationRequest::clear_gimbal_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.gimbal_id_ = 0; +} +inline ::int32_t SetRoiLocationRequest::gimbal_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.SetRoiLocationRequest.gimbal_id) + return _internal_gimbal_id(); +} +inline void SetRoiLocationRequest::set_gimbal_id(::int32_t value) { + _internal_set_gimbal_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.SetRoiLocationRequest.gimbal_id) +} +inline ::int32_t SetRoiLocationRequest::_internal_gimbal_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.gimbal_id_; +} +inline void SetRoiLocationRequest::_internal_set_gimbal_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.gimbal_id_ = value; +} + +// double latitude_deg = 2; inline void SetRoiLocationRequest::clear_latitude_deg() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.latitude_deg_ = 0; @@ -4559,7 +6262,7 @@ inline void SetRoiLocationRequest::_internal_set_latitude_deg(double value) { _impl_.latitude_deg_ = value; } -// double longitude_deg = 2; +// double longitude_deg = 3; inline void SetRoiLocationRequest::clear_longitude_deg() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.longitude_deg_ = 0; @@ -4582,7 +6285,7 @@ inline void SetRoiLocationRequest::_internal_set_longitude_deg(double value) { _impl_.longitude_deg_ = value; } -// float altitude_m = 3; +// float altitude_m = 4; inline void SetRoiLocationRequest::clear_altitude_m() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.altitude_m_ = 0; @@ -4709,7 +6412,30 @@ inline void SetRoiLocationResponse::set_allocated_gimbal_result(::mavsdk::rpc::g // TakeControlRequest -// .mavsdk.rpc.gimbal.ControlMode control_mode = 1; +// int32 gimbal_id = 1; +inline void TakeControlRequest::clear_gimbal_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.gimbal_id_ = 0; +} +inline ::int32_t TakeControlRequest::gimbal_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.TakeControlRequest.gimbal_id) + return _internal_gimbal_id(); +} +inline void TakeControlRequest::set_gimbal_id(::int32_t value) { + _internal_set_gimbal_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.TakeControlRequest.gimbal_id) +} +inline ::int32_t TakeControlRequest::_internal_gimbal_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.gimbal_id_; +} +inline void TakeControlRequest::_internal_set_gimbal_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.gimbal_id_ = value; +} + +// .mavsdk.rpc.gimbal.ControlMode control_mode = 2; inline void TakeControlRequest::clear_control_mode() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.control_mode_ = 0; @@ -4836,6 +6562,29 @@ inline void TakeControlResponse::set_allocated_gimbal_result(::mavsdk::rpc::gimb // ReleaseControlRequest +// int32 gimbal_id = 1; +inline void ReleaseControlRequest::clear_gimbal_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.gimbal_id_ = 0; +} +inline ::int32_t ReleaseControlRequest::gimbal_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.ReleaseControlRequest.gimbal_id) + return _internal_gimbal_id(); +} +inline void ReleaseControlRequest::set_gimbal_id(::int32_t value) { + _internal_set_gimbal_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.ReleaseControlRequest.gimbal_id) +} +inline ::int32_t ReleaseControlRequest::_internal_gimbal_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.gimbal_id_; +} +inline void ReleaseControlRequest::_internal_set_gimbal_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.gimbal_id_ = value; +} + // ------------------------------------------------------------------- // ReleaseControlResponse @@ -4938,49 +6687,272 @@ inline void ReleaseControlResponse::set_allocated_gimbal_result(::mavsdk::rpc::g // ------------------------------------------------------------------- -// SubscribeControlRequest +// SubscribeControlStatusRequest // ------------------------------------------------------------------- -// ControlResponse +// ControlStatusResponse // .mavsdk.rpc.gimbal.ControlStatus control_status = 1; -inline bool ControlResponse::has_control_status() const { +inline bool ControlStatusResponse::has_control_status() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; PROTOBUF_ASSUME(!value || _impl_.control_status_ != nullptr); return value; } -inline void ControlResponse::clear_control_status() { +inline void ControlStatusResponse::clear_control_status() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (_impl_.control_status_ != nullptr) _impl_.control_status_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::gimbal::ControlStatus& ControlResponse::_internal_control_status() const { +inline const ::mavsdk::rpc::gimbal::ControlStatus& ControlStatusResponse::_internal_control_status() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::gimbal::ControlStatus* p = _impl_.control_status_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_ControlStatus_default_instance_); +} +inline const ::mavsdk::rpc::gimbal::ControlStatus& ControlStatusResponse::control_status() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.ControlStatusResponse.control_status) + return _internal_control_status(); +} +inline void ControlStatusResponse::unsafe_arena_set_allocated_control_status(::mavsdk::rpc::gimbal::ControlStatus* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.control_status_); + } + _impl_.control_status_ = reinterpret_cast<::mavsdk::rpc::gimbal::ControlStatus*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.ControlStatusResponse.control_status) +} +inline ::mavsdk::rpc::gimbal::ControlStatus* ControlStatusResponse::release_control_status() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::gimbal::ControlStatus* released = _impl_.control_status_; + _impl_.control_status_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return released; +} +inline ::mavsdk::rpc::gimbal::ControlStatus* ControlStatusResponse::unsafe_arena_release_control_status() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.ControlStatusResponse.control_status) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::gimbal::ControlStatus* temp = _impl_.control_status_; + _impl_.control_status_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::gimbal::ControlStatus* ControlStatusResponse::_internal_mutable_control_status() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.control_status_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::ControlStatus>(GetArena()); + _impl_.control_status_ = reinterpret_cast<::mavsdk::rpc::gimbal::ControlStatus*>(p); + } + return _impl_.control_status_; +} +inline ::mavsdk::rpc::gimbal::ControlStatus* ControlStatusResponse::mutable_control_status() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::gimbal::ControlStatus* _msg = _internal_mutable_control_status(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.ControlStatusResponse.control_status) + return _msg; +} +inline void ControlStatusResponse::set_allocated_control_status(::mavsdk::rpc::gimbal::ControlStatus* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::gimbal::ControlStatus*>(_impl_.control_status_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::ControlStatus*>(value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + + _impl_.control_status_ = reinterpret_cast<::mavsdk::rpc::gimbal::ControlStatus*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.ControlStatusResponse.control_status) +} + +// ------------------------------------------------------------------- + +// GetControlStatusRequest + +// int32 gimbal_id = 1; +inline void GetControlStatusRequest::clear_gimbal_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.gimbal_id_ = 0; +} +inline ::int32_t GetControlStatusRequest::gimbal_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.GetControlStatusRequest.gimbal_id) + return _internal_gimbal_id(); +} +inline void GetControlStatusRequest::set_gimbal_id(::int32_t value) { + _internal_set_gimbal_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.GetControlStatusRequest.gimbal_id) +} +inline ::int32_t GetControlStatusRequest::_internal_gimbal_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.gimbal_id_; +} +inline void GetControlStatusRequest::_internal_set_gimbal_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.gimbal_id_ = value; +} + +// ------------------------------------------------------------------- + +// GetControlStatusResponse + +// .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; +inline bool GetControlStatusResponse::has_gimbal_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.gimbal_result_ != nullptr); + return value; +} +inline void GetControlStatusResponse::clear_gimbal_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.gimbal_result_ != nullptr) _impl_.gimbal_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::gimbal::GimbalResult& GetControlStatusResponse::_internal_gimbal_result() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::gimbal::GimbalResult* p = _impl_.gimbal_result_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_GimbalResult_default_instance_); +} +inline const ::mavsdk::rpc::gimbal::GimbalResult& GetControlStatusResponse::gimbal_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.GetControlStatusResponse.gimbal_result) + return _internal_gimbal_result(); +} +inline void GetControlStatusResponse::unsafe_arena_set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.gimbal_result_); + } + _impl_.gimbal_result_ = reinterpret_cast<::mavsdk::rpc::gimbal::GimbalResult*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.GetControlStatusResponse.gimbal_result) +} +inline ::mavsdk::rpc::gimbal::GimbalResult* GetControlStatusResponse::release_gimbal_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::gimbal::GimbalResult* released = _impl_.gimbal_result_; + _impl_.gimbal_result_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return released; +} +inline ::mavsdk::rpc::gimbal::GimbalResult* GetControlStatusResponse::unsafe_arena_release_gimbal_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.GetControlStatusResponse.gimbal_result) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::gimbal::GimbalResult* temp = _impl_.gimbal_result_; + _impl_.gimbal_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::gimbal::GimbalResult* GetControlStatusResponse::_internal_mutable_gimbal_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.gimbal_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::GimbalResult>(GetArena()); + _impl_.gimbal_result_ = reinterpret_cast<::mavsdk::rpc::gimbal::GimbalResult*>(p); + } + return _impl_.gimbal_result_; +} +inline ::mavsdk::rpc::gimbal::GimbalResult* GetControlStatusResponse::mutable_gimbal_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::gimbal::GimbalResult* _msg = _internal_mutable_gimbal_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.GetControlStatusResponse.gimbal_result) + return _msg; +} +inline void GetControlStatusResponse::set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::gimbal::GimbalResult*>(_impl_.gimbal_result_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::GimbalResult*>(value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + + _impl_.gimbal_result_ = reinterpret_cast<::mavsdk::rpc::gimbal::GimbalResult*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.GetControlStatusResponse.gimbal_result) +} + +// .mavsdk.rpc.gimbal.ControlStatus control_status = 2; +inline bool GetControlStatusResponse::has_control_status() const { + bool value = (_impl_._has_bits_[0] & 0x00000002u) != 0; + PROTOBUF_ASSUME(!value || _impl_.control_status_ != nullptr); + return value; +} +inline void GetControlStatusResponse::clear_control_status() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.control_status_ != nullptr) _impl_.control_status_->Clear(); + _impl_._has_bits_[0] &= ~0x00000002u; +} +inline const ::mavsdk::rpc::gimbal::ControlStatus& GetControlStatusResponse::_internal_control_status() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); const ::mavsdk::rpc::gimbal::ControlStatus* p = _impl_.control_status_; return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_ControlStatus_default_instance_); } -inline const ::mavsdk::rpc::gimbal::ControlStatus& ControlResponse::control_status() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.ControlResponse.control_status) +inline const ::mavsdk::rpc::gimbal::ControlStatus& GetControlStatusResponse::control_status() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.GetControlStatusResponse.control_status) return _internal_control_status(); } -inline void ControlResponse::unsafe_arena_set_allocated_control_status(::mavsdk::rpc::gimbal::ControlStatus* value) { +inline void GetControlStatusResponse::unsafe_arena_set_allocated_control_status(::mavsdk::rpc::gimbal::ControlStatus* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (GetArena() == nullptr) { delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.control_status_); } _impl_.control_status_ = reinterpret_cast<::mavsdk::rpc::gimbal::ControlStatus*>(value); if (value != nullptr) { - _impl_._has_bits_[0] |= 0x00000001u; + _impl_._has_bits_[0] |= 0x00000002u; } else { - _impl_._has_bits_[0] &= ~0x00000001u; + _impl_._has_bits_[0] &= ~0x00000002u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.ControlResponse.control_status) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.GetControlStatusResponse.control_status) } -inline ::mavsdk::rpc::gimbal::ControlStatus* ControlResponse::release_control_status() { +inline ::mavsdk::rpc::gimbal::ControlStatus* GetControlStatusResponse::release_control_status() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] &= ~0x00000001u; + _impl_._has_bits_[0] &= ~0x00000002u; ::mavsdk::rpc::gimbal::ControlStatus* released = _impl_.control_status_; _impl_.control_status_ = nullptr; #ifdef PROTOBUF_FORCE_COPY_IN_RELEASE @@ -4996,30 +6968,30 @@ inline ::mavsdk::rpc::gimbal::ControlStatus* ControlResponse::release_control_st #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::gimbal::ControlStatus* ControlResponse::unsafe_arena_release_control_status() { +inline ::mavsdk::rpc::gimbal::ControlStatus* GetControlStatusResponse::unsafe_arena_release_control_status() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.ControlResponse.control_status) + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.GetControlStatusResponse.control_status) - _impl_._has_bits_[0] &= ~0x00000001u; + _impl_._has_bits_[0] &= ~0x00000002u; ::mavsdk::rpc::gimbal::ControlStatus* temp = _impl_.control_status_; _impl_.control_status_ = nullptr; return temp; } -inline ::mavsdk::rpc::gimbal::ControlStatus* ControlResponse::_internal_mutable_control_status() { +inline ::mavsdk::rpc::gimbal::ControlStatus* GetControlStatusResponse::_internal_mutable_control_status() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000001u; + _impl_._has_bits_[0] |= 0x00000002u; if (_impl_.control_status_ == nullptr) { auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::ControlStatus>(GetArena()); _impl_.control_status_ = reinterpret_cast<::mavsdk::rpc::gimbal::ControlStatus*>(p); } return _impl_.control_status_; } -inline ::mavsdk::rpc::gimbal::ControlStatus* ControlResponse::mutable_control_status() ABSL_ATTRIBUTE_LIFETIME_BOUND { +inline ::mavsdk::rpc::gimbal::ControlStatus* GetControlStatusResponse::mutable_control_status() ABSL_ATTRIBUTE_LIFETIME_BOUND { ::mavsdk::rpc::gimbal::ControlStatus* _msg = _internal_mutable_control_status(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.ControlResponse.control_status) + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.GetControlStatusResponse.control_status) return _msg; } -inline void ControlResponse::set_allocated_control_status(::mavsdk::rpc::gimbal::ControlStatus* value) { +inline void GetControlStatusResponse::set_allocated_control_status(::mavsdk::rpc::gimbal::ControlStatus* value) { ::google::protobuf::Arena* message_arena = GetArena(); PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (message_arena == nullptr) { @@ -5031,13 +7003,13 @@ inline void ControlResponse::set_allocated_control_status(::mavsdk::rpc::gimbal: if (message_arena != submessage_arena) { value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); } - _impl_._has_bits_[0] |= 0x00000001u; + _impl_._has_bits_[0] |= 0x00000002u; } else { - _impl_._has_bits_[0] &= ~0x00000001u; + _impl_._has_bits_[0] &= ~0x00000002u; } _impl_.control_status_ = reinterpret_cast<::mavsdk::rpc::gimbal::ControlStatus*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.ControlResponse.control_status) + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.GetControlStatusResponse.control_status) } // ------------------------------------------------------------------- @@ -5241,90 +7213,401 @@ inline void AngularVelocityBody::clear_pitch_rad_s() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.pitch_rad_s_ = 0; } -inline float AngularVelocityBody::pitch_rad_s() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.AngularVelocityBody.pitch_rad_s) - return _internal_pitch_rad_s(); +inline float AngularVelocityBody::pitch_rad_s() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.AngularVelocityBody.pitch_rad_s) + return _internal_pitch_rad_s(); +} +inline void AngularVelocityBody::set_pitch_rad_s(float value) { + _internal_set_pitch_rad_s(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.AngularVelocityBody.pitch_rad_s) +} +inline float AngularVelocityBody::_internal_pitch_rad_s() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.pitch_rad_s_; +} +inline void AngularVelocityBody::_internal_set_pitch_rad_s(float value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.pitch_rad_s_ = value; +} + +// float yaw_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; +inline void AngularVelocityBody::clear_yaw_rad_s() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.yaw_rad_s_ = 0; +} +inline float AngularVelocityBody::yaw_rad_s() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.AngularVelocityBody.yaw_rad_s) + return _internal_yaw_rad_s(); +} +inline void AngularVelocityBody::set_yaw_rad_s(float value) { + _internal_set_yaw_rad_s(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.AngularVelocityBody.yaw_rad_s) +} +inline float AngularVelocityBody::_internal_yaw_rad_s() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.yaw_rad_s_; +} +inline void AngularVelocityBody::_internal_set_yaw_rad_s(float value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.yaw_rad_s_ = value; +} + +// ------------------------------------------------------------------- + +// Attitude + +// int32 gimbal_id = 1; +inline void Attitude::clear_gimbal_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.gimbal_id_ = 0; +} +inline ::int32_t Attitude::gimbal_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.Attitude.gimbal_id) + return _internal_gimbal_id(); +} +inline void Attitude::set_gimbal_id(::int32_t value) { + _internal_set_gimbal_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.Attitude.gimbal_id) +} +inline ::int32_t Attitude::_internal_gimbal_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.gimbal_id_; +} +inline void Attitude::_internal_set_gimbal_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.gimbal_id_ = value; +} + +// .mavsdk.rpc.gimbal.EulerAngle euler_angle_forward = 2; +inline bool Attitude::has_euler_angle_forward() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.euler_angle_forward_ != nullptr); + return value; +} +inline void Attitude::clear_euler_angle_forward() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.euler_angle_forward_ != nullptr) _impl_.euler_angle_forward_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::gimbal::EulerAngle& Attitude::_internal_euler_angle_forward() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::gimbal::EulerAngle* p = _impl_.euler_angle_forward_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_EulerAngle_default_instance_); +} +inline const ::mavsdk::rpc::gimbal::EulerAngle& Attitude::euler_angle_forward() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.Attitude.euler_angle_forward) + return _internal_euler_angle_forward(); +} +inline void Attitude::unsafe_arena_set_allocated_euler_angle_forward(::mavsdk::rpc::gimbal::EulerAngle* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.euler_angle_forward_); + } + _impl_.euler_angle_forward_ = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.Attitude.euler_angle_forward) +} +inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::release_euler_angle_forward() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::gimbal::EulerAngle* released = _impl_.euler_angle_forward_; + _impl_.euler_angle_forward_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return released; +} +inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::unsafe_arena_release_euler_angle_forward() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.Attitude.euler_angle_forward) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::gimbal::EulerAngle* temp = _impl_.euler_angle_forward_; + _impl_.euler_angle_forward_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::_internal_mutable_euler_angle_forward() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.euler_angle_forward_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::EulerAngle>(GetArena()); + _impl_.euler_angle_forward_ = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(p); + } + return _impl_.euler_angle_forward_; +} +inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::mutable_euler_angle_forward() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::gimbal::EulerAngle* _msg = _internal_mutable_euler_angle_forward(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.Attitude.euler_angle_forward) + return _msg; +} +inline void Attitude::set_allocated_euler_angle_forward(::mavsdk::rpc::gimbal::EulerAngle* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(_impl_.euler_angle_forward_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000001u; + } else { + _impl_._has_bits_[0] &= ~0x00000001u; + } + + _impl_.euler_angle_forward_ = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.Attitude.euler_angle_forward) +} + +// .mavsdk.rpc.gimbal.Quaternion quaternion_forward = 3; +inline bool Attitude::has_quaternion_forward() const { + bool value = (_impl_._has_bits_[0] & 0x00000002u) != 0; + PROTOBUF_ASSUME(!value || _impl_.quaternion_forward_ != nullptr); + return value; +} +inline void Attitude::clear_quaternion_forward() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.quaternion_forward_ != nullptr) _impl_.quaternion_forward_->Clear(); + _impl_._has_bits_[0] &= ~0x00000002u; +} +inline const ::mavsdk::rpc::gimbal::Quaternion& Attitude::_internal_quaternion_forward() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::gimbal::Quaternion* p = _impl_.quaternion_forward_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_Quaternion_default_instance_); +} +inline const ::mavsdk::rpc::gimbal::Quaternion& Attitude::quaternion_forward() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.Attitude.quaternion_forward) + return _internal_quaternion_forward(); +} +inline void Attitude::unsafe_arena_set_allocated_quaternion_forward(::mavsdk::rpc::gimbal::Quaternion* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.quaternion_forward_); + } + _impl_.quaternion_forward_ = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000002u; + } else { + _impl_._has_bits_[0] &= ~0x00000002u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.Attitude.quaternion_forward) +} +inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::release_quaternion_forward() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000002u; + ::mavsdk::rpc::gimbal::Quaternion* released = _impl_.quaternion_forward_; + _impl_.quaternion_forward_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return released; +} +inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::unsafe_arena_release_quaternion_forward() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.Attitude.quaternion_forward) + + _impl_._has_bits_[0] &= ~0x00000002u; + ::mavsdk::rpc::gimbal::Quaternion* temp = _impl_.quaternion_forward_; + _impl_.quaternion_forward_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::_internal_mutable_quaternion_forward() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000002u; + if (_impl_.quaternion_forward_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::Quaternion>(GetArena()); + _impl_.quaternion_forward_ = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(p); + } + return _impl_.quaternion_forward_; +} +inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::mutable_quaternion_forward() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::gimbal::Quaternion* _msg = _internal_mutable_quaternion_forward(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.Attitude.quaternion_forward) + return _msg; +} +inline void Attitude::set_allocated_quaternion_forward(::mavsdk::rpc::gimbal::Quaternion* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(_impl_.quaternion_forward_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000002u; + } else { + _impl_._has_bits_[0] &= ~0x00000002u; + } + + _impl_.quaternion_forward_ = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.Attitude.quaternion_forward) +} + +// .mavsdk.rpc.gimbal.EulerAngle euler_angle_north = 4; +inline bool Attitude::has_euler_angle_north() const { + bool value = (_impl_._has_bits_[0] & 0x00000004u) != 0; + PROTOBUF_ASSUME(!value || _impl_.euler_angle_north_ != nullptr); + return value; } -inline void AngularVelocityBody::set_pitch_rad_s(float value) { - _internal_set_pitch_rad_s(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.AngularVelocityBody.pitch_rad_s) +inline void Attitude::clear_euler_angle_north() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.euler_angle_north_ != nullptr) _impl_.euler_angle_north_->Clear(); + _impl_._has_bits_[0] &= ~0x00000004u; } -inline float AngularVelocityBody::_internal_pitch_rad_s() const { +inline const ::mavsdk::rpc::gimbal::EulerAngle& Attitude::_internal_euler_angle_north() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.pitch_rad_s_; + const ::mavsdk::rpc::gimbal::EulerAngle* p = _impl_.euler_angle_north_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_EulerAngle_default_instance_); } -inline void AngularVelocityBody::_internal_set_pitch_rad_s(float value) { +inline const ::mavsdk::rpc::gimbal::EulerAngle& Attitude::euler_angle_north() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.Attitude.euler_angle_north) + return _internal_euler_angle_north(); +} +inline void Attitude::unsafe_arena_set_allocated_euler_angle_north(::mavsdk::rpc::gimbal::EulerAngle* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.pitch_rad_s_ = value; + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.euler_angle_north_); + } + _impl_.euler_angle_north_ = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(value); + if (value != nullptr) { + _impl_._has_bits_[0] |= 0x00000004u; + } else { + _impl_._has_bits_[0] &= ~0x00000004u; + } + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.Attitude.euler_angle_north) } - -// float yaw_rad_s = 3 [(.mavsdk.options.default_value) = "NaN"]; -inline void AngularVelocityBody::clear_yaw_rad_s() { +inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::release_euler_angle_north() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.yaw_rad_s_ = 0; + + _impl_._has_bits_[0] &= ~0x00000004u; + ::mavsdk::rpc::gimbal::EulerAngle* released = _impl_.euler_angle_north_; + _impl_.euler_angle_north_ = nullptr; +#ifdef PROTOBUF_FORCE_COPY_IN_RELEASE + auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + if (GetArena() == nullptr) { + delete old; + } +#else // PROTOBUF_FORCE_COPY_IN_RELEASE + if (GetArena() != nullptr) { + released = ::google::protobuf::internal::DuplicateIfNonNull(released); + } +#endif // !PROTOBUF_FORCE_COPY_IN_RELEASE + return released; } -inline float AngularVelocityBody::yaw_rad_s() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.AngularVelocityBody.yaw_rad_s) - return _internal_yaw_rad_s(); +inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::unsafe_arena_release_euler_angle_north() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.Attitude.euler_angle_north) + + _impl_._has_bits_[0] &= ~0x00000004u; + ::mavsdk::rpc::gimbal::EulerAngle* temp = _impl_.euler_angle_north_; + _impl_.euler_angle_north_ = nullptr; + return temp; } -inline void AngularVelocityBody::set_yaw_rad_s(float value) { - _internal_set_yaw_rad_s(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.AngularVelocityBody.yaw_rad_s) +inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::_internal_mutable_euler_angle_north() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000004u; + if (_impl_.euler_angle_north_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::EulerAngle>(GetArena()); + _impl_.euler_angle_north_ = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(p); + } + return _impl_.euler_angle_north_; } -inline float AngularVelocityBody::_internal_yaw_rad_s() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.yaw_rad_s_; +inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::mutable_euler_angle_north() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::gimbal::EulerAngle* _msg = _internal_mutable_euler_angle_north(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.Attitude.euler_angle_north) + return _msg; } -inline void AngularVelocityBody::_internal_set_yaw_rad_s(float value) { +inline void Attitude::set_allocated_euler_angle_north(::mavsdk::rpc::gimbal::EulerAngle* value) { + ::google::protobuf::Arena* message_arena = GetArena(); PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.yaw_rad_s_ = value; -} + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(_impl_.euler_angle_north_); + } -// ------------------------------------------------------------------- + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(value)->GetArena(); + if (message_arena != submessage_arena) { + value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); + } + _impl_._has_bits_[0] |= 0x00000004u; + } else { + _impl_._has_bits_[0] &= ~0x00000004u; + } -// Attitude + _impl_.euler_angle_north_ = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.Attitude.euler_angle_north) +} -// .mavsdk.rpc.gimbal.EulerAngle euler_angle_forward = 1; -inline bool Attitude::has_euler_angle_forward() const { - bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.euler_angle_forward_ != nullptr); +// .mavsdk.rpc.gimbal.Quaternion quaternion_north = 5; +inline bool Attitude::has_quaternion_north() const { + bool value = (_impl_._has_bits_[0] & 0x00000008u) != 0; + PROTOBUF_ASSUME(!value || _impl_.quaternion_north_ != nullptr); return value; } -inline void Attitude::clear_euler_angle_forward() { +inline void Attitude::clear_quaternion_north() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.euler_angle_forward_ != nullptr) _impl_.euler_angle_forward_->Clear(); - _impl_._has_bits_[0] &= ~0x00000001u; + if (_impl_.quaternion_north_ != nullptr) _impl_.quaternion_north_->Clear(); + _impl_._has_bits_[0] &= ~0x00000008u; } -inline const ::mavsdk::rpc::gimbal::EulerAngle& Attitude::_internal_euler_angle_forward() const { +inline const ::mavsdk::rpc::gimbal::Quaternion& Attitude::_internal_quaternion_north() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::gimbal::EulerAngle* p = _impl_.euler_angle_forward_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_EulerAngle_default_instance_); + const ::mavsdk::rpc::gimbal::Quaternion* p = _impl_.quaternion_north_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_Quaternion_default_instance_); } -inline const ::mavsdk::rpc::gimbal::EulerAngle& Attitude::euler_angle_forward() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.Attitude.euler_angle_forward) - return _internal_euler_angle_forward(); +inline const ::mavsdk::rpc::gimbal::Quaternion& Attitude::quaternion_north() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.Attitude.quaternion_north) + return _internal_quaternion_north(); } -inline void Attitude::unsafe_arena_set_allocated_euler_angle_forward(::mavsdk::rpc::gimbal::EulerAngle* value) { +inline void Attitude::unsafe_arena_set_allocated_quaternion_north(::mavsdk::rpc::gimbal::Quaternion* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.euler_angle_forward_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.quaternion_north_); } - _impl_.euler_angle_forward_ = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(value); + _impl_.quaternion_north_ = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(value); if (value != nullptr) { - _impl_._has_bits_[0] |= 0x00000001u; + _impl_._has_bits_[0] |= 0x00000008u; } else { - _impl_._has_bits_[0] &= ~0x00000001u; + _impl_._has_bits_[0] &= ~0x00000008u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.Attitude.euler_angle_forward) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.Attitude.quaternion_north) } -inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::release_euler_angle_forward() { +inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::release_quaternion_north() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::gimbal::EulerAngle* released = _impl_.euler_angle_forward_; - _impl_.euler_angle_forward_ = nullptr; + _impl_._has_bits_[0] &= ~0x00000008u; + ::mavsdk::rpc::gimbal::Quaternion* released = _impl_.quaternion_north_; + _impl_.quaternion_north_ = nullptr; #ifdef PROTOBUF_FORCE_COPY_IN_RELEASE auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); released = ::google::protobuf::internal::DuplicateIfNonNull(released); @@ -5338,89 +7621,89 @@ inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::release_euler_angle_forward( #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::unsafe_arena_release_euler_angle_forward() { +inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::unsafe_arena_release_quaternion_north() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.Attitude.euler_angle_forward) + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.Attitude.quaternion_north) - _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::gimbal::EulerAngle* temp = _impl_.euler_angle_forward_; - _impl_.euler_angle_forward_ = nullptr; + _impl_._has_bits_[0] &= ~0x00000008u; + ::mavsdk::rpc::gimbal::Quaternion* temp = _impl_.quaternion_north_; + _impl_.quaternion_north_ = nullptr; return temp; } -inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::_internal_mutable_euler_angle_forward() { +inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::_internal_mutable_quaternion_north() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.euler_angle_forward_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::EulerAngle>(GetArena()); - _impl_.euler_angle_forward_ = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(p); + _impl_._has_bits_[0] |= 0x00000008u; + if (_impl_.quaternion_north_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::Quaternion>(GetArena()); + _impl_.quaternion_north_ = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(p); } - return _impl_.euler_angle_forward_; + return _impl_.quaternion_north_; } -inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::mutable_euler_angle_forward() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::gimbal::EulerAngle* _msg = _internal_mutable_euler_angle_forward(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.Attitude.euler_angle_forward) +inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::mutable_quaternion_north() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::gimbal::Quaternion* _msg = _internal_mutable_quaternion_north(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.Attitude.quaternion_north) return _msg; } -inline void Attitude::set_allocated_euler_angle_forward(::mavsdk::rpc::gimbal::EulerAngle* value) { +inline void Attitude::set_allocated_quaternion_north(::mavsdk::rpc::gimbal::Quaternion* value) { ::google::protobuf::Arena* message_arena = GetArena(); PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(_impl_.euler_angle_forward_); + delete reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(_impl_.quaternion_north_); } if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(value)->GetArena(); + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(value)->GetArena(); if (message_arena != submessage_arena) { value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); } - _impl_._has_bits_[0] |= 0x00000001u; + _impl_._has_bits_[0] |= 0x00000008u; } else { - _impl_._has_bits_[0] &= ~0x00000001u; + _impl_._has_bits_[0] &= ~0x00000008u; } - _impl_.euler_angle_forward_ = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.Attitude.euler_angle_forward) + _impl_.quaternion_north_ = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.Attitude.quaternion_north) } -// .mavsdk.rpc.gimbal.Quaternion quaternion_forward = 2; -inline bool Attitude::has_quaternion_forward() const { - bool value = (_impl_._has_bits_[0] & 0x00000002u) != 0; - PROTOBUF_ASSUME(!value || _impl_.quaternion_forward_ != nullptr); +// .mavsdk.rpc.gimbal.AngularVelocityBody angular_velocity = 6; +inline bool Attitude::has_angular_velocity() const { + bool value = (_impl_._has_bits_[0] & 0x00000010u) != 0; + PROTOBUF_ASSUME(!value || _impl_.angular_velocity_ != nullptr); return value; } -inline void Attitude::clear_quaternion_forward() { +inline void Attitude::clear_angular_velocity() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.quaternion_forward_ != nullptr) _impl_.quaternion_forward_->Clear(); - _impl_._has_bits_[0] &= ~0x00000002u; + if (_impl_.angular_velocity_ != nullptr) _impl_.angular_velocity_->Clear(); + _impl_._has_bits_[0] &= ~0x00000010u; } -inline const ::mavsdk::rpc::gimbal::Quaternion& Attitude::_internal_quaternion_forward() const { +inline const ::mavsdk::rpc::gimbal::AngularVelocityBody& Attitude::_internal_angular_velocity() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::gimbal::Quaternion* p = _impl_.quaternion_forward_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_Quaternion_default_instance_); + const ::mavsdk::rpc::gimbal::AngularVelocityBody* p = _impl_.angular_velocity_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_AngularVelocityBody_default_instance_); } -inline const ::mavsdk::rpc::gimbal::Quaternion& Attitude::quaternion_forward() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.Attitude.quaternion_forward) - return _internal_quaternion_forward(); +inline const ::mavsdk::rpc::gimbal::AngularVelocityBody& Attitude::angular_velocity() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.Attitude.angular_velocity) + return _internal_angular_velocity(); } -inline void Attitude::unsafe_arena_set_allocated_quaternion_forward(::mavsdk::rpc::gimbal::Quaternion* value) { +inline void Attitude::unsafe_arena_set_allocated_angular_velocity(::mavsdk::rpc::gimbal::AngularVelocityBody* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.quaternion_forward_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.angular_velocity_); } - _impl_.quaternion_forward_ = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(value); + _impl_.angular_velocity_ = reinterpret_cast<::mavsdk::rpc::gimbal::AngularVelocityBody*>(value); if (value != nullptr) { - _impl_._has_bits_[0] |= 0x00000002u; + _impl_._has_bits_[0] |= 0x00000010u; } else { - _impl_._has_bits_[0] &= ~0x00000002u; + _impl_._has_bits_[0] &= ~0x00000010u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.Attitude.quaternion_forward) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.Attitude.angular_velocity) } -inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::release_quaternion_forward() { +inline ::mavsdk::rpc::gimbal::AngularVelocityBody* Attitude::release_angular_velocity() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] &= ~0x00000002u; - ::mavsdk::rpc::gimbal::Quaternion* released = _impl_.quaternion_forward_; - _impl_.quaternion_forward_ = nullptr; + _impl_._has_bits_[0] &= ~0x00000010u; + ::mavsdk::rpc::gimbal::AngularVelocityBody* released = _impl_.angular_velocity_; + _impl_.angular_velocity_ = nullptr; #ifdef PROTOBUF_FORCE_COPY_IN_RELEASE auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); released = ::google::protobuf::internal::DuplicateIfNonNull(released); @@ -5434,89 +7717,120 @@ inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::release_quaternion_forward() #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::unsafe_arena_release_quaternion_forward() { +inline ::mavsdk::rpc::gimbal::AngularVelocityBody* Attitude::unsafe_arena_release_angular_velocity() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.Attitude.quaternion_forward) + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.Attitude.angular_velocity) - _impl_._has_bits_[0] &= ~0x00000002u; - ::mavsdk::rpc::gimbal::Quaternion* temp = _impl_.quaternion_forward_; - _impl_.quaternion_forward_ = nullptr; + _impl_._has_bits_[0] &= ~0x00000010u; + ::mavsdk::rpc::gimbal::AngularVelocityBody* temp = _impl_.angular_velocity_; + _impl_.angular_velocity_ = nullptr; return temp; } -inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::_internal_mutable_quaternion_forward() { +inline ::mavsdk::rpc::gimbal::AngularVelocityBody* Attitude::_internal_mutable_angular_velocity() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000002u; - if (_impl_.quaternion_forward_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::Quaternion>(GetArena()); - _impl_.quaternion_forward_ = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(p); + _impl_._has_bits_[0] |= 0x00000010u; + if (_impl_.angular_velocity_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::AngularVelocityBody>(GetArena()); + _impl_.angular_velocity_ = reinterpret_cast<::mavsdk::rpc::gimbal::AngularVelocityBody*>(p); } - return _impl_.quaternion_forward_; + return _impl_.angular_velocity_; } -inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::mutable_quaternion_forward() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::gimbal::Quaternion* _msg = _internal_mutable_quaternion_forward(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.Attitude.quaternion_forward) +inline ::mavsdk::rpc::gimbal::AngularVelocityBody* Attitude::mutable_angular_velocity() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::gimbal::AngularVelocityBody* _msg = _internal_mutable_angular_velocity(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.Attitude.angular_velocity) return _msg; } -inline void Attitude::set_allocated_quaternion_forward(::mavsdk::rpc::gimbal::Quaternion* value) { +inline void Attitude::set_allocated_angular_velocity(::mavsdk::rpc::gimbal::AngularVelocityBody* value) { ::google::protobuf::Arena* message_arena = GetArena(); PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(_impl_.quaternion_forward_); + delete reinterpret_cast<::mavsdk::rpc::gimbal::AngularVelocityBody*>(_impl_.angular_velocity_); } if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(value)->GetArena(); + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::AngularVelocityBody*>(value)->GetArena(); if (message_arena != submessage_arena) { value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); } - _impl_._has_bits_[0] |= 0x00000002u; + _impl_._has_bits_[0] |= 0x00000010u; } else { - _impl_._has_bits_[0] &= ~0x00000002u; + _impl_._has_bits_[0] &= ~0x00000010u; } - _impl_.quaternion_forward_ = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.Attitude.quaternion_forward) + _impl_.angular_velocity_ = reinterpret_cast<::mavsdk::rpc::gimbal::AngularVelocityBody*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.Attitude.angular_velocity) } -// .mavsdk.rpc.gimbal.EulerAngle euler_angle_north = 3; -inline bool Attitude::has_euler_angle_north() const { - bool value = (_impl_._has_bits_[0] & 0x00000004u) != 0; - PROTOBUF_ASSUME(!value || _impl_.euler_angle_north_ != nullptr); +// uint64 timestamp_us = 7; +inline void Attitude::clear_timestamp_us() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.timestamp_us_ = ::uint64_t{0u}; +} +inline ::uint64_t Attitude::timestamp_us() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.Attitude.timestamp_us) + return _internal_timestamp_us(); +} +inline void Attitude::set_timestamp_us(::uint64_t value) { + _internal_set_timestamp_us(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.Attitude.timestamp_us) +} +inline ::uint64_t Attitude::_internal_timestamp_us() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.timestamp_us_; +} +inline void Attitude::_internal_set_timestamp_us(::uint64_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.timestamp_us_ = value; +} + +// ------------------------------------------------------------------- + +// SubscribeAttitudeRequest + +// ------------------------------------------------------------------- + +// AttitudeResponse + +// .mavsdk.rpc.gimbal.Attitude attitude = 1; +inline bool AttitudeResponse::has_attitude() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.attitude_ != nullptr); return value; } -inline void Attitude::clear_euler_angle_north() { +inline void AttitudeResponse::clear_attitude() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.euler_angle_north_ != nullptr) _impl_.euler_angle_north_->Clear(); - _impl_._has_bits_[0] &= ~0x00000004u; + if (_impl_.attitude_ != nullptr) _impl_.attitude_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::gimbal::EulerAngle& Attitude::_internal_euler_angle_north() const { +inline const ::mavsdk::rpc::gimbal::Attitude& AttitudeResponse::_internal_attitude() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::gimbal::EulerAngle* p = _impl_.euler_angle_north_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_EulerAngle_default_instance_); + const ::mavsdk::rpc::gimbal::Attitude* p = _impl_.attitude_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_Attitude_default_instance_); } -inline const ::mavsdk::rpc::gimbal::EulerAngle& Attitude::euler_angle_north() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.Attitude.euler_angle_north) - return _internal_euler_angle_north(); +inline const ::mavsdk::rpc::gimbal::Attitude& AttitudeResponse::attitude() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.AttitudeResponse.attitude) + return _internal_attitude(); } -inline void Attitude::unsafe_arena_set_allocated_euler_angle_north(::mavsdk::rpc::gimbal::EulerAngle* value) { +inline void AttitudeResponse::unsafe_arena_set_allocated_attitude(::mavsdk::rpc::gimbal::Attitude* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.euler_angle_north_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.attitude_); } - _impl_.euler_angle_north_ = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(value); + _impl_.attitude_ = reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(value); if (value != nullptr) { - _impl_._has_bits_[0] |= 0x00000004u; + _impl_._has_bits_[0] |= 0x00000001u; } else { - _impl_._has_bits_[0] &= ~0x00000004u; + _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.Attitude.euler_angle_north) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.AttitudeResponse.attitude) } -inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::release_euler_angle_north() { +inline ::mavsdk::rpc::gimbal::Attitude* AttitudeResponse::release_attitude() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] &= ~0x00000004u; - ::mavsdk::rpc::gimbal::EulerAngle* released = _impl_.euler_angle_north_; - _impl_.euler_angle_north_ = nullptr; + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::gimbal::Attitude* released = _impl_.attitude_; + _impl_.attitude_ = nullptr; #ifdef PROTOBUF_FORCE_COPY_IN_RELEASE auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); released = ::google::protobuf::internal::DuplicateIfNonNull(released); @@ -5530,89 +7844,120 @@ inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::release_euler_angle_north() #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::unsafe_arena_release_euler_angle_north() { +inline ::mavsdk::rpc::gimbal::Attitude* AttitudeResponse::unsafe_arena_release_attitude() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.Attitude.euler_angle_north) + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.AttitudeResponse.attitude) - _impl_._has_bits_[0] &= ~0x00000004u; - ::mavsdk::rpc::gimbal::EulerAngle* temp = _impl_.euler_angle_north_; - _impl_.euler_angle_north_ = nullptr; + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::gimbal::Attitude* temp = _impl_.attitude_; + _impl_.attitude_ = nullptr; return temp; } -inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::_internal_mutable_euler_angle_north() { +inline ::mavsdk::rpc::gimbal::Attitude* AttitudeResponse::_internal_mutable_attitude() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000004u; - if (_impl_.euler_angle_north_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::EulerAngle>(GetArena()); - _impl_.euler_angle_north_ = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(p); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.attitude_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::Attitude>(GetArena()); + _impl_.attitude_ = reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(p); } - return _impl_.euler_angle_north_; + return _impl_.attitude_; } -inline ::mavsdk::rpc::gimbal::EulerAngle* Attitude::mutable_euler_angle_north() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::gimbal::EulerAngle* _msg = _internal_mutable_euler_angle_north(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.Attitude.euler_angle_north) +inline ::mavsdk::rpc::gimbal::Attitude* AttitudeResponse::mutable_attitude() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::gimbal::Attitude* _msg = _internal_mutable_attitude(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.AttitudeResponse.attitude) return _msg; } -inline void Attitude::set_allocated_euler_angle_north(::mavsdk::rpc::gimbal::EulerAngle* value) { +inline void AttitudeResponse::set_allocated_attitude(::mavsdk::rpc::gimbal::Attitude* value) { ::google::protobuf::Arena* message_arena = GetArena(); PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(_impl_.euler_angle_north_); + delete reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(_impl_.attitude_); } if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(value)->GetArena(); + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(value)->GetArena(); if (message_arena != submessage_arena) { value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); } - _impl_._has_bits_[0] |= 0x00000004u; + _impl_._has_bits_[0] |= 0x00000001u; } else { - _impl_._has_bits_[0] &= ~0x00000004u; + _impl_._has_bits_[0] &= ~0x00000001u; } - _impl_.euler_angle_north_ = reinterpret_cast<::mavsdk::rpc::gimbal::EulerAngle*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.Attitude.euler_angle_north) + _impl_.attitude_ = reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.AttitudeResponse.attitude) } -// .mavsdk.rpc.gimbal.Quaternion quaternion_north = 4; -inline bool Attitude::has_quaternion_north() const { - bool value = (_impl_._has_bits_[0] & 0x00000008u) != 0; - PROTOBUF_ASSUME(!value || _impl_.quaternion_north_ != nullptr); +// ------------------------------------------------------------------- + +// GetAttitudeRequest + +// int32 gimbal_id = 1; +inline void GetAttitudeRequest::clear_gimbal_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.gimbal_id_ = 0; +} +inline ::int32_t GetAttitudeRequest::gimbal_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.GetAttitudeRequest.gimbal_id) + return _internal_gimbal_id(); +} +inline void GetAttitudeRequest::set_gimbal_id(::int32_t value) { + _internal_set_gimbal_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.GetAttitudeRequest.gimbal_id) +} +inline ::int32_t GetAttitudeRequest::_internal_gimbal_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.gimbal_id_; +} +inline void GetAttitudeRequest::_internal_set_gimbal_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.gimbal_id_ = value; +} + +// ------------------------------------------------------------------- + +// GetAttitudeResponse + +// .mavsdk.rpc.gimbal.GimbalResult gimbal_result = 1; +inline bool GetAttitudeResponse::has_gimbal_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.gimbal_result_ != nullptr); return value; } -inline void Attitude::clear_quaternion_north() { +inline void GetAttitudeResponse::clear_gimbal_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.quaternion_north_ != nullptr) _impl_.quaternion_north_->Clear(); - _impl_._has_bits_[0] &= ~0x00000008u; + if (_impl_.gimbal_result_ != nullptr) _impl_.gimbal_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::gimbal::Quaternion& Attitude::_internal_quaternion_north() const { +inline const ::mavsdk::rpc::gimbal::GimbalResult& GetAttitudeResponse::_internal_gimbal_result() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::gimbal::Quaternion* p = _impl_.quaternion_north_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_Quaternion_default_instance_); + const ::mavsdk::rpc::gimbal::GimbalResult* p = _impl_.gimbal_result_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_GimbalResult_default_instance_); } -inline const ::mavsdk::rpc::gimbal::Quaternion& Attitude::quaternion_north() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.Attitude.quaternion_north) - return _internal_quaternion_north(); +inline const ::mavsdk::rpc::gimbal::GimbalResult& GetAttitudeResponse::gimbal_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.GetAttitudeResponse.gimbal_result) + return _internal_gimbal_result(); } -inline void Attitude::unsafe_arena_set_allocated_quaternion_north(::mavsdk::rpc::gimbal::Quaternion* value) { +inline void GetAttitudeResponse::unsafe_arena_set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.quaternion_north_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.gimbal_result_); } - _impl_.quaternion_north_ = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(value); + _impl_.gimbal_result_ = reinterpret_cast<::mavsdk::rpc::gimbal::GimbalResult*>(value); if (value != nullptr) { - _impl_._has_bits_[0] |= 0x00000008u; + _impl_._has_bits_[0] |= 0x00000001u; } else { - _impl_._has_bits_[0] &= ~0x00000008u; + _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.Attitude.quaternion_north) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.GetAttitudeResponse.gimbal_result) } -inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::release_quaternion_north() { +inline ::mavsdk::rpc::gimbal::GimbalResult* GetAttitudeResponse::release_gimbal_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] &= ~0x00000008u; - ::mavsdk::rpc::gimbal::Quaternion* released = _impl_.quaternion_north_; - _impl_.quaternion_north_ = nullptr; + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::gimbal::GimbalResult* released = _impl_.gimbal_result_; + _impl_.gimbal_result_ = nullptr; #ifdef PROTOBUF_FORCE_COPY_IN_RELEASE auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); released = ::google::protobuf::internal::DuplicateIfNonNull(released); @@ -5626,89 +7971,89 @@ inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::release_quaternion_north() { #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::unsafe_arena_release_quaternion_north() { +inline ::mavsdk::rpc::gimbal::GimbalResult* GetAttitudeResponse::unsafe_arena_release_gimbal_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.Attitude.quaternion_north) + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.GetAttitudeResponse.gimbal_result) - _impl_._has_bits_[0] &= ~0x00000008u; - ::mavsdk::rpc::gimbal::Quaternion* temp = _impl_.quaternion_north_; - _impl_.quaternion_north_ = nullptr; + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::gimbal::GimbalResult* temp = _impl_.gimbal_result_; + _impl_.gimbal_result_ = nullptr; return temp; } -inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::_internal_mutable_quaternion_north() { +inline ::mavsdk::rpc::gimbal::GimbalResult* GetAttitudeResponse::_internal_mutable_gimbal_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000008u; - if (_impl_.quaternion_north_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::Quaternion>(GetArena()); - _impl_.quaternion_north_ = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(p); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.gimbal_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::GimbalResult>(GetArena()); + _impl_.gimbal_result_ = reinterpret_cast<::mavsdk::rpc::gimbal::GimbalResult*>(p); } - return _impl_.quaternion_north_; + return _impl_.gimbal_result_; } -inline ::mavsdk::rpc::gimbal::Quaternion* Attitude::mutable_quaternion_north() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::gimbal::Quaternion* _msg = _internal_mutable_quaternion_north(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.Attitude.quaternion_north) +inline ::mavsdk::rpc::gimbal::GimbalResult* GetAttitudeResponse::mutable_gimbal_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::gimbal::GimbalResult* _msg = _internal_mutable_gimbal_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.GetAttitudeResponse.gimbal_result) return _msg; } -inline void Attitude::set_allocated_quaternion_north(::mavsdk::rpc::gimbal::Quaternion* value) { +inline void GetAttitudeResponse::set_allocated_gimbal_result(::mavsdk::rpc::gimbal::GimbalResult* value) { ::google::protobuf::Arena* message_arena = GetArena(); PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(_impl_.quaternion_north_); + delete reinterpret_cast<::mavsdk::rpc::gimbal::GimbalResult*>(_impl_.gimbal_result_); } if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(value)->GetArena(); + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::GimbalResult*>(value)->GetArena(); if (message_arena != submessage_arena) { value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); } - _impl_._has_bits_[0] |= 0x00000008u; + _impl_._has_bits_[0] |= 0x00000001u; } else { - _impl_._has_bits_[0] &= ~0x00000008u; + _impl_._has_bits_[0] &= ~0x00000001u; } - _impl_.quaternion_north_ = reinterpret_cast<::mavsdk::rpc::gimbal::Quaternion*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.Attitude.quaternion_north) + _impl_.gimbal_result_ = reinterpret_cast<::mavsdk::rpc::gimbal::GimbalResult*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.GetAttitudeResponse.gimbal_result) } -// .mavsdk.rpc.gimbal.AngularVelocityBody angular_velocity = 5; -inline bool Attitude::has_angular_velocity() const { - bool value = (_impl_._has_bits_[0] & 0x00000010u) != 0; - PROTOBUF_ASSUME(!value || _impl_.angular_velocity_ != nullptr); +// .mavsdk.rpc.gimbal.Attitude attitude = 2; +inline bool GetAttitudeResponse::has_attitude() const { + bool value = (_impl_._has_bits_[0] & 0x00000002u) != 0; + PROTOBUF_ASSUME(!value || _impl_.attitude_ != nullptr); return value; } -inline void Attitude::clear_angular_velocity() { +inline void GetAttitudeResponse::clear_attitude() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.angular_velocity_ != nullptr) _impl_.angular_velocity_->Clear(); - _impl_._has_bits_[0] &= ~0x00000010u; + if (_impl_.attitude_ != nullptr) _impl_.attitude_->Clear(); + _impl_._has_bits_[0] &= ~0x00000002u; } -inline const ::mavsdk::rpc::gimbal::AngularVelocityBody& Attitude::_internal_angular_velocity() const { +inline const ::mavsdk::rpc::gimbal::Attitude& GetAttitudeResponse::_internal_attitude() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::gimbal::AngularVelocityBody* p = _impl_.angular_velocity_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_AngularVelocityBody_default_instance_); + const ::mavsdk::rpc::gimbal::Attitude* p = _impl_.attitude_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_Attitude_default_instance_); } -inline const ::mavsdk::rpc::gimbal::AngularVelocityBody& Attitude::angular_velocity() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.Attitude.angular_velocity) - return _internal_angular_velocity(); +inline const ::mavsdk::rpc::gimbal::Attitude& GetAttitudeResponse::attitude() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.GetAttitudeResponse.attitude) + return _internal_attitude(); } -inline void Attitude::unsafe_arena_set_allocated_angular_velocity(::mavsdk::rpc::gimbal::AngularVelocityBody* value) { +inline void GetAttitudeResponse::unsafe_arena_set_allocated_attitude(::mavsdk::rpc::gimbal::Attitude* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.angular_velocity_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.attitude_); } - _impl_.angular_velocity_ = reinterpret_cast<::mavsdk::rpc::gimbal::AngularVelocityBody*>(value); + _impl_.attitude_ = reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(value); if (value != nullptr) { - _impl_._has_bits_[0] |= 0x00000010u; + _impl_._has_bits_[0] |= 0x00000002u; } else { - _impl_._has_bits_[0] &= ~0x00000010u; + _impl_._has_bits_[0] &= ~0x00000002u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.Attitude.angular_velocity) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.GetAttitudeResponse.attitude) } -inline ::mavsdk::rpc::gimbal::AngularVelocityBody* Attitude::release_angular_velocity() { +inline ::mavsdk::rpc::gimbal::Attitude* GetAttitudeResponse::release_attitude() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] &= ~0x00000010u; - ::mavsdk::rpc::gimbal::AngularVelocityBody* released = _impl_.angular_velocity_; - _impl_.angular_velocity_ = nullptr; + _impl_._has_bits_[0] &= ~0x00000002u; + ::mavsdk::rpc::gimbal::Attitude* released = _impl_.attitude_; + _impl_.attitude_ = nullptr; #ifdef PROTOBUF_FORCE_COPY_IN_RELEASE auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); released = ::google::protobuf::internal::DuplicateIfNonNull(released); @@ -5722,120 +8067,97 @@ inline ::mavsdk::rpc::gimbal::AngularVelocityBody* Attitude::release_angular_vel #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::gimbal::AngularVelocityBody* Attitude::unsafe_arena_release_angular_velocity() { +inline ::mavsdk::rpc::gimbal::Attitude* GetAttitudeResponse::unsafe_arena_release_attitude() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.Attitude.angular_velocity) + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.GetAttitudeResponse.attitude) - _impl_._has_bits_[0] &= ~0x00000010u; - ::mavsdk::rpc::gimbal::AngularVelocityBody* temp = _impl_.angular_velocity_; - _impl_.angular_velocity_ = nullptr; + _impl_._has_bits_[0] &= ~0x00000002u; + ::mavsdk::rpc::gimbal::Attitude* temp = _impl_.attitude_; + _impl_.attitude_ = nullptr; return temp; } -inline ::mavsdk::rpc::gimbal::AngularVelocityBody* Attitude::_internal_mutable_angular_velocity() { +inline ::mavsdk::rpc::gimbal::Attitude* GetAttitudeResponse::_internal_mutable_attitude() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_._has_bits_[0] |= 0x00000010u; - if (_impl_.angular_velocity_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::AngularVelocityBody>(GetArena()); - _impl_.angular_velocity_ = reinterpret_cast<::mavsdk::rpc::gimbal::AngularVelocityBody*>(p); + _impl_._has_bits_[0] |= 0x00000002u; + if (_impl_.attitude_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::Attitude>(GetArena()); + _impl_.attitude_ = reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(p); } - return _impl_.angular_velocity_; + return _impl_.attitude_; } -inline ::mavsdk::rpc::gimbal::AngularVelocityBody* Attitude::mutable_angular_velocity() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::gimbal::AngularVelocityBody* _msg = _internal_mutable_angular_velocity(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.Attitude.angular_velocity) +inline ::mavsdk::rpc::gimbal::Attitude* GetAttitudeResponse::mutable_attitude() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::gimbal::Attitude* _msg = _internal_mutable_attitude(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.GetAttitudeResponse.attitude) return _msg; } -inline void Attitude::set_allocated_angular_velocity(::mavsdk::rpc::gimbal::AngularVelocityBody* value) { +inline void GetAttitudeResponse::set_allocated_attitude(::mavsdk::rpc::gimbal::Attitude* value) { ::google::protobuf::Arena* message_arena = GetArena(); PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::gimbal::AngularVelocityBody*>(_impl_.angular_velocity_); + delete reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(_impl_.attitude_); } if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::AngularVelocityBody*>(value)->GetArena(); + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(value)->GetArena(); if (message_arena != submessage_arena) { value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); } - _impl_._has_bits_[0] |= 0x00000010u; + _impl_._has_bits_[0] |= 0x00000002u; } else { - _impl_._has_bits_[0] &= ~0x00000010u; + _impl_._has_bits_[0] &= ~0x00000002u; } - _impl_.angular_velocity_ = reinterpret_cast<::mavsdk::rpc::gimbal::AngularVelocityBody*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.Attitude.angular_velocity) -} - -// uint64 timestamp_us = 6; -inline void Attitude::clear_timestamp_us() { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - _impl_.timestamp_us_ = ::uint64_t{0u}; -} -inline ::uint64_t Attitude::timestamp_us() const { - // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.Attitude.timestamp_us) - return _internal_timestamp_us(); -} -inline void Attitude::set_timestamp_us(::uint64_t value) { - _internal_set_timestamp_us(value); - // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.Attitude.timestamp_us) -} -inline ::uint64_t Attitude::_internal_timestamp_us() const { - PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - return _impl_.timestamp_us_; -} -inline void Attitude::_internal_set_timestamp_us(::uint64_t value) { - PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - ; - _impl_.timestamp_us_ = value; + _impl_.attitude_ = reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.GetAttitudeResponse.attitude) } // ------------------------------------------------------------------- -// SubscribeAttitudeRequest +// SubscribeGimbalListRequest // ------------------------------------------------------------------- -// AttitudeResponse +// GimbalListResponse -// .mavsdk.rpc.gimbal.Attitude attitude = 1; -inline bool AttitudeResponse::has_attitude() const { +// .mavsdk.rpc.gimbal.GimbalList gimbal_list = 1; +inline bool GimbalListResponse::has_gimbal_list() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.attitude_ != nullptr); + PROTOBUF_ASSUME(!value || _impl_.gimbal_list_ != nullptr); return value; } -inline void AttitudeResponse::clear_attitude() { +inline void GimbalListResponse::clear_gimbal_list() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.attitude_ != nullptr) _impl_.attitude_->Clear(); + if (_impl_.gimbal_list_ != nullptr) _impl_.gimbal_list_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::gimbal::Attitude& AttitudeResponse::_internal_attitude() const { +inline const ::mavsdk::rpc::gimbal::GimbalList& GimbalListResponse::_internal_gimbal_list() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::gimbal::Attitude* p = _impl_.attitude_; - return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_Attitude_default_instance_); + const ::mavsdk::rpc::gimbal::GimbalList* p = _impl_.gimbal_list_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::gimbal::_GimbalList_default_instance_); } -inline const ::mavsdk::rpc::gimbal::Attitude& AttitudeResponse::attitude() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.AttitudeResponse.attitude) - return _internal_attitude(); +inline const ::mavsdk::rpc::gimbal::GimbalList& GimbalListResponse::gimbal_list() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.GimbalListResponse.gimbal_list) + return _internal_gimbal_list(); } -inline void AttitudeResponse::unsafe_arena_set_allocated_attitude(::mavsdk::rpc::gimbal::Attitude* value) { +inline void GimbalListResponse::unsafe_arena_set_allocated_gimbal_list(::mavsdk::rpc::gimbal::GimbalList* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.attitude_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.gimbal_list_); } - _impl_.attitude_ = reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(value); + _impl_.gimbal_list_ = reinterpret_cast<::mavsdk::rpc::gimbal::GimbalList*>(value); if (value != nullptr) { _impl_._has_bits_[0] |= 0x00000001u; } else { _impl_._has_bits_[0] &= ~0x00000001u; } - // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.AttitudeResponse.attitude) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.gimbal.GimbalListResponse.gimbal_list) } -inline ::mavsdk::rpc::gimbal::Attitude* AttitudeResponse::release_attitude() { +inline ::mavsdk::rpc::gimbal::GimbalList* GimbalListResponse::release_gimbal_list() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::gimbal::Attitude* released = _impl_.attitude_; - _impl_.attitude_ = nullptr; + ::mavsdk::rpc::gimbal::GimbalList* released = _impl_.gimbal_list_; + _impl_.gimbal_list_ = nullptr; #ifdef PROTOBUF_FORCE_COPY_IN_RELEASE auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); released = ::google::protobuf::internal::DuplicateIfNonNull(released); @@ -5849,38 +8171,38 @@ inline ::mavsdk::rpc::gimbal::Attitude* AttitudeResponse::release_attitude() { #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::gimbal::Attitude* AttitudeResponse::unsafe_arena_release_attitude() { +inline ::mavsdk::rpc::gimbal::GimbalList* GimbalListResponse::unsafe_arena_release_gimbal_list() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.AttitudeResponse.attitude) + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.GimbalListResponse.gimbal_list) _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::gimbal::Attitude* temp = _impl_.attitude_; - _impl_.attitude_ = nullptr; + ::mavsdk::rpc::gimbal::GimbalList* temp = _impl_.gimbal_list_; + _impl_.gimbal_list_ = nullptr; return temp; } -inline ::mavsdk::rpc::gimbal::Attitude* AttitudeResponse::_internal_mutable_attitude() { +inline ::mavsdk::rpc::gimbal::GimbalList* GimbalListResponse::_internal_mutable_gimbal_list() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.attitude_ == nullptr) { - auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::Attitude>(GetArena()); - _impl_.attitude_ = reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(p); + if (_impl_.gimbal_list_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::gimbal::GimbalList>(GetArena()); + _impl_.gimbal_list_ = reinterpret_cast<::mavsdk::rpc::gimbal::GimbalList*>(p); } - return _impl_.attitude_; + return _impl_.gimbal_list_; } -inline ::mavsdk::rpc::gimbal::Attitude* AttitudeResponse::mutable_attitude() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::gimbal::Attitude* _msg = _internal_mutable_attitude(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.AttitudeResponse.attitude) +inline ::mavsdk::rpc::gimbal::GimbalList* GimbalListResponse::mutable_gimbal_list() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::gimbal::GimbalList* _msg = _internal_mutable_gimbal_list(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.GimbalListResponse.gimbal_list) return _msg; } -inline void AttitudeResponse::set_allocated_attitude(::mavsdk::rpc::gimbal::Attitude* value) { +inline void GimbalListResponse::set_allocated_gimbal_list(::mavsdk::rpc::gimbal::GimbalList* value) { ::google::protobuf::Arena* message_arena = GetArena(); PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(_impl_.attitude_); + delete reinterpret_cast<::mavsdk::rpc::gimbal::GimbalList*>(_impl_.gimbal_list_); } if (value != nullptr) { - ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(value)->GetArena(); + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::gimbal::GimbalList*>(value)->GetArena(); if (message_arena != submessage_arena) { value = ::google::protobuf::internal::GetOwnedMessage(message_arena, value, submessage_arena); } @@ -5889,15 +8211,323 @@ inline void AttitudeResponse::set_allocated_attitude(::mavsdk::rpc::gimbal::Atti _impl_._has_bits_[0] &= ~0x00000001u; } - _impl_.attitude_ = reinterpret_cast<::mavsdk::rpc::gimbal::Attitude*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.AttitudeResponse.attitude) + _impl_.gimbal_list_ = reinterpret_cast<::mavsdk::rpc::gimbal::GimbalList*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.GimbalListResponse.gimbal_list) +} + +// ------------------------------------------------------------------- + +// GimbalItem + +// int32 gimbal_id = 1; +inline void GimbalItem::clear_gimbal_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.gimbal_id_ = 0; +} +inline ::int32_t GimbalItem::gimbal_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.GimbalItem.gimbal_id) + return _internal_gimbal_id(); +} +inline void GimbalItem::set_gimbal_id(::int32_t value) { + _internal_set_gimbal_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.GimbalItem.gimbal_id) +} +inline ::int32_t GimbalItem::_internal_gimbal_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.gimbal_id_; +} +inline void GimbalItem::_internal_set_gimbal_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.gimbal_id_ = value; +} + +// string vendor_name = 2; +inline void GimbalItem::clear_vendor_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.vendor_name_.ClearToEmpty(); +} +inline const std::string& GimbalItem::vendor_name() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.GimbalItem.vendor_name) + return _internal_vendor_name(); +} +template +inline PROTOBUF_ALWAYS_INLINE void GimbalItem::set_vendor_name(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.vendor_name_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.GimbalItem.vendor_name) +} +inline std::string* GimbalItem::mutable_vendor_name() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_vendor_name(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.GimbalItem.vendor_name) + return _s; +} +inline const std::string& GimbalItem::_internal_vendor_name() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.vendor_name_.Get(); +} +inline void GimbalItem::_internal_set_vendor_name(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.vendor_name_.Set(value, GetArena()); +} +inline std::string* GimbalItem::_internal_mutable_vendor_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.vendor_name_.Mutable( GetArena()); +} +inline std::string* GimbalItem::release_vendor_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.GimbalItem.vendor_name) + return _impl_.vendor_name_.Release(); +} +inline void GimbalItem::set_allocated_vendor_name(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.vendor_name_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.vendor_name_.IsDefault()) { + _impl_.vendor_name_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.GimbalItem.vendor_name) +} + +// string model_name = 3; +inline void GimbalItem::clear_model_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.model_name_.ClearToEmpty(); +} +inline const std::string& GimbalItem::model_name() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.GimbalItem.model_name) + return _internal_model_name(); +} +template +inline PROTOBUF_ALWAYS_INLINE void GimbalItem::set_model_name(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.model_name_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.GimbalItem.model_name) +} +inline std::string* GimbalItem::mutable_model_name() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_model_name(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.GimbalItem.model_name) + return _s; +} +inline const std::string& GimbalItem::_internal_model_name() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.model_name_.Get(); +} +inline void GimbalItem::_internal_set_model_name(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.model_name_.Set(value, GetArena()); +} +inline std::string* GimbalItem::_internal_mutable_model_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.model_name_.Mutable( GetArena()); +} +inline std::string* GimbalItem::release_model_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.GimbalItem.model_name) + return _impl_.model_name_.Release(); +} +inline void GimbalItem::set_allocated_model_name(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.model_name_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.model_name_.IsDefault()) { + _impl_.model_name_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.GimbalItem.model_name) +} + +// string custom_name = 4; +inline void GimbalItem::clear_custom_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.custom_name_.ClearToEmpty(); +} +inline const std::string& GimbalItem::custom_name() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.GimbalItem.custom_name) + return _internal_custom_name(); +} +template +inline PROTOBUF_ALWAYS_INLINE void GimbalItem::set_custom_name(Arg_&& arg, + Args_... args) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.custom_name_.Set(static_cast(arg), args..., GetArena()); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.GimbalItem.custom_name) +} +inline std::string* GimbalItem::mutable_custom_name() ABSL_ATTRIBUTE_LIFETIME_BOUND { + std::string* _s = _internal_mutable_custom_name(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.GimbalItem.custom_name) + return _s; +} +inline const std::string& GimbalItem::_internal_custom_name() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.custom_name_.Get(); +} +inline void GimbalItem::_internal_set_custom_name(const std::string& value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.custom_name_.Set(value, GetArena()); +} +inline std::string* GimbalItem::_internal_mutable_custom_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + return _impl_.custom_name_.Mutable( GetArena()); +} +inline std::string* GimbalItem::release_custom_name() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.gimbal.GimbalItem.custom_name) + return _impl_.custom_name_.Release(); +} +inline void GimbalItem::set_allocated_custom_name(std::string* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.custom_name_.SetAllocated(value, GetArena()); + #ifdef PROTOBUF_FORCE_COPY_DEFAULT_STRING + if (_impl_.custom_name_.IsDefault()) { + _impl_.custom_name_.Set("", GetArena()); + } + #endif // PROTOBUF_FORCE_COPY_DEFAULT_STRING + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.gimbal.GimbalItem.custom_name) +} + +// int32 gimbal_manager_component_id = 5; +inline void GimbalItem::clear_gimbal_manager_component_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.gimbal_manager_component_id_ = 0; +} +inline ::int32_t GimbalItem::gimbal_manager_component_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.GimbalItem.gimbal_manager_component_id) + return _internal_gimbal_manager_component_id(); +} +inline void GimbalItem::set_gimbal_manager_component_id(::int32_t value) { + _internal_set_gimbal_manager_component_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.GimbalItem.gimbal_manager_component_id) +} +inline ::int32_t GimbalItem::_internal_gimbal_manager_component_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.gimbal_manager_component_id_; +} +inline void GimbalItem::_internal_set_gimbal_manager_component_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.gimbal_manager_component_id_ = value; +} + +// int32 gimbal_device_id = 6; +inline void GimbalItem::clear_gimbal_device_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.gimbal_device_id_ = 0; +} +inline ::int32_t GimbalItem::gimbal_device_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.GimbalItem.gimbal_device_id) + return _internal_gimbal_device_id(); +} +inline void GimbalItem::set_gimbal_device_id(::int32_t value) { + _internal_set_gimbal_device_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.GimbalItem.gimbal_device_id) +} +inline ::int32_t GimbalItem::_internal_gimbal_device_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.gimbal_device_id_; +} +inline void GimbalItem::_internal_set_gimbal_device_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.gimbal_device_id_ = value; +} + +// ------------------------------------------------------------------- + +// GimbalList + +// repeated .mavsdk.rpc.gimbal.GimbalItem gimbals = 1; +inline int GimbalList::_internal_gimbals_size() const { + return _internal_gimbals().size(); +} +inline int GimbalList::gimbals_size() const { + return _internal_gimbals_size(); +} +inline void GimbalList::clear_gimbals() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.gimbals_.Clear(); +} +inline ::mavsdk::rpc::gimbal::GimbalItem* GimbalList::mutable_gimbals(int index) + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.gimbal.GimbalList.gimbals) + return _internal_mutable_gimbals()->Mutable(index); +} +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::gimbal::GimbalItem>* GimbalList::mutable_gimbals() + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_mutable_list:mavsdk.rpc.gimbal.GimbalList.gimbals) + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + return _internal_mutable_gimbals(); +} +inline const ::mavsdk::rpc::gimbal::GimbalItem& GimbalList::gimbals(int index) const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.GimbalList.gimbals) + return _internal_gimbals().Get(index); +} +inline ::mavsdk::rpc::gimbal::GimbalItem* GimbalList::add_gimbals() ABSL_ATTRIBUTE_LIFETIME_BOUND { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ::mavsdk::rpc::gimbal::GimbalItem* _add = _internal_mutable_gimbals()->Add(); + // @@protoc_insertion_point(field_add:mavsdk.rpc.gimbal.GimbalList.gimbals) + return _add; +} +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::gimbal::GimbalItem>& GimbalList::gimbals() const + ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_list:mavsdk.rpc.gimbal.GimbalList.gimbals) + return _internal_gimbals(); +} +inline const ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::gimbal::GimbalItem>& +GimbalList::_internal_gimbals() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.gimbals_; +} +inline ::google::protobuf::RepeatedPtrField<::mavsdk::rpc::gimbal::GimbalItem>* +GimbalList::_internal_mutable_gimbals() { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return &_impl_.gimbals_; } // ------------------------------------------------------------------- // ControlStatus -// .mavsdk.rpc.gimbal.ControlMode control_mode = 1; +// int32 gimbal_id = 1; +inline void ControlStatus::clear_gimbal_id() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.gimbal_id_ = 0; +} +inline ::int32_t ControlStatus::gimbal_id() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.gimbal.ControlStatus.gimbal_id) + return _internal_gimbal_id(); +} +inline void ControlStatus::set_gimbal_id(::int32_t value) { + _internal_set_gimbal_id(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.gimbal.ControlStatus.gimbal_id) +} +inline ::int32_t ControlStatus::_internal_gimbal_id() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.gimbal_id_; +} +inline void ControlStatus::_internal_set_gimbal_id(::int32_t value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.gimbal_id_ = value; +} + +// .mavsdk.rpc.gimbal.ControlMode control_mode = 2; inline void ControlStatus::clear_control_mode() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.control_mode_ = 0; @@ -5920,7 +8550,7 @@ inline void ControlStatus::_internal_set_control_mode(::mavsdk::rpc::gimbal::Con _impl_.control_mode_ = value; } -// int32 sysid_primary_control = 2; +// int32 sysid_primary_control = 3; inline void ControlStatus::clear_sysid_primary_control() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.sysid_primary_control_ = 0; @@ -5943,7 +8573,7 @@ inline void ControlStatus::_internal_set_sysid_primary_control(::int32_t value) _impl_.sysid_primary_control_ = value; } -// int32 compid_primary_control = 3; +// int32 compid_primary_control = 4; inline void ControlStatus::clear_compid_primary_control() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.compid_primary_control_ = 0; @@ -5966,7 +8596,7 @@ inline void ControlStatus::_internal_set_compid_primary_control(::int32_t value) _impl_.compid_primary_control_ = value; } -// int32 sysid_secondary_control = 4; +// int32 sysid_secondary_control = 5; inline void ControlStatus::clear_sysid_secondary_control() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.sysid_secondary_control_ = 0; @@ -5989,7 +8619,7 @@ inline void ControlStatus::_internal_set_sysid_secondary_control(::int32_t value _impl_.sysid_secondary_control_ = value; } -// int32 compid_secondary_control = 5; +// int32 compid_secondary_control = 6; inline void ControlStatus::clear_compid_secondary_control() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_.compid_secondary_control_ = 0; diff --git a/src/mavsdk_server/src/plugins/gimbal/gimbal_service_impl.h b/src/mavsdk_server/src/plugins/gimbal/gimbal_service_impl.h index 374abe7d82..692550376b 100644 --- a/src/mavsdk_server/src/plugins/gimbal/gimbal_service_impl.h +++ b/src/mavsdk_server/src/plugins/gimbal/gimbal_service_impl.h @@ -221,6 +221,8 @@ class GimbalServiceImpl final : public rpc::gimbal::GimbalService::Service { { auto rpc_obj = std::make_unique(); + rpc_obj->set_gimbal_id(attitude.gimbal_id); + rpc_obj->set_allocated_euler_angle_forward( translateToRpcEulerAngle(attitude.euler_angle_forward).release()); @@ -245,6 +247,8 @@ class GimbalServiceImpl final : public rpc::gimbal::GimbalService::Service { { mavsdk::Gimbal::Attitude obj; + obj.gimbal_id = attitude.gimbal_id(); + obj.euler_angle_forward = translateFromRpcEulerAngle(attitude.euler_angle_forward()); obj.quaternion_forward = translateFromRpcQuaternion(attitude.quaternion_forward()); @@ -260,11 +264,79 @@ class GimbalServiceImpl final : public rpc::gimbal::GimbalService::Service { return obj; } + static std::unique_ptr + translateToRpcGimbalItem(const mavsdk::Gimbal::GimbalItem& gimbal_item) + { + auto rpc_obj = std::make_unique(); + + rpc_obj->set_gimbal_id(gimbal_item.gimbal_id); + + rpc_obj->set_vendor_name(gimbal_item.vendor_name); + + rpc_obj->set_model_name(gimbal_item.model_name); + + rpc_obj->set_custom_name(gimbal_item.custom_name); + + rpc_obj->set_gimbal_manager_component_id(gimbal_item.gimbal_manager_component_id); + + rpc_obj->set_gimbal_device_id(gimbal_item.gimbal_device_id); + + return rpc_obj; + } + + static mavsdk::Gimbal::GimbalItem + translateFromRpcGimbalItem(const rpc::gimbal::GimbalItem& gimbal_item) + { + mavsdk::Gimbal::GimbalItem obj; + + obj.gimbal_id = gimbal_item.gimbal_id(); + + obj.vendor_name = gimbal_item.vendor_name(); + + obj.model_name = gimbal_item.model_name(); + + obj.custom_name = gimbal_item.custom_name(); + + obj.gimbal_manager_component_id = gimbal_item.gimbal_manager_component_id(); + + obj.gimbal_device_id = gimbal_item.gimbal_device_id(); + + return obj; + } + + static std::unique_ptr + translateToRpcGimbalList(const mavsdk::Gimbal::GimbalList& gimbal_list) + { + auto rpc_obj = std::make_unique(); + + for (const auto& elem : gimbal_list.gimbals) { + auto* ptr = rpc_obj->add_gimbals(); + ptr->CopyFrom(*translateToRpcGimbalItem(elem).release()); + } + + return rpc_obj; + } + + static mavsdk::Gimbal::GimbalList + translateFromRpcGimbalList(const rpc::gimbal::GimbalList& gimbal_list) + { + mavsdk::Gimbal::GimbalList obj; + + for (const auto& elem : gimbal_list.gimbals()) { + obj.gimbals.push_back( + translateFromRpcGimbalItem(static_cast(elem))); + } + + return obj; + } + static std::unique_ptr translateToRpcControlStatus(const mavsdk::Gimbal::ControlStatus& control_status) { auto rpc_obj = std::make_unique(); + rpc_obj->set_gimbal_id(control_status.gimbal_id); + rpc_obj->set_control_mode(translateToRpcControlMode(control_status.control_mode)); rpc_obj->set_sysid_primary_control(control_status.sysid_primary_control); @@ -283,6 +355,8 @@ class GimbalServiceImpl final : public rpc::gimbal::GimbalService::Service { { mavsdk::Gimbal::ControlStatus obj; + obj.gimbal_id = control_status.gimbal_id(); + obj.control_mode = translateFromRpcControlMode(control_status.control_mode()); obj.sysid_primary_control = control_status.sysid_primary_control(); @@ -364,6 +438,7 @@ class GimbalServiceImpl final : public rpc::gimbal::GimbalService::Service { } auto result = _lazy_plugin.maybe_plugin()->set_angles( + request->gimbal_id(), request->roll_deg(), request->pitch_deg(), request->yaw_deg(), @@ -397,6 +472,7 @@ class GimbalServiceImpl final : public rpc::gimbal::GimbalService::Service { } auto result = _lazy_plugin.maybe_plugin()->set_angular_rates( + request->gimbal_id(), request->roll_rate_deg_s(), request->pitch_rate_deg_s(), request->yaw_rate_deg_s(), @@ -430,7 +506,10 @@ class GimbalServiceImpl final : public rpc::gimbal::GimbalService::Service { } auto result = _lazy_plugin.maybe_plugin()->set_roi_location( - request->latitude_deg(), request->longitude_deg(), request->altitude_m()); + request->gimbal_id(), + request->latitude_deg(), + request->longitude_deg(), + request->altitude_m()); if (response != nullptr) { fillResponseWithResult(response, result); @@ -459,7 +538,7 @@ class GimbalServiceImpl final : public rpc::gimbal::GimbalService::Service { } auto result = _lazy_plugin.maybe_plugin()->take_control( - translateFromRpcControlMode(request->control_mode())); + request->gimbal_id(), translateFromRpcControlMode(request->control_mode())); if (response != nullptr) { fillResponseWithResult(response, result); @@ -470,7 +549,7 @@ class GimbalServiceImpl final : public rpc::gimbal::GimbalService::Service { grpc::Status ReleaseControl( grpc::ServerContext* /* context */, - const rpc::gimbal::ReleaseControlRequest* /* request */, + const rpc::gimbal::ReleaseControlRequest* request, rpc::gimbal::ReleaseControlResponse* response) override { if (_lazy_plugin.maybe_plugin() == nullptr) { @@ -482,7 +561,12 @@ class GimbalServiceImpl final : public rpc::gimbal::GimbalService::Service { return grpc::Status::OK; } - auto result = _lazy_plugin.maybe_plugin()->release_control(); + if (request == nullptr) { + LogWarn() << "ReleaseControl sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->release_control(request->gimbal_id()); if (response != nullptr) { fillResponseWithResult(response, result); @@ -491,10 +575,52 @@ class GimbalServiceImpl final : public rpc::gimbal::GimbalService::Service { return grpc::Status::OK; } - grpc::Status SubscribeControl( + grpc::Status SubscribeGimbalList( + grpc::ServerContext* /* context */, + const mavsdk::rpc::gimbal::SubscribeGimbalListRequest* /* request */, + grpc::ServerWriter* writer) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + return grpc::Status::OK; + } + + auto stream_closed_promise = std::make_shared>(); + auto stream_closed_future = stream_closed_promise->get_future(); + register_stream_stop_promise(stream_closed_promise); + + auto is_finished = std::make_shared(false); + auto subscribe_mutex = std::make_shared(); + + const mavsdk::Gimbal::GimbalListHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_gimbal_list( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const mavsdk::Gimbal::GimbalList gimbal_list) { + rpc::gimbal::GimbalListResponse rpc_response; + + rpc_response.set_allocated_gimbal_list( + translateToRpcGimbalList(gimbal_list).release()); + + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_gimbal_list(handle); + + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); + + stream_closed_future.wait(); + std::unique_lock lock(*subscribe_mutex); + *is_finished = true; + + return grpc::Status::OK; + } + + grpc::Status SubscribeControlStatus( grpc::ServerContext* /* context */, - const mavsdk::rpc::gimbal::SubscribeControlRequest* /* request */, - grpc::ServerWriter* writer) override + const mavsdk::rpc::gimbal::SubscribeControlStatusRequest* /* request */, + grpc::ServerWriter* writer) override { if (_lazy_plugin.maybe_plugin() == nullptr) { return grpc::Status::OK; @@ -507,23 +633,24 @@ class GimbalServiceImpl final : public rpc::gimbal::GimbalService::Service { auto is_finished = std::make_shared(false); auto subscribe_mutex = std::make_shared(); - const mavsdk::Gimbal::ControlHandle handle = _lazy_plugin.maybe_plugin()->subscribe_control( - [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( - const mavsdk::Gimbal::ControlStatus control) { - rpc::gimbal::ControlResponse rpc_response; + const mavsdk::Gimbal::ControlStatusHandle handle = + _lazy_plugin.maybe_plugin()->subscribe_control_status( + [this, &writer, &stream_closed_promise, is_finished, subscribe_mutex, &handle]( + const mavsdk::Gimbal::ControlStatus control_status) { + rpc::gimbal::ControlStatusResponse rpc_response; - rpc_response.set_allocated_control_status( - translateToRpcControlStatus(control).release()); + rpc_response.set_allocated_control_status( + translateToRpcControlStatus(control_status).release()); - std::unique_lock lock(*subscribe_mutex); - if (!*is_finished && !writer->Write(rpc_response)) { - _lazy_plugin.maybe_plugin()->unsubscribe_control(handle); + std::unique_lock lock(*subscribe_mutex); + if (!*is_finished && !writer->Write(rpc_response)) { + _lazy_plugin.maybe_plugin()->unsubscribe_control_status(handle); - *is_finished = true; - unregister_stream_stop_promise(stream_closed_promise); - stream_closed_promise->set_value(); - } - }); + *is_finished = true; + unregister_stream_stop_promise(stream_closed_promise); + stream_closed_promise->set_value(); + } + }); stream_closed_future.wait(); std::unique_lock lock(*subscribe_mutex); @@ -532,6 +659,37 @@ class GimbalServiceImpl final : public rpc::gimbal::GimbalService::Service { return grpc::Status::OK; } + grpc::Status GetControlStatus( + grpc::ServerContext* /* context */, + const rpc::gimbal::GetControlStatusRequest* request, + rpc::gimbal::GetControlStatusResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + auto result = mavsdk::Gimbal::Result::NoSystem; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "GetControlStatus sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->get_control_status(request->gimbal_id()); + + if (response != nullptr) { + fillResponseWithResult(response, result.first); + + response->set_allocated_control_status( + translateToRpcControlStatus(result.second).release()); + } + + return grpc::Status::OK; + } + grpc::Status SubscribeAttitude( grpc::ServerContext* /* context */, const mavsdk::rpc::gimbal::SubscribeAttitudeRequest* /* request */, @@ -573,6 +731,36 @@ class GimbalServiceImpl final : public rpc::gimbal::GimbalService::Service { return grpc::Status::OK; } + grpc::Status GetAttitude( + grpc::ServerContext* /* context */, + const rpc::gimbal::GetAttitudeRequest* request, + rpc::gimbal::GetAttitudeResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + auto result = mavsdk::Gimbal::Result::NoSystem; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "GetAttitude sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->get_attitude(request->gimbal_id()); + + if (response != nullptr) { + fillResponseWithResult(response, result.first); + + response->set_allocated_attitude(translateToRpcAttitude(result.second).release()); + } + + return grpc::Status::OK; + } + void stop() { _stopped.store(true);