From 778bacab186e5b3c4d5402a011b6c9beae0a7cd3 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sat, 26 Oct 2024 22:14:51 +1300 Subject: [PATCH] camera: implement params changing on camera side --- proto | 2 +- src/integration_tests/CMakeLists.txt | 6 - src/integration_tests/camera_capture_info.cpp | 39 - src/integration_tests/camera_mode.cpp | 104 --- .../camera_reset_settings.cpp | 26 - src/integration_tests/camera_settings.cpp | 363 --------- src/integration_tests/camera_take_photo.cpp | 103 --- src/integration_tests/camera_test_helpers.cpp | 25 - src/integration_tests/camera_test_helpers.h | 12 - src/mavsdk/core/mavlink_parameter_client.cpp | 12 +- src/mavsdk/core/mavlink_parameter_server.cpp | 65 +- src/mavsdk/core/mavlink_parameter_server.h | 7 +- .../core/mavlink_parameter_subscription.cpp | 49 +- .../core/mavlink_parameter_subscription.h | 78 +- src/mavsdk/core/param_value.cpp | 25 +- src/mavsdk/core/system_impl.h | 4 +- .../plugins/camera/camera_definition.cpp | 1 - src/mavsdk/plugins/camera/camera_impl.cpp | 145 +++- src/mavsdk/plugins/camera/camera_impl.h | 5 +- .../plugins/param_server/param_server.h | 13 + .../plugins/param_server/param_server.cpp | 5 + .../param_server/param_server_impl.cpp | 63 +- .../plugins/param_server/param_server_impl.h | 2 + .../src/generated/camera/camera.pb.cc | 56 +- .../src/generated/camera/camera.pb.h | 90 +-- .../param_server/param_server.grpc.pb.cc | 80 +- .../param_server/param_server.grpc.pb.h | 357 ++++++--- .../generated/param_server/param_server.pb.cc | 724 ++++++++++++++---- .../generated/param_server/param_server.pb.h | 539 ++++++++++++- .../param_server/param_server_service_impl.h | 30 + src/system_tests/CMakeLists.txt | 2 +- src/system_tests/camera_definition.cpp | 101 --- src/system_tests/camera_settings.cpp | 223 ++++++ 33 files changed, 2071 insertions(+), 1285 deletions(-) delete mode 100644 src/integration_tests/camera_capture_info.cpp delete mode 100644 src/integration_tests/camera_mode.cpp delete mode 100644 src/integration_tests/camera_reset_settings.cpp delete mode 100644 src/integration_tests/camera_settings.cpp delete mode 100644 src/integration_tests/camera_take_photo.cpp delete mode 100644 src/integration_tests/camera_test_helpers.cpp delete mode 100644 src/integration_tests/camera_test_helpers.h delete mode 100644 src/system_tests/camera_definition.cpp create mode 100644 src/system_tests/camera_settings.cpp diff --git a/proto b/proto index 329fbd9dbe..82fb558e62 160000 --- a/proto +++ b/proto @@ -1 +1 @@ -Subproject commit 329fbd9dbe4a48736582ce2aa1c5bf46dcb3f46e +Subproject commit 82fb558e621f76455086a6f1a7780e0703a4c597 diff --git a/src/integration_tests/CMakeLists.txt b/src/integration_tests/CMakeLists.txt index b7f2f78db1..a6234b9e31 100644 --- a/src/integration_tests/CMakeLists.txt +++ b/src/integration_tests/CMakeLists.txt @@ -11,14 +11,8 @@ add_executable(integration_tests_runner action_goto.cpp action_hold.cpp calibration.cpp - camera_capture_info.cpp - camera_mode.cpp - camera_settings.cpp camera_status.cpp - camera_take_photo.cpp camera_take_photo_interval.cpp - camera_reset_settings.cpp - camera_test_helpers.cpp connection.cpp follow_me.cpp geofence.cpp diff --git a/src/integration_tests/camera_capture_info.cpp b/src/integration_tests/camera_capture_info.cpp deleted file mode 100644 index 264f30e049..0000000000 --- a/src/integration_tests/camera_capture_info.cpp +++ /dev/null @@ -1,39 +0,0 @@ -#include "integration_test_helper.h" -#include "mavsdk.h" -#include -#include -#include -#include -#include "plugins/camera/camera.h" - -using namespace mavsdk; - -TEST(CameraTest, CaptureInfo) -{ - Mavsdk mavsdk{Mavsdk::Configuration{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_camera()); - auto camera = Camera{system}; - - std::this_thread::sleep_for(std::chrono::seconds(2)); - - EXPECT_EQ(camera.take_photo(), Camera::Result::Success); - - bool received_capture_info = false; - camera.subscribe_capture_info([&received_capture_info](Camera::CaptureInfo capture_info) { - received_capture_info = true; - LogInfo() << capture_info; - }); - - std::this_thread::sleep_for(std::chrono::seconds(5)); - EXPECT_TRUE(received_capture_info); -} diff --git a/src/integration_tests/camera_mode.cpp b/src/integration_tests/camera_mode.cpp deleted file mode 100644 index 1fe6a111d8..0000000000 --- a/src/integration_tests/camera_mode.cpp +++ /dev/null @@ -1,104 +0,0 @@ -#include -#include -#include "integration_test_helper.h" -#include "mavsdk.h" -#include "system.h" -#include "camera_test_helpers.h" - -using namespace mavsdk; - -TEST(CameraTest, SetModeSync) -{ - Mavsdk mavsdk{Mavsdk::Configuration{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)); - - auto system = mavsdk.systems().at(0); - ASSERT_TRUE(system->has_camera()); - auto camera = std::make_shared(system); - - bool received_mode_change = false; - Camera::Mode last_mode = Camera::Mode::Unknown; - - camera->subscribe_mode([&received_mode_change, &last_mode](Camera::Mode mode) { - LogInfo() << "Got mode: " << int(mode); - received_mode_change = true; - last_mode = mode; - }); - - std::vector modes_to_test; - modes_to_test.push_back(Camera::Mode::Photo); - modes_to_test.push_back(Camera::Mode::Video); - modes_to_test.push_back(Camera::Mode::Photo); - modes_to_test.push_back(Camera::Mode::Video); - - for (auto mode : modes_to_test) { - auto result = camera->set_mode(mode); - EXPECT_EQ(result, Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::milliseconds(500)); - EXPECT_TRUE(received_mode_change); - EXPECT_EQ(last_mode, mode); - received_mode_change = false; - } -} - -TEST(CameraTest, SetModeAsync) -{ - Mavsdk mavsdk{Mavsdk::Configuration{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)); - - auto system = mavsdk.systems().at(0); - ASSERT_TRUE(system->has_camera()); - auto camera = std::make_shared(system); - - EXPECT_EQ(camera->set_mode(Camera::Mode::Photo), Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(2)); - Camera::Mode new_mode = camera->mode(); - EXPECT_EQ(new_mode, Camera::Mode::Photo); - std::this_thread::sleep_for(std::chrono::seconds(2)); - - EXPECT_EQ(camera->set_mode(Camera::Mode::Video), Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(2)); - new_mode = camera->mode(); - EXPECT_EQ(new_mode, Camera::Mode::Video); - std::this_thread::sleep_for(std::chrono::seconds(2)); - - EXPECT_EQ(camera->set_mode(Camera::Mode::Photo), Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(2)); - new_mode = camera->mode(); - EXPECT_EQ(new_mode, Camera::Mode::Photo); - std::this_thread::sleep_for(std::chrono::seconds(2)); - - EXPECT_EQ(camera->set_mode(Camera::Mode::Photo), Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(2)); - new_mode = camera->mode(); - EXPECT_EQ(new_mode, Camera::Mode::Photo); - std::this_thread::sleep_for(std::chrono::seconds(2)); - - EXPECT_EQ(camera->set_mode(Camera::Mode::Video), Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(2)); - new_mode = camera->mode(); - EXPECT_EQ(new_mode, Camera::Mode::Video); - std::this_thread::sleep_for(std::chrono::seconds(2)); - - EXPECT_EQ(camera->set_mode(Camera::Mode::Video), Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(2)); - new_mode = camera->mode(); - EXPECT_EQ(new_mode, Camera::Mode::Video); - std::this_thread::sleep_for(std::chrono::seconds(2)); - - EXPECT_EQ(camera->set_mode(Camera::Mode::Video), Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(2)); - new_mode = camera->mode(); - EXPECT_EQ(new_mode, Camera::Mode::Video); - std::this_thread::sleep_for(std::chrono::seconds(2)); -} diff --git a/src/integration_tests/camera_reset_settings.cpp b/src/integration_tests/camera_reset_settings.cpp deleted file mode 100644 index a5becaaeff..0000000000 --- a/src/integration_tests/camera_reset_settings.cpp +++ /dev/null @@ -1,26 +0,0 @@ -#include "integration_test_helper.h" -#include "mavsdk.h" -#include -#include -#include -#include "plugins/camera/camera.h" - -using namespace mavsdk; - -TEST(CameraTest, ResetSettings) -{ - Mavsdk mavsdk{Mavsdk::Configuration{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)); - - auto system = mavsdk.systems().at(0); - ASSERT_TRUE(system->has_camera()); - - auto camera = std::make_shared(system); - - EXPECT_EQ(Camera::Result::Success, camera->reset_settings()); -} diff --git a/src/integration_tests/camera_settings.cpp b/src/integration_tests/camera_settings.cpp deleted file mode 100644 index d0516df5c4..0000000000 --- a/src/integration_tests/camera_settings.cpp +++ /dev/null @@ -1,363 +0,0 @@ -#include -#include -#include -#include -#include -#include "mavsdk.h" -#include "system.h" -#include "integration_test_helper.h" -#include "camera_test_helpers.h" -#include "unused.h" - -using namespace mavsdk; - -// To run specific tests for Yuneec cameras. -const static bool is_e90 = false; -const static bool is_e50 = false; -const static bool is_et = false; - -void contains_num_options( - const std::vector& settings, std::string setting_id, unsigned num) -{ - const auto it = - std::find_if(settings.begin(), settings.end(), [&setting_id](Camera::SettingOptions elem) { - return elem.setting_id == setting_id; - }); - const bool found = it != settings.end(); - if (num > 0) { - EXPECT_TRUE(found); - if (found) { - EXPECT_EQ(it->options.size(), num); - } - } else { - EXPECT_FALSE(found); - } -} - -TEST(CameraTest, ShowSettingsAndOptions) -{ - Mavsdk mavsdk{Mavsdk::Configuration{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)); - - auto system = mavsdk.systems().at(0); - ASSERT_TRUE(system->has_camera()); - auto camera = std::make_shared(system); - - // Wait for download to happen. - std::this_thread::sleep_for(std::chrono::seconds(2)); - - if (is_e90 || is_e50 || is_et) { - // Set to photo mode - EXPECT_EQ(camera->set_mode(Camera::Mode::Photo), Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(2)); - - auto settings = camera->possible_setting_options(); - EXPECT_GT(settings.size(), 0); - - LogDebug() << "Possible settings in photo mode: "; - for (auto setting : settings) { - LogDebug() << "- " << setting; - } - - if (is_e90) { - EXPECT_EQ(settings.size(), 10); - } else if (is_e50) { - EXPECT_EQ(settings.size(), 6); - } else if (is_et) { - EXPECT_EQ(settings.size(), 5); - } - - EXPECT_EQ(camera->set_mode(Camera::Mode::Video), Camera::Result::Success); - - std::this_thread::sleep_for(std::chrono::seconds(2)); - - settings = camera->possible_setting_options(); - EXPECT_GT(settings.size(), 0); - - LogDebug() << "Possible settings in video mode: "; - for (auto setting : settings) { - LogDebug() << "-" << setting; - } - - if (is_e90) { - EXPECT_EQ(settings.size(), 8); - } else if (is_e50) { - EXPECT_EQ(settings.size(), 5); - } else if (is_et) { - EXPECT_EQ(settings.size(), 5); - } - - if (is_e90) { - // Try something that is specific to the camera mode. - contains_num_options(settings, "CAM_VIDRES", 32); - } else if (is_e50) { - // Try something that is specific to the camera mode. - contains_num_options(settings, "CAM_VIDRES", 12); - } - - if (is_e90) { - // This param is not applicable, so we should get an empty vector back. - contains_num_options(settings, "CAM_PHOTOQUAL", 0); - } - - // The same should happen with a param that does not exist at all. - contains_num_options(settings, "CAM_BLABLA", 0); - - EXPECT_EQ(camera->set_mode(Camera::Mode::Photo), Camera::Result::Success); - - if (is_e90) { - // Try something that is specific to the camera mode. - contains_num_options(settings, "CAM_PHOTOQUAL", 4); - } - - // This param is not applicable, so we should get an empty vector back. - contains_num_options(settings, "CAM_VIDRES", 0); - - // The same should happen with a param that does not exist at all. - contains_num_options(settings, "CAM_BLABLA", 0); - } -} - -TEST(CameraTest, SetSettings) -{ - Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; - - ConnectionResult connection_ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); - ASSERT_EQ(connection_ret, ConnectionResult::Success); - - // Wait for system to connect via heartbeat. - std::this_thread::sleep_for(std::chrono::seconds(2)); - - auto system = mavsdk.systems().at(0); - ASSERT_TRUE(system->has_camera()); - auto camera = std::make_shared(system); - - // We need to wait for the camera definition to be ready - // because we don't have a check yet. - std::this_thread::sleep_for(std::chrono::seconds(2)); - - EXPECT_EQ(camera->set_mode(Camera::Mode::Photo), Camera::Result::Success); - - // Try setting garbage first - EXPECT_EQ(set_setting(camera, "DOES_NOT", "EXIST"), Camera::Result::Error); - - if (is_e90) { - std::string value_set; - EXPECT_EQ(set_setting(camera, "CAM_PHOTOQUAL", "1"), Camera::Result::Success); - EXPECT_EQ(get_setting(camera, "CAM_PHOTOQUAL", value_set), Camera::Result::Success); - EXPECT_STREQ("1", value_set.c_str()); - - EXPECT_EQ(set_setting(camera, "CAM_COLORMODE", "5"), Camera::Result::Success); - EXPECT_EQ(get_setting(camera, "CAM_COLORMODE", value_set), Camera::Result::Success); - EXPECT_STREQ("5", value_set.c_str()); - - EXPECT_EQ(set_setting(camera, "CAM_COLORMODE", "1"), Camera::Result::Success); - EXPECT_EQ(get_setting(camera, "CAM_COLORMODE", value_set), Camera::Result::Success); - EXPECT_STREQ("1", value_set.c_str()); - - EXPECT_EQ(set_setting(camera, "CAM_COLORMODE", "3"), Camera::Result::Success); - EXPECT_EQ(get_setting(camera, "CAM_COLORMODE", value_set), Camera::Result::Success); - EXPECT_STREQ("3", value_set.c_str()); - - // Let's check the manual exposure mode first. - std::this_thread::sleep_for(std::chrono::seconds(2)); - EXPECT_EQ(set_setting(camera, "CAM_EXPMODE", "1"), Camera::Result::Success); - EXPECT_EQ(get_setting(camera, "CAM_EXPMODE", value_set), Camera::Result::Success); - EXPECT_STREQ("1", value_set.c_str()); - - auto settings = camera->possible_setting_options(); - - // Try something that is specific to the camera mode. - contains_num_options(settings, "CAM_SHUTTERSPD", 19); - contains_num_options(settings, "CAM_ISO", 10); - - // But not EV and metering - contains_num_options(settings, "CAM_EV", 0); - contains_num_options(settings, "CAM_METERING", 0); - - // Now we'll try the same for Auto exposure mode - EXPECT_EQ(set_setting(camera, "CAM_EXPMODE", "0"), Camera::Result::Success); - EXPECT_EQ(get_setting(camera, "CAM_EXPMODE", value_set), Camera::Result::Success); - EXPECT_STREQ("0", value_set.c_str()); - - settings = camera->possible_setting_options(); - - // Shutter speed and ISO don't have options in Auto mode. - contains_num_options(settings, "CAM_SHUTTERSPD", 0); - contains_num_options(settings, "CAM_ISO", 0); - - // But not EV and metering - contains_num_options(settings, "CAM_EV", 13); - contains_num_options(settings, "CAM_METERING", 3); - - EXPECT_EQ(camera->set_mode(Camera::Mode::Video), Camera::Result::Success); - - UNUSED(camera->possible_setting_options()); - - // This should fail in video mode. - EXPECT_EQ(set_setting(camera, "CAM_PHOTOQUAL", "1"), Camera::Result::Error); - - // Let's check the manual exposure mode first. - - EXPECT_EQ(set_setting(camera, "CAM_EXPMODE", "1"), Camera::Result::Success); - EXPECT_EQ(get_setting(camera, "CAM_EXPMODE", value_set), Camera::Result::Success); - EXPECT_STREQ("1", value_set.c_str()); - - // FIXME: otherwise the camera is too slow - std::this_thread::sleep_for(std::chrono::seconds(1)); - - // But a video setting should work - EXPECT_EQ(set_setting(camera, "CAM_VIDRES", "30"), Camera::Result::Success); - EXPECT_EQ(get_setting(camera, "CAM_VIDRES", value_set), Camera::Result::Success); - EXPECT_STREQ("30", value_set.c_str()); - - settings = camera->possible_setting_options(); - - // Shutter speed and ISO don't have options in Auto mode. - contains_num_options(settings, "CAM_SHUTTERSPD", 15); - - // FIXME: otherwise the camera is too slow - std::this_thread::sleep_for(std::chrono::seconds(1)); - - // But a video setting should work - EXPECT_EQ(set_setting(camera, "CAM_VIDRES", "0"), Camera::Result::Success); - EXPECT_EQ(get_setting(camera, "CAM_VIDRES", value_set), Camera::Result::Success); - EXPECT_STREQ("0", value_set.c_str()); - - settings = camera->possible_setting_options(); - - // Shutter speed and ISO don't have options in Auto mode. - contains_num_options(settings, "CAM_SHUTTERSPD", 12); - - // Back to auto exposure mode - std::this_thread::sleep_for(std::chrono::seconds(2)); - EXPECT_EQ(set_setting(camera, "CAM_EXPMODE", "0"), Camera::Result::Success); - EXPECT_EQ(get_setting(camera, "CAM_EXPMODE", value_set), Camera::Result::Success); - EXPECT_STREQ("0", value_set.c_str()); - } -} - -static void -receive_current_settings(bool& subscription_called, const std::vector& settings) -{ - LogDebug() << "Received current options:"; - EXPECT_TRUE(settings.size() > 0); - for (auto& setting : settings) { - LogDebug() << "Got setting '" << setting.setting_description << "' with selected option '" - << setting.option.option_description << "'"; - - // Check human readable strings too. - if (setting.setting_id == "CAM_SHUTTERSPD") { - EXPECT_STREQ(setting.setting_description.c_str(), "Shutter Speed"); - } else if (setting.setting_id == "CAM_EXPMODE") { - EXPECT_STREQ(setting.setting_description.c_str(), "Exposure Mode"); - } - } - subscription_called = true; -} - -TEST(CameraTest, SubscribeCurrentSettings) -{ - Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; - - ConnectionResult connection_ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); - ASSERT_EQ(connection_ret, ConnectionResult::Success); - - // Wait for system to connect via heartbeat. - std::this_thread::sleep_for(std::chrono::seconds(2)); - - auto system = mavsdk.systems().at(0); - ASSERT_TRUE(system->has_camera()); - auto camera = std::make_shared(system); - - // We need to wait for the camera definition to be ready - // because we don't have a check yet. - std::this_thread::sleep_for(std::chrono::seconds(2)); - // Reset exposure mode - EXPECT_EQ(set_setting(camera, "CAM_EXPMODE", "0"), Camera::Result::Success); - - bool subscription_called = false; - camera->subscribe_current_settings( - [&subscription_called](const std::vector& settings) { - receive_current_settings(subscription_called, settings); - }); - - EXPECT_EQ(camera->set_mode(Camera::Mode::Photo), Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(1)); - EXPECT_TRUE(subscription_called); - - subscription_called = false; - EXPECT_EQ(set_setting(camera, "CAM_EXPMODE", "1"), Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(1)); - EXPECT_TRUE(subscription_called); -} - -static void receive_possible_setting_options( - bool& subscription_called, const std::vector& settings_options) -{ - LogDebug() << "Received possible options:"; - EXPECT_TRUE(settings_options.size() > 0); - for (auto& setting_options : settings_options) { - LogDebug() << "Got setting '" << setting_options.setting_description << "' with options:"; - - // Check human readable strings too. - if (setting_options.setting_id == "CAM_SHUTTERSPD") { - EXPECT_STREQ(setting_options.setting_description.c_str(), "Shutter Speed"); - } else if (setting_options.setting_id == "CAM_EXPMODE") { - EXPECT_STREQ(setting_options.setting_description.c_str(), "Exposure Mode"); - } - - EXPECT_TRUE(setting_options.options.size() > 0); - for (auto& option : setting_options.options) { - LogDebug() << " - '" << option.option_description << "'"; - if (setting_options.setting_id == "CAM_SHUTTERSPD" && option.option_id == "0.0025") { - EXPECT_STREQ(option.option_description.c_str(), "1/400"); - } else if (setting_options.setting_id == "CAM_WBMODE" && option.option_id == "2") { - EXPECT_STREQ(option.option_description.c_str(), "Sunrise"); - } - } - } - subscription_called = true; -} - -TEST(CameraTest, SubscribePossibleSettings) -{ - Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; - - ConnectionResult connection_ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); - ASSERT_EQ(connection_ret, ConnectionResult::Success); - - // Wait for system to connect via heartbeat. - std::this_thread::sleep_for(std::chrono::seconds(2)); - - auto system = mavsdk.systems().at(0); - ASSERT_TRUE(system->has_camera()); - auto camera = std::make_shared(system); - - // We need to wait for the camera definition to be ready - // because we don't have a check yet. - std::this_thread::sleep_for(std::chrono::seconds(2)); - // Reset exposure mode - EXPECT_EQ(set_setting(camera, "CAM_EXPMODE", "0"), Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(1)); - - bool subscription_called = false; - camera->subscribe_possible_setting_options( - [&subscription_called](const std::vector& possible_settings) { - receive_possible_setting_options(subscription_called, possible_settings); - }); - - EXPECT_EQ(camera->set_mode(Camera::Mode::Photo), Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(1)); - EXPECT_TRUE(subscription_called); - - subscription_called = false; - EXPECT_EQ(set_setting(camera, "CAM_EXPMODE", "1"), Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(1)); - EXPECT_TRUE(subscription_called); -} diff --git a/src/integration_tests/camera_take_photo.cpp b/src/integration_tests/camera_take_photo.cpp deleted file mode 100644 index 875442a7fb..0000000000 --- a/src/integration_tests/camera_take_photo.cpp +++ /dev/null @@ -1,103 +0,0 @@ -#include "integration_test_helper.h" -#include "mavsdk.h" -#include "system.h" -#include "plugins/camera/camera.h" -#include "plugins/camera_server/camera_server.h" - -using namespace mavsdk; - -static void receive_capture_info(Camera::CaptureInfo capture_info, bool& received_capture_info); - -TEST(CameraTest, TakePhotoSingle) -{ - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; - - Mavsdk mavsdk_camera{Mavsdk::Configuration{ComponentType::Camera}}; - - ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); - ASSERT_EQ(mavsdk_camera.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); - - auto camera_server = CameraServer{mavsdk_camera.server_component()}; - camera_server.subscribe_take_photo([&camera_server](int32_t index) { - LogInfo() << "Let's take photo " << index; - - CameraServer::CaptureInfo info; - info.index = index; - info.is_success = true; - - camera_server.respond_take_photo(CameraServer::CameraFeedback::Ok, info); - }); - - // Wait for system to connect via heartbeat. - std::this_thread::sleep_for(std::chrono::seconds(2)); - - ASSERT_EQ(mavsdk_groundstation.systems().size(), 1); - auto system = mavsdk_groundstation.systems().at(0); - ASSERT_TRUE(system->has_camera()); - - auto camera = Camera{system}; - - // We want to take the picture in photo mode. - EXPECT_EQ(camera.set_mode(Camera::Mode::Photo), Camera::Result::Success); - - bool received_capture_info = false; - camera.subscribe_capture_info([&received_capture_info](Camera::CaptureInfo capture_info) { - receive_capture_info(capture_info, received_capture_info); - }); - - EXPECT_EQ(camera.take_photo(), Camera::Result::Success); - std::this_thread::sleep_for(std::chrono::seconds(1)); - EXPECT_TRUE(received_capture_info); -} - -TEST(CameraTest, TakePhotosMultiple) -{ - Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; - - const int num_photos_to_take = 3; - - 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)); - - auto system = mavsdk.systems().at(0); - ASSERT_TRUE(system->has_camera()); - auto camera = std::make_shared(system); - - // We want to take the picture in photo mode. - EXPECT_EQ(camera->set_mode(Camera::Mode::Photo), Camera::Result::Success); - - std::this_thread::sleep_for(std::chrono::seconds(1)); - - bool received_capture_info = false; - camera->subscribe_capture_info([&received_capture_info](Camera::CaptureInfo capture_info) { - receive_capture_info(capture_info, received_capture_info); - }); - - for (unsigned i = 0; i < num_photos_to_take; ++i) { - const auto result = camera->take_photo(); - EXPECT_EQ(result, Camera::Result::Success); - LogDebug() << "taking picture: " << i; - std::this_thread::sleep_for(std::chrono::seconds(5)); - EXPECT_TRUE(received_capture_info); - received_capture_info = false; - } -} - -void receive_capture_info(Camera::CaptureInfo capture_info, bool& received_capture_info) -{ - LogInfo() << "New capture at " << capture_info.position.latitude_deg << ", " - << capture_info.position.longitude_deg << ", " - << capture_info.position.absolute_altitude_m << " m, " - << capture_info.position.relative_altitude_m << " m (relative to home)."; - LogInfo() << "Time: " << capture_info.time_utc_us << " us."; - LogInfo() << "Attitude: " << capture_info.attitude_quaternion.w << ", " - << capture_info.attitude_quaternion.x << ", " << capture_info.attitude_quaternion.y - << ", " << capture_info.attitude_quaternion.z << "."; - LogInfo() << "Result: " << (capture_info.is_success ? "success" : "fail") << "."; - LogInfo() << "Saved to " << capture_info.file_url << " (" << capture_info.index << ")."; - - received_capture_info = true; -} diff --git a/src/integration_tests/camera_test_helpers.cpp b/src/integration_tests/camera_test_helpers.cpp deleted file mode 100644 index adbfd81f76..0000000000 --- a/src/integration_tests/camera_test_helpers.cpp +++ /dev/null @@ -1,25 +0,0 @@ -#include -#include -#include "integration_test_helper.h" -#include "camera_test_helpers.h" - -using namespace mavsdk; - -Camera::Result set_setting( - std::shared_ptr camera, const std::string& setting_id, const std::string& option_id) -{ - Camera::Setting new_setting{}; - new_setting.setting_id = setting_id; - new_setting.option.option_id = option_id; - return camera->set_setting(new_setting); -} - -mavsdk::Camera::Result get_setting( - std::shared_ptr camera, const std::string& setting_id, std::string& option_id) -{ - Camera::Setting new_setting{}; - new_setting.setting_id = setting_id; - auto result_pair = camera->get_setting(new_setting); - option_id = result_pair.second.option.option_id; - return result_pair.first; -} diff --git a/src/integration_tests/camera_test_helpers.h b/src/integration_tests/camera_test_helpers.h deleted file mode 100644 index bec703ef23..0000000000 --- a/src/integration_tests/camera_test_helpers.h +++ /dev/null @@ -1,12 +0,0 @@ -#pragma once - -#include "mavsdk.h" -#include "plugins/camera/camera.h" - -mavsdk::Camera::Result set_setting( - std::shared_ptr camera, - const std::string& setting_id, - const std::string& option_id); - -mavsdk::Camera::Result get_setting( - std::shared_ptr camera, const std::string& setting_id, std::string& option_d); diff --git a/src/mavsdk/core/mavlink_parameter_client.cpp b/src/mavsdk/core/mavlink_parameter_client.cpp index 690cfcfa92..a4cb1557ae 100644 --- a/src/mavsdk/core/mavlink_parameter_client.cpp +++ b/src/mavsdk/core/mavlink_parameter_client.cpp @@ -670,7 +670,10 @@ void MavlinkParameterClient::process_param_value(const mavlink_message_t& messag // out of scope. auto work_queue_guard = std::make_unique::Guard>(_work_queue); const auto work = work_queue_guard->get_front(); + if (!work) { + // update existing param + find_and_call_subscriptions_value_changed(safe_param_id, received_value); return; } @@ -836,8 +839,6 @@ void MavlinkParameterClient::process_param_value(const mavlink_message_t& messag } }}, work->work_item_variant); - - // find_and_call_subscriptions_value_changed(safe_param_id, received_value); } void MavlinkParameterClient::process_param_ext_value(const mavlink_message_t& message) @@ -862,9 +863,13 @@ void MavlinkParameterClient::process_param_ext_value(const mavlink_message_t& me // See comments on process_param_value for use of unique_ptr auto work_queue_guard = std::make_unique::Guard>(_work_queue); auto work = work_queue_guard->get_front(); + if (!work) { + // update existing param + find_and_call_subscriptions_value_changed(safe_param_id, received_value); return; } + if (!work->already_requested) { return; } @@ -943,9 +948,6 @@ void MavlinkParameterClient::process_param_ext_value(const mavlink_message_t& me }, }, work->work_item_variant); - - // TODO I think we need to consider more edge cases here - // find_and_call_subscriptions_value_changed(safe_param_id, received_value); } void MavlinkParameterClient::process_param_ext_ack(const mavlink_message_t& message) diff --git a/src/mavsdk/core/mavlink_parameter_server.cpp b/src/mavsdk/core/mavlink_parameter_server.cpp index 7e26fe60a1..c649eb6c39 100644 --- a/src/mavsdk/core/mavlink_parameter_server.cpp +++ b/src/mavsdk/core/mavlink_parameter_server.cpp @@ -3,6 +3,7 @@ #include "mavlink_parameter_helper.h" #include "plugin_base.h" #include +#include namespace mavsdk { @@ -25,7 +26,7 @@ MavlinkParameterServer::MavlinkParameterServer( const auto& param_values = optional_param_values.value(); for (const auto& [key, value] : param_values) { const auto result = provide_server_param(key, value); - if (result != Result::Success) { + if (result != Result::Ok) { LogDebug() << "Cannot add parameter:" << key << ":" << value << " " << result; } } @@ -85,30 +86,39 @@ MavlinkParameterServer::provide_server_param(const std::string& name, const Para // first we try to add it as a new parameter switch (_param_cache.add_new_param(name, param_value)) { case MavlinkParameterCache::AddNewParamResult::Ok: - return Result::Success; + return Result::Ok; case MavlinkParameterCache::AddNewParamResult::AlreadyExists: - return Result::ParamExistsAlready; + // then, to not change the public api behaviour, try updating its value. + switch (_param_cache.update_existing_param(name, param_value)) { + case MavlinkParameterCache::UpdateExistingParamResult::Ok: + find_and_call_subscriptions_value_changed(name, param_value); + { + auto new_work = std::make_shared( + name, + param_value, + WorkItemValue{ + std::numeric_limits::max(), + std::numeric_limits::max(), + _last_extended}); + _work_queue.push_back(new_work); + } + return Result::OkExistsAlready; + case MavlinkParameterCache::UpdateExistingParamResult::MissingParam: + return Result::ParamNotFound; + case MavlinkParameterCache::UpdateExistingParamResult::WrongType: + return Result::WrongType; + default: + LogErr() << "Unknown update_existing_param result"; + assert(false); + return Result::Unknown; + } case MavlinkParameterCache::AddNewParamResult::TooManyParams: return Result::TooManyParams; default: LogErr() << "Unknown add_new_param result"; assert(false); + return Result::Unknown; } - - // then, to not change the public api behaviour, try updating its value. - switch (_param_cache.update_existing_param(name, param_value)) { - case MavlinkParameterCache::UpdateExistingParamResult::Ok: - return Result::Success; - case MavlinkParameterCache::UpdateExistingParamResult::MissingParam: - return Result::ParamNotFound; - case MavlinkParameterCache::UpdateExistingParamResult::WrongType: - return Result::WrongType; - default: - LogErr() << "Unknown update_existing_param result"; - assert(false); - } - - return Result::Unknown; } MavlinkParameterServer::Result @@ -157,7 +167,7 @@ MavlinkParameterServer::retrieve_server_param(const std::string& name) // This parameter exists, check its type const auto& param = param_opt.value(); if (param.value.is()) { - return {Result::Success, param.value.get()}; + return {Result::Ok, param.value.get()}; } return {Result::WrongType, {}}; } @@ -183,9 +193,10 @@ MavlinkParameterServer::retrieve_server_param_int(const std::string& name) void MavlinkParameterServer::process_param_set_internally( const std::string& param_id, const ParamValue& value_to_set, bool extended) { - // TODO: add debugging env - LogDebug() << "Param set request" << (extended ? " extended" : "") << ": " << param_id - << " with " << value_to_set; + if (_parameter_debugging) { + LogDebug() << "Param set request" << (extended ? " extended" : "") << ": " << param_id + << " with " << value_to_set; + } std::lock_guard lock(_all_params_mutex); // for checking if the update actually changed the value const auto opt_before_update = _param_cache.param_by_id(param_id, extended); @@ -223,6 +234,7 @@ void MavlinkParameterServer::process_param_set_internally( return; } case MavlinkParameterCache::UpdateExistingParamResult::Ok: { + LogWarn() << "Update existing params!"; const auto updated_parameter = _param_cache.param_by_id(param_id, extended).value(); // The param set doesn't differentiate between an update that actually changed the value // e.g. 0 to 1 and an update that had no effect e.g. 0 to 0. @@ -377,6 +389,8 @@ void MavlinkParameterServer::internal_process_param_request_read_by_id( auto new_work = std::make_shared( param.id, param.value, WorkItemValue{param.index, param_count, extended}); _work_queue.push_back(new_work); + + _last_extended = extended; } void MavlinkParameterServer::internal_process_param_request_read_by_index( @@ -479,6 +493,7 @@ void MavlinkParameterServer::do_work() return; } } else { + LogWarn() << "sending not extended message"; float param_value; if (_sender.autopilot() == Autopilot::ArduPilot) { param_value = work->param_value.get_4_float_bytes_cast(); @@ -534,8 +549,10 @@ void MavlinkParameterServer::do_work() std::ostream& operator<<(std::ostream& str, const MavlinkParameterServer::Result& result) { switch (result) { - case MavlinkParameterServer::Result::Success: - return str << "Success"; + case MavlinkParameterServer::Result::Ok: + return str << "Ok"; + case MavlinkParameterServer::Result::OkExistsAlready: + return str << "OkExistsAlready"; case MavlinkParameterServer::Result::WrongType: return str << "WrongType"; case MavlinkParameterServer::Result::ParamNameTooLong: diff --git a/src/mavsdk/core/mavlink_parameter_server.h b/src/mavsdk/core/mavlink_parameter_server.h index b71194bd76..ea38ae4388 100644 --- a/src/mavsdk/core/mavlink_parameter_server.h +++ b/src/mavsdk/core/mavlink_parameter_server.h @@ -33,12 +33,12 @@ class MavlinkParameterServer : public MavlinkParameterSubscription { ~MavlinkParameterServer(); enum class Result { - Success, + Ok, + OkExistsAlready, WrongType, ParamNameTooLong, NotFound, ParamValueTooLong, - ParamExistsAlready, TooManyParams, ParamNotFound, Unknown, @@ -55,6 +55,7 @@ class MavlinkParameterServer : public MavlinkParameterSubscription { std::pair retrieve_server_param_int(const std::string& name); std::pair retrieve_server_param_custom(const std::string& name); + void set_extended_protocol(bool extended_protocol) { _extended_protocol = extended_protocol; }; void do_work(); friend std::ostream& operator<<(std::ostream&, const Result&); @@ -117,7 +118,9 @@ class MavlinkParameterServer : public MavlinkParameterSubscription { LockedQueue _work_queue{}; + bool _extended_protocol = true; bool _parameter_debugging = false; + bool _last_extended = true; }; } // namespace mavsdk diff --git a/src/mavsdk/core/mavlink_parameter_subscription.cpp b/src/mavsdk/core/mavlink_parameter_subscription.cpp index d59a9039d7..6c7f9f635f 100644 --- a/src/mavsdk/core/mavlink_parameter_subscription.cpp +++ b/src/mavsdk/core/mavlink_parameter_subscription.cpp @@ -2,40 +2,6 @@ namespace mavsdk { -template -void MavlinkParameterSubscription::subscribe_param_changed( - const std::string& name, const ParamChangedCallback& callback, const void* cookie) -{ - std::lock_guard lock(_param_changed_subscriptions_mutex); - if (callback != nullptr) { - ParamChangedSubscription subscription{name, callback, cookie}; - // This is just to let the upper level know of what probably is a bug, but we check again - // when actually calling the callback We also cannot assume here that the user called - // provide_param before subscribe_param_changed, so the only thing that makes sense is to - // log a warning, but then continue anyways. - /*std::lock_guard lock2(_all_params_mutex); - if (_all_params.find(name) != _all_params.end()) { - const auto curr_value = _all_params.at(name); - if (!curr_value.template is_same_type_templated()) { - LogDebug() - << "You just registered a param changed callback where the type does not match - the type already stored"; - } - }*/ - _param_changed_subscriptions.push_back(subscription); - } else { - for (auto it = _param_changed_subscriptions.begin(); - it != _param_changed_subscriptions.end(); - /* ++it */) { - if (it->param_name == name && it->cookie == cookie) { - it = _param_changed_subscriptions.erase(it); - } else { - ++it; - } - } - } -} - void MavlinkParameterSubscription::subscribe_param_float_changed( const std::string& name, const ParamFloatChangedCallback& callback, const void* cookie) { @@ -62,6 +28,7 @@ void MavlinkParameterSubscription::find_and_call_subscriptions_value_changed( if (subscription.param_name != param_name) { continue; } + LogDebug() << "Param " << param_name << " changed"; // We have a subscription on this param name, now check if the subscription is for the right // type and call the callback when matching if (std::get_if(&subscription.callback) && value.get_float()) { @@ -83,14 +50,12 @@ void MavlinkParameterSubscription::unsubscribe_all_params_changed(const void* co { std::lock_guard lock(_param_changed_subscriptions_mutex); - for (auto it = _param_changed_subscriptions.begin(); it != _param_changed_subscriptions.end(); - /* it++ */) { - if (it->cookie == cookie) { - it = _param_changed_subscriptions.erase(it); - } else { - it++; - } - } + _param_changed_subscriptions.erase( + std::remove_if( + _param_changed_subscriptions.begin(), + _param_changed_subscriptions.end(), + [&](const auto& subscription) { return subscription.cookie == cookie; }), + _param_changed_subscriptions.end()); } } // namespace mavsdk diff --git a/src/mavsdk/core/mavlink_parameter_subscription.h b/src/mavsdk/core/mavlink_parameter_subscription.h index ddd7ce4605..d064fdbd3d 100644 --- a/src/mavsdk/core/mavlink_parameter_subscription.h +++ b/src/mavsdk/core/mavlink_parameter_subscription.h @@ -2,7 +2,8 @@ #include "param_value.h" #include -#include +#include +#include namespace mavsdk { @@ -16,6 +17,30 @@ class MavlinkParameterSubscription { public: template using ParamChangedCallback = std::function; + using ParamChangedCallbacks = std::variant< + ParamChangedCallback, + ParamChangedCallback, + ParamChangedCallback, + ParamChangedCallback, + ParamChangedCallback, + ParamChangedCallback, + ParamChangedCallback, + ParamChangedCallback, + ParamChangedCallback, + ParamChangedCallback, + ParamChangedCallback>; + + struct ParamChangedSubscription { + std::string param_name; + ParamChangedCallbacks callback; + const void* cookie; + ParamChangedSubscription( + std::string param_name1, ParamChangedCallbacks callback1, const void* cookie1) : + param_name(std::move(param_name1)), + callback(std::move(callback1)), + cookie(cookie1){}; + }; + /** * Subscribe to changes on the parameter referenced by @param name. * If the value for this parameter changes, the given callback is called provided that the @@ -23,15 +48,46 @@ class MavlinkParameterSubscription { */ template void subscribe_param_changed( - const std::string& name, const ParamChangedCallback& callback, const void* cookie); + const std::string& name, const ParamChangedCallback& callback, const void* cookie) + { + std::lock_guard lock(_param_changed_subscriptions_mutex); + if (callback != nullptr) { + ParamChangedSubscription subscription{name, callback, cookie}; + // This is just to let the upper level know of what probably is a bug, but we check + // again when actually calling the callback We also cannot assume here that the user + // called provide_param before subscribe_param_changed, so the only thing that makes + // sense is to log a warning, but then continue anyways. + /*std::lock_guard lock2(_all_params_mutex); + if (_all_params.find(name) != _all_params.end()) { + const auto curr_value = _all_params.at(name); + if (!curr_value.template is_same_type_templated()) { + LogDebug() + << "You just registered a param changed callback where the type does not + match the type already stored"; + } + }*/ + _param_changed_subscriptions.push_back(subscription); + } else { + for (auto it = _param_changed_subscriptions.begin(); + it != _param_changed_subscriptions.end(); + /* ++it */) { + if (it->param_name == name && it->cookie == cookie) { + it = _param_changed_subscriptions.erase(it); + } else { + ++it; + } + } + } + } using ParamFloatChangedCallback = ParamChangedCallback; + using ParamIntChangedCallback = ParamChangedCallback; + using ParamCustomChangedCallback = ParamChangedCallback; + void subscribe_param_float_changed( const std::string& name, const ParamFloatChangedCallback& callback, const void* cookie); - using ParamIntChangedCallback = ParamChangedCallback; void subscribe_param_int_changed( const std::string& name, const ParamIntChangedCallback& callback, const void* cookie); - using ParamCustomChangedCallback = ParamChangedCallback; void subscribe_param_custom_changed( const std::string& name, const ParamCustomChangedCallback& callback, const void* cookie); @@ -47,20 +103,8 @@ class MavlinkParameterSubscription { const std::string& param_name, const ParamValue& new_param_value); private: - using ParamChangedCallbacks = std:: - variant; - struct ParamChangedSubscription { - const std::string param_name; - const ParamChangedCallbacks callback; - const void* const cookie; - explicit ParamChangedSubscription( - std::string param_name1, ParamChangedCallbacks callback1, const void* cookie1) : - param_name(std::move(param_name1)), - callback(std::move(callback1)), - cookie(cookie1){}; - }; std::mutex _param_changed_subscriptions_mutex{}; - std::list _param_changed_subscriptions{}; + std::vector _param_changed_subscriptions{}; }; } // namespace mavsdk diff --git a/src/mavsdk/core/param_value.cpp b/src/mavsdk/core/param_value.cpp index 2c2e7f02b5..dedd4ca01e 100644 --- a/src/mavsdk/core/param_value.cpp +++ b/src/mavsdk/core/param_value.cpp @@ -580,10 +580,29 @@ std::array ParamValue::get_128_bytes() const (std::get_if(&_value) && std::get_if(&rhs._value)) || (std::get_if(&_value) && std::get_if(&rhs._value))) { return true; - } else { - LogWarn() << "Comparison type mismatch between " << typestr() << " and " << rhs.typestr(); - return false; } + + if ((std::get_if(&_value) || std::get_if(&_value) || + std::get_if(&_value) || std::get_if(&_value) || + std::get_if(&_value) || std::get_if(&_value) || + std::get_if(&_value) || std::get_if(&_value)) && + (std::get_if(&rhs._value) || std::get_if(&rhs._value) || + std::get_if(&rhs._value) || std::get_if(&rhs._value) || + std::get_if(&rhs._value) || std::get_if(&rhs._value) || + std::get_if(&rhs._value) || std::get_if(&rhs._value))) { + LogDebug() << "Ignoring int mismatch between " << typestr() << " and " << rhs.typestr(); + return true; + } + + if ((std::get_if(&_value) || std::get_if(&_value)) && + (std::get_if(&rhs._value) || std::get_if(&rhs._value))) { + LogDebug() << "Ignoring float/double mismatch between " << typestr() << " and " + << rhs.typestr(); + return true; + } + + LogWarn() << "Comparison type mismatch between " << typestr() << " and " << rhs.typestr(); + return false; } bool ParamValue::operator==(const std::string& value_str) const diff --git a/src/mavsdk/core/system_impl.h b/src/mavsdk/core/system_impl.h index 1286123a23..047c6e5b12 100644 --- a/src/mavsdk/core/system_impl.h +++ b/src/mavsdk/core/system_impl.h @@ -136,6 +136,8 @@ class SystemImpl { bool is_armed() const { return _armed; } + MavlinkParameterClient* param_sender(uint8_t component_id, bool extended); + MavlinkParameterClient::Result set_param( const std::string& name, ParamValue value, @@ -349,8 +351,6 @@ class SystemImpl { MavlinkStatustextHandler _statustext_handler{}; - MavlinkParameterClient* param_sender(uint8_t component_id, bool extended); - struct StatustextCallback { std::function callback; void* cookie; diff --git a/src/mavsdk/plugins/camera/camera_definition.cpp b/src/mavsdk/plugins/camera/camera_definition.cpp index c3632b3129..0a237058a4 100644 --- a/src/mavsdk/plugins/camera/camera_definition.cpp +++ b/src/mavsdk/plugins/camera/camera_definition.cpp @@ -559,7 +559,6 @@ bool CameraDefinition::get_setting(const std::string& name, ParamValue& value) value = _current_settings.at(name).value; return true; } else { - LogWarn() << "Needs updating."; return false; } } diff --git a/src/mavsdk/plugins/camera/camera_impl.cpp b/src/mavsdk/plugins/camera/camera_impl.cpp index f021b44930..742181de10 100644 --- a/src/mavsdk/plugins/camera/camera_impl.cpp +++ b/src/mavsdk/plugins/camera/camera_impl.cpp @@ -117,6 +117,7 @@ void CameraImpl::init() void CameraImpl::deinit() { _system_impl->unregister_all_mavlink_message_handlers(this); + _system_impl->cancel_all_param(this); std::lock_guard lock(_mutex); @@ -876,7 +877,7 @@ void CameraImpl::save_camera_mode_with_lock(PotentialCamera& potential_camera, C } potential_camera.camera_definition->set_setting("CAM_MODE", value); - refresh_params_with_lock(potential_camera); + refresh_params_with_lock(potential_camera, false); notify_mode_with_lock(); } @@ -1304,7 +1305,12 @@ void CameraImpl::check_camera_definition_with_lock(PotentialCamera& potential_ca } else { potential_camera.is_fetching_camera_definition = true; - if (starts_with(url, "http://") || starts_with(url, "https://")) { + if (url.empty()) { + LogInfo() << "No camera definition URL available"; + potential_camera.camera_definition_result = Camera::Result::ProtocolUnsupported; + notify_camera_list_with_lock(); + + } else if (starts_with(url, "http://") || starts_with(url, "https://")) { #if BUILD_WITHOUT_CURL == 1 potential_camera.camera_definition_result = Camera::Result::ProtocolUnsupported; notify_camera_list(); @@ -1437,7 +1443,7 @@ void CameraImpl::load_camera_definition_with_lock( // This way we can start using it straightaway. potential_camera.camera_definition->reset_to_default_settings(true); - refresh_params_with_lock(potential_camera); + refresh_params_with_lock(potential_camera, true); } void CameraImpl::process_video_information(const mavlink_message_t& message) @@ -1744,6 +1750,7 @@ void CameraImpl::set_option_async( _system_impl->call_user_callback( [callback]() { callback(Camera::Result::Success); }); } + refresh_params_with_lock(camera_later, false); }, this, camera.component_id, @@ -2046,12 +2053,13 @@ CameraImpl::get_possible_setting_options_with_lock(PotentialCamera& potential_ca return result; } -void CameraImpl::refresh_params_with_lock(PotentialCamera& potential_camera) +void CameraImpl::refresh_params_with_lock(PotentialCamera& potential_camera, bool initial_load) { assert(potential_camera.camera_definition != nullptr); std::vector> params; potential_camera.camera_definition->get_unknown_params(params); + if (params.empty()) { // We're assuming that we changed one option and this did not cause // any other possible settings to change. However, we still would @@ -2071,43 +2079,107 @@ void CameraImpl::refresh_params_with_lock(PotentialCamera& potential_camera) if (_debugging) { LogDebug() << "Trying to get param: " << param_name; } - _system_impl->get_param_async( - param_name, - param_value_type, - [camera_id, param_name, is_last, this]( - MavlinkParameterClient::Result result, const ParamValue& value) { - if (result != MavlinkParameterClient::Result::Success) { - return; - } + _system_impl->param_sender(potential_camera.component_id, true) + ->get_param_async( + param_name, + param_value_type, + [camera_id, param_name, is_last, this]( + MavlinkParameterClient::Result result, const ParamValue& value) { + if (result != MavlinkParameterClient::Result::Success) { + return; + } - std::lock_guard lock_later(_mutex); - auto maybe_potential_camera_later = - maybe_potential_camera_for_camera_id_with_lock(camera_id); - // We already checked these fields earlier, so we don't check again. - assert(maybe_potential_camera_later != nullptr); - assert(maybe_potential_camera_later->camera_definition != nullptr); + std::lock_guard lock_later(_mutex); + auto maybe_potential_camera_later = + maybe_potential_camera_for_camera_id_with_lock(camera_id); + // We already checked these fields earlier, so we don't check again. + assert(maybe_potential_camera_later != nullptr); + assert(maybe_potential_camera_later->camera_definition != nullptr); - auto& camera_later = *maybe_potential_camera_later; + auto& camera_later = *maybe_potential_camera_later; - if (camera_later.camera_definition->set_setting(param_name, value)) { - if (_debugging) { - LogDebug() << "Got setting for " << param_name << ": " << value; + if (camera_later.camera_definition->set_setting(param_name, value)) { + if (_debugging) { + LogDebug() << "Got setting for " << param_name << ": " << value; + } + return; } - return; - } - if (is_last) { - notify_current_settings_with_lock(camera_later); - notify_possible_setting_options_with_lock(camera_later); - } - }, - this, - potential_camera.component_id, - true); + if (is_last) { + notify_current_settings_with_lock(camera_later); + notify_possible_setting_options_with_lock(camera_later); + } + }, + this); + + if (initial_load) { + subscribe_to_param_changes_with_lock(potential_camera, param_name, param_value_type); + } ++count; } } +void CameraImpl::subscribe_to_param_changes_with_lock( + PotentialCamera& camera, std::string param_name, const ParamValue& param_value_type) +{ + auto camera_id = camera_id_for_potential_camera_with_lock(camera); + auto changed = [this, camera_id, param_name](auto new_param) { + if (_debugging) { + LogDebug() << "Got changing param: " << param_name << " -> " << new_param; + } + + std::lock_guard lock_later(_mutex); + + auto maybe_potential_camera_later = + maybe_potential_camera_for_camera_id_with_lock(camera_id); + // We already checked these fields earlier, so we don't check again. + assert(maybe_potential_camera_later != nullptr); + assert(maybe_potential_camera_later->camera_definition != nullptr); + auto& camera_later = *maybe_potential_camera_later; + + ParamValue param_value; + param_value.set(new_param); + camera_later.camera_definition->set_setting(param_name, param_value); + }; + + if (param_value_type.is()) { + _system_impl->param_sender(camera.component_id, true) + ->subscribe_param_changed(param_name, changed, this); + } else if (param_value_type.is()) { + _system_impl->param_sender(camera.component_id, true) + ->subscribe_param_changed(param_name, changed, this); + } else if (param_value_type.is()) { + _system_impl->param_sender(camera.component_id, true) + ->subscribe_param_changed(param_name, changed, this); + } else if (param_value_type.is()) { + _system_impl->param_sender(camera.component_id, true) + ->subscribe_param_changed(param_name, changed, this); + } else if (param_value_type.is()) { + _system_impl->param_sender(camera.component_id, true) + ->subscribe_param_changed(param_name, changed, this); + } else if (param_value_type.is()) { + _system_impl->param_sender(camera.component_id, true) + ->subscribe_param_changed(param_name, changed, this); + } else if (param_value_type.is()) { + _system_impl->param_sender(camera.component_id, true) + ->subscribe_param_changed(param_name, changed, this); + } else if (param_value_type.is()) { + _system_impl->param_sender(camera.component_id, true) + ->subscribe_param_changed(param_name, changed, this); + } else if (param_value_type.is()) { + _system_impl->param_sender(camera.component_id, true) + ->subscribe_param_changed(param_name, changed, this); + } else if (param_value_type.is()) { + _system_impl->param_sender(camera.component_id, true) + ->subscribe_param_changed(param_name, changed, this); + } else if (param_value_type.is()) { + _system_impl->param_sender(camera.component_id, true) + ->subscribe_param_changed(param_name, changed, this); + } else { + LogErr() << "Unknown type for param " << param_name; + } +} + bool CameraImpl::get_setting_str_with_lock( PotentialCamera& potential_camera, const std::string& setting_id, std::string& description) { @@ -2534,11 +2606,10 @@ CameraImpl::maybe_potential_camera_for_camera_id_with_lock(int32_t camera_id) CameraImpl::PotentialCamera* CameraImpl::maybe_potential_camera_for_component_id_with_lock(uint8_t component_id) { - const auto it = - std::find_if(_potential_cameras.begin(), _potential_cameras.end(), - [&](auto& potential_camera) { - return potential_camera.component_id = component_id; - }); + const auto it = std::find_if( + _potential_cameras.begin(), _potential_cameras.end(), [&](auto& potential_camera) { + return potential_camera.component_id = component_id; + }); if (it == _potential_cameras.end()) { return nullptr; diff --git a/src/mavsdk/plugins/camera/camera_impl.h b/src/mavsdk/plugins/camera/camera_impl.h index 27ec1004f0..3234cbed24 100644 --- a/src/mavsdk/plugins/camera/camera_impl.h +++ b/src/mavsdk/plugins/camera/camera_impl.h @@ -290,7 +290,7 @@ class CameraImpl : public PluginImplBase { void check_status(); - void refresh_params_with_lock(PotentialCamera& camera); + void refresh_params_with_lock(PotentialCamera& camera, bool initial_load); void save_camera_mode_with_lock(PotentialCamera& potential_camera, Camera::Mode mode); @@ -347,6 +347,9 @@ class CameraImpl : public PluginImplBase { void request_missing_capture_info(); + void subscribe_to_param_changes_with_lock( + PotentialCamera& camera, std::string param_name, const ParamValue& param_value_type); + uint8_t component_id_for_camera_id(int32_t camera_id); uint8_t component_id_for_camera_id_with_lock(int32_t camera_id); diff --git a/src/mavsdk/plugins/param_server/include/plugins/param_server/param_server.h b/src/mavsdk/plugins/param_server/include/plugins/param_server/param_server.h index e1ad16894a..81768b7a29 100644 --- a/src/mavsdk/plugins/param_server/include/plugins/param_server/param_server.h +++ b/src/mavsdk/plugins/param_server/include/plugins/param_server/param_server.h @@ -164,6 +164,19 @@ class ParamServer : public ServerPluginBase { */ using ResultCallback = std::function; + /** + * @brief Set param protocol. + * + * The extended param protocol is used by default. This allows to use the previous/normal one. + * + * Note that camera definition files are meant to implement/use the extended protocol. + * + * This function is blocking. + * + * @return Result of request. + */ + Result set_protocol(bool extended_protocol) const; + /** * @brief Retrieve an int parameter. * diff --git a/src/mavsdk/plugins/param_server/param_server.cpp b/src/mavsdk/plugins/param_server/param_server.cpp index 73ad3c44e0..208b377c49 100644 --- a/src/mavsdk/plugins/param_server/param_server.cpp +++ b/src/mavsdk/plugins/param_server/param_server.cpp @@ -21,6 +21,11 @@ ParamServer::ParamServer(std::shared_ptr server_component) : ParamServer::~ParamServer() {} +ParamServer::Result ParamServer::set_protocol(bool extended_protocol) const +{ + return _impl->set_protocol(extended_protocol); +} + std::pair ParamServer::retrieve_param_int(std::string name) const { return _impl->retrieve_param_int(name); diff --git a/src/mavsdk/plugins/param_server/param_server_impl.cpp b/src/mavsdk/plugins/param_server/param_server_impl.cpp index a26bc384b0..eb577bf091 100644 --- a/src/mavsdk/plugins/param_server/param_server_impl.cpp +++ b/src/mavsdk/plugins/param_server/param_server_impl.cpp @@ -26,12 +26,18 @@ void ParamServerImpl::deinit() _server_component_impl->mavlink_parameter_server().unsubscribe_all_params_changed(this); } +ParamServer::Result ParamServerImpl::set_protocol(bool extended_protocol) +{ + _server_component_impl->mavlink_parameter_server().set_extended_protocol(extended_protocol); + return ParamServer::Result::Success; +} + std::pair ParamServerImpl::retrieve_param_int(std::string name) const { auto result = _server_component_impl->mavlink_parameter_server().retrieve_server_param_int(name); - if (result.first == MavlinkParameterServer::Result::Success) { + if (result.first == MavlinkParameterServer::Result::Ok) { return {ParamServer::Result::Success, result.second}; } else { return {ParamServer::Result::NotFound, -1}; @@ -43,12 +49,15 @@ ParamServer::Result ParamServerImpl::provide_param_int(std::string name, int32_t if (name.size() > 16) { return ParamServer::Result::ParamNameTooLong; } - _server_component_impl->mavlink_parameter_server().provide_server_param_int(name, value); - _server_component_impl->mavlink_parameter_server().subscribe_param_int_changed( - name, - [name, this](int32_t new_value) { _changed_param_int_callbacks({name, new_value}); }, - this); - return ParamServer::Result::Success; + const auto ret = + _server_component_impl->mavlink_parameter_server().provide_server_param_int(name, value); + if (ret == MavlinkParameterServer::Result::Ok) { + _server_component_impl->mavlink_parameter_server().subscribe_param_int_changed( + name, + [name, this](int32_t new_value) { _changed_param_int_callbacks({name, new_value}); }, + this); + } + return result_from_mavlink_parameter_server_result(ret); } std::pair ParamServerImpl::retrieve_param_float(std::string name) const @@ -56,7 +65,7 @@ std::pair ParamServerImpl::retrieve_param_float(std: const auto result = _server_component_impl->mavlink_parameter_server().retrieve_server_param_float(name); - if (result.first == MavlinkParameterServer::Result::Success) { + if (result.first == MavlinkParameterServer::Result::Ok) { return {ParamServer::Result::Success, result.second}; } else { return {ParamServer::Result::NotFound, NAN}; @@ -68,12 +77,15 @@ ParamServer::Result ParamServerImpl::provide_param_float(std::string name, float if (name.size() > 16) { return ParamServer::Result::ParamNameTooLong; } - _server_component_impl->mavlink_parameter_server().provide_server_param_float(name, value); - _server_component_impl->mavlink_parameter_server().subscribe_param_float_changed( - name, - [name, this](float new_value) { _changed_param_float_callbacks({name, new_value}); }, - this); - return ParamServer::Result::Success; + const auto ret = + _server_component_impl->mavlink_parameter_server().provide_server_param_float(name, value); + if (ret == MavlinkParameterServer::Result::Ok) { + _server_component_impl->mavlink_parameter_server().subscribe_param_int_changed( + name, + [name, this](float new_value) { _changed_param_float_callbacks({name, new_value}); }, + this); + } + return result_from_mavlink_parameter_server_result(ret); } std::pair @@ -82,7 +94,7 @@ ParamServerImpl::retrieve_param_custom(std::string name) const const auto result = _server_component_impl->mavlink_parameter_server().retrieve_server_param_custom(name); - if (result.first == MavlinkParameterServer::Result::Success) { + if (result.first == MavlinkParameterServer::Result::Ok) { return {ParamServer::Result::Success, result.second}; } else { return {ParamServer::Result::NotFound, {}}; @@ -95,12 +107,18 @@ ParamServerImpl::provide_param_custom(std::string name, const std::string& value if (name.size() > 16) { return ParamServer::Result::ParamNameTooLong; } - _server_component_impl->mavlink_parameter_server().provide_server_param_custom(name, value); - _server_component_impl->mavlink_parameter_server().subscribe_param_custom_changed( - name, - [name, this](std::string new_value) { _changed_param_custom_callbacks({name, new_value}); }, - this); - return ParamServer::Result::Success; + + const auto ret = + _server_component_impl->mavlink_parameter_server().provide_server_param_custom(name, value); + if (ret == MavlinkParameterServer::Result::Ok) { + _server_component_impl->mavlink_parameter_server().subscribe_param_custom_changed( + name, + [name, this](const std::string& new_value) { + _changed_param_custom_callbacks({name, new_value}); + }, + this); + } + return result_from_mavlink_parameter_server_result(ret); } ParamServer::AllParams ParamServerImpl::retrieve_all_params() const @@ -163,7 +181,8 @@ ParamServer::Result ParamServerImpl::result_from_mavlink_parameter_server_result(MavlinkParameterServer::Result result) { switch (result) { - case MavlinkParameterServer::Result::Success: + case MavlinkParameterServer::Result::Ok: + case MavlinkParameterServer::Result::OkExistsAlready: return ParamServer::Result::Success; case MavlinkParameterServer::Result::NotFound: return ParamServer::Result::NotFound; diff --git a/src/mavsdk/plugins/param_server/param_server_impl.h b/src/mavsdk/plugins/param_server/param_server_impl.h index ab41ae968e..799b6e9c83 100644 --- a/src/mavsdk/plugins/param_server/param_server_impl.h +++ b/src/mavsdk/plugins/param_server/param_server_impl.h @@ -15,6 +15,8 @@ class ParamServerImpl : public ServerPluginImplBase { void init() override; void deinit() override; + ParamServer::Result set_protocol(bool extended_protocol); + std::pair retrieve_param_int(std::string name) const; ParamServer::Result provide_param_int(std::string name, int32_t value); diff --git a/src/mavsdk_server/src/generated/camera/camera.pb.cc b/src/mavsdk_server/src/generated/camera/camera.pb.cc index 3f37e4f97c..e666522a62 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.cc +++ b/src/mavsdk_server/src/generated/camera/camera.pb.cc @@ -1555,7 +1555,7 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT inline constexpr GetVideoStreamInfoResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, - camera_reuslt_{nullptr}, + camera_result_{nullptr}, video_stream_info_{nullptr} {} template @@ -2251,7 +2251,7 @@ const ::uint32_t TableStruct_camera_2fcamera_2eproto::offsets[] PROTOBUF_SECTION ~0u, // no _inlined_string_donated_ ~0u, // no _split_ ~0u, // no sizeof(Split) - PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetVideoStreamInfoResponse, _impl_.camera_reuslt_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetVideoStreamInfoResponse, _impl_.camera_result_), PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::camera::GetVideoStreamInfoResponse, _impl_.video_stream_info_), 0, 1, @@ -2996,7 +2996,7 @@ const char descriptor_table_protodef_camera_2fcamera_2eproto[] PROTOBUF_SECTION_ ".CameraResult\022%\n\004mode\030\002 \001(\0162\027.mavsdk.rpc" ".camera.Mode\".\n\031GetVideoStreamInfoReques" "t\022\021\n\tcamera_id\030\001 \001(\005\"\223\001\n\032GetVideoStreamI" - "nfoResponse\0226\n\rcamera_reuslt\030\001 \001(\0132\037.mav" + "nfoResponse\0226\n\rcamera_result\030\001 \001(\0132\037.mav" "sdk.rpc.camera.CameraResult\022=\n\021video_str" "eam_info\030\002 \001(\0132\".mavsdk.rpc.camera.Video" "StreamInfo\"%\n\020GetStatusRequest\022\021\n\tcamera" @@ -12088,8 +12088,8 @@ class GetVideoStreamInfoResponse::_Internal { using HasBits = decltype(std::declval()._impl_._has_bits_); static constexpr ::int32_t kHasBitsOffset = 8 * PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoResponse, _impl_._has_bits_); - static const ::mavsdk::rpc::camera::CameraResult& camera_reuslt(const GetVideoStreamInfoResponse* msg); - static void set_has_camera_reuslt(HasBits* has_bits) { + static const ::mavsdk::rpc::camera::CameraResult& camera_result(const GetVideoStreamInfoResponse* msg); + static void set_has_camera_result(HasBits* has_bits) { (*has_bits)[0] |= 1u; } static const ::mavsdk::rpc::camera::VideoStreamInfo& video_stream_info(const GetVideoStreamInfoResponse* msg); @@ -12098,8 +12098,8 @@ class GetVideoStreamInfoResponse::_Internal { } }; -const ::mavsdk::rpc::camera::CameraResult& GetVideoStreamInfoResponse::_Internal::camera_reuslt(const GetVideoStreamInfoResponse* msg) { - return *msg->_impl_.camera_reuslt_; +const ::mavsdk::rpc::camera::CameraResult& GetVideoStreamInfoResponse::_Internal::camera_result(const GetVideoStreamInfoResponse* msg) { + return *msg->_impl_.camera_result_; } const ::mavsdk::rpc::camera::VideoStreamInfo& GetVideoStreamInfoResponse::_Internal::video_stream_info(const GetVideoStreamInfoResponse* msg) { return *msg->_impl_.video_stream_info_; @@ -12125,8 +12125,8 @@ GetVideoStreamInfoResponse::GetVideoStreamInfoResponse( from._internal_metadata_); new (&_impl_) Impl_(internal_visibility(), arena, from._impl_); ::uint32_t cached_has_bits = _impl_._has_bits_[0]; - _impl_.camera_reuslt_ = (cached_has_bits & 0x00000001u) - ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_reuslt_) + _impl_.camera_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(arena, *from._impl_.camera_result_) : nullptr; _impl_.video_stream_info_ = (cached_has_bits & 0x00000002u) ? CreateMaybeMessage<::mavsdk::rpc::camera::VideoStreamInfo>(arena, *from._impl_.video_stream_info_) @@ -12142,10 +12142,10 @@ inline PROTOBUF_NDEBUG_INLINE GetVideoStreamInfoResponse::Impl_::Impl_( inline void GetVideoStreamInfoResponse::SharedCtor(::_pb::Arena* arena) { new (&_impl_) Impl_(internal_visibility(), arena); ::memset(reinterpret_cast(&_impl_) + - offsetof(Impl_, camera_reuslt_), + offsetof(Impl_, camera_result_), 0, offsetof(Impl_, video_stream_info_) - - offsetof(Impl_, camera_reuslt_) + + offsetof(Impl_, camera_result_) + sizeof(Impl_::video_stream_info_)); } GetVideoStreamInfoResponse::~GetVideoStreamInfoResponse() { @@ -12155,7 +12155,7 @@ GetVideoStreamInfoResponse::~GetVideoStreamInfoResponse() { } inline void GetVideoStreamInfoResponse::SharedDtor() { ABSL_DCHECK(GetArena() == nullptr); - delete _impl_.camera_reuslt_; + delete _impl_.camera_result_; delete _impl_.video_stream_info_; _impl_.~Impl_(); } @@ -12170,8 +12170,8 @@ PROTOBUF_NOINLINE void GetVideoStreamInfoResponse::Clear() { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000003u) { if (cached_has_bits & 0x00000001u) { - ABSL_DCHECK(_impl_.camera_reuslt_ != nullptr); - _impl_.camera_reuslt_->Clear(); + ABSL_DCHECK(_impl_.camera_result_ != nullptr); + _impl_.camera_result_->Clear(); } if (cached_has_bits & 0x00000002u) { ABSL_DCHECK(_impl_.video_stream_info_ != nullptr); @@ -12207,14 +12207,14 @@ const ::_pbi::TcParseTable<1, 2, 2, 0, 2> GetVideoStreamInfoResponse::_table_ = // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 2; {::_pbi::TcParser::FastMtS1, {18, 1, 1, PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoResponse, _impl_.video_stream_info_)}}, - // .mavsdk.rpc.camera.CameraResult camera_reuslt = 1; + // .mavsdk.rpc.camera.CameraResult camera_result = 1; {::_pbi::TcParser::FastMtS1, - {10, 0, 0, PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoResponse, _impl_.camera_reuslt_)}}, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoResponse, _impl_.camera_result_)}}, }}, {{ 65535, 65535 }}, {{ - // .mavsdk.rpc.camera.CameraResult camera_reuslt = 1; - {PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoResponse, _impl_.camera_reuslt_), _Internal::kHasBitsOffset + 0, 0, + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + {PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoResponse, _impl_.camera_result_), _Internal::kHasBitsOffset + 0, 0, (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 2; {PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoResponse, _impl_.video_stream_info_), _Internal::kHasBitsOffset + 1, 1, @@ -12234,11 +12234,11 @@ ::uint8_t* GetVideoStreamInfoResponse::_InternalSerialize( (void)cached_has_bits; cached_has_bits = _impl_._has_bits_[0]; - // .mavsdk.rpc.camera.CameraResult camera_reuslt = 1; + // .mavsdk.rpc.camera.CameraResult camera_result = 1; if (cached_has_bits & 0x00000001u) { target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( - 1, _Internal::camera_reuslt(this), - _Internal::camera_reuslt(this).GetCachedSize(), target, stream); + 1, _Internal::camera_result(this), + _Internal::camera_result(this).GetCachedSize(), target, stream); } // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 2; @@ -12267,10 +12267,10 @@ ::size_t GetVideoStreamInfoResponse::ByteSizeLong() const { cached_has_bits = _impl_._has_bits_[0]; if (cached_has_bits & 0x00000003u) { - // .mavsdk.rpc.camera.CameraResult camera_reuslt = 1; + // .mavsdk.rpc.camera.CameraResult camera_result = 1; if (cached_has_bits & 0x00000001u) { total_size += - 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_reuslt_); + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.camera_result_); } // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 2; @@ -12302,8 +12302,8 @@ void GetVideoStreamInfoResponse::MergeImpl(::google::protobuf::Message& to_msg, cached_has_bits = from._impl_._has_bits_[0]; if (cached_has_bits & 0x00000003u) { if (cached_has_bits & 0x00000001u) { - _this->_internal_mutable_camera_reuslt()->::mavsdk::rpc::camera::CameraResult::MergeFrom( - from._internal_camera_reuslt()); + _this->_internal_mutable_camera_result()->::mavsdk::rpc::camera::CameraResult::MergeFrom( + from._internal_camera_result()); } if (cached_has_bits & 0x00000002u) { _this->_internal_mutable_video_stream_info()->::mavsdk::rpc::camera::VideoStreamInfo::MergeFrom( @@ -12334,9 +12334,9 @@ void GetVideoStreamInfoResponse::InternalSwap(GetVideoStreamInfoResponse* PROTOB ::google::protobuf::internal::memswap< PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoResponse, _impl_.video_stream_info_) + sizeof(GetVideoStreamInfoResponse::_impl_.video_stream_info_) - - PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoResponse, _impl_.camera_reuslt_)>( - reinterpret_cast(&_impl_.camera_reuslt_), - reinterpret_cast(&other->_impl_.camera_reuslt_)); + - PROTOBUF_FIELD_OFFSET(GetVideoStreamInfoResponse, _impl_.camera_result_)>( + reinterpret_cast(&_impl_.camera_result_), + reinterpret_cast(&other->_impl_.camera_result_)); } ::google::protobuf::Metadata GetVideoStreamInfoResponse::GetMetadata() const { diff --git a/src/mavsdk_server/src/generated/camera/camera.pb.h b/src/mavsdk_server/src/generated/camera/camera.pb.h index 9a779bd96a..04944d32c8 100644 --- a/src/mavsdk_server/src/generated/camera/camera.pb.h +++ b/src/mavsdk_server/src/generated/camera/camera.pb.h @@ -15381,22 +15381,22 @@ class GetVideoStreamInfoResponse final : // accessors ------------------------------------------------------- enum : int { - kCameraReusltFieldNumber = 1, + kCameraResultFieldNumber = 1, kVideoStreamInfoFieldNumber = 2, }; - // .mavsdk.rpc.camera.CameraResult camera_reuslt = 1; - bool has_camera_reuslt() const; - void clear_camera_reuslt() ; - const ::mavsdk::rpc::camera::CameraResult& camera_reuslt() const; - PROTOBUF_NODISCARD ::mavsdk::rpc::camera::CameraResult* release_camera_reuslt(); - ::mavsdk::rpc::camera::CameraResult* mutable_camera_reuslt(); - void set_allocated_camera_reuslt(::mavsdk::rpc::camera::CameraResult* value); - void unsafe_arena_set_allocated_camera_reuslt(::mavsdk::rpc::camera::CameraResult* value); - ::mavsdk::rpc::camera::CameraResult* unsafe_arena_release_camera_reuslt(); + // .mavsdk.rpc.camera.CameraResult camera_result = 1; + bool has_camera_result() const; + void clear_camera_result() ; + const ::mavsdk::rpc::camera::CameraResult& camera_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::camera::CameraResult* release_camera_result(); + ::mavsdk::rpc::camera::CameraResult* mutable_camera_result(); + void set_allocated_camera_result(::mavsdk::rpc::camera::CameraResult* value); + void unsafe_arena_set_allocated_camera_result(::mavsdk::rpc::camera::CameraResult* value); + ::mavsdk::rpc::camera::CameraResult* unsafe_arena_release_camera_result(); private: - const ::mavsdk::rpc::camera::CameraResult& _internal_camera_reuslt() const; - ::mavsdk::rpc::camera::CameraResult* _internal_mutable_camera_reuslt(); + const ::mavsdk::rpc::camera::CameraResult& _internal_camera_result() const; + ::mavsdk::rpc::camera::CameraResult* _internal_mutable_camera_result(); public: // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 2; @@ -15439,7 +15439,7 @@ class GetVideoStreamInfoResponse final : ::google::protobuf::Arena* arena, const Impl_& from); ::google::protobuf::internal::HasBits<1> _has_bits_; mutable ::google::protobuf::internal::CachedSize _cached_size_; - ::mavsdk::rpc::camera::CameraResult* camera_reuslt_; + ::mavsdk::rpc::camera::CameraResult* camera_result_; ::mavsdk::rpc::camera::VideoStreamInfo* video_stream_info_; PROTOBUF_TSAN_DECLARE_MEMBER }; @@ -21024,45 +21024,45 @@ inline void GetVideoStreamInfoRequest::_internal_set_camera_id(::int32_t value) // GetVideoStreamInfoResponse -// .mavsdk.rpc.camera.CameraResult camera_reuslt = 1; -inline bool GetVideoStreamInfoResponse::has_camera_reuslt() const { +// .mavsdk.rpc.camera.CameraResult camera_result = 1; +inline bool GetVideoStreamInfoResponse::has_camera_result() const { bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; - PROTOBUF_ASSUME(!value || _impl_.camera_reuslt_ != nullptr); + PROTOBUF_ASSUME(!value || _impl_.camera_result_ != nullptr); return value; } -inline void GetVideoStreamInfoResponse::clear_camera_reuslt() { +inline void GetVideoStreamInfoResponse::clear_camera_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - if (_impl_.camera_reuslt_ != nullptr) _impl_.camera_reuslt_->Clear(); + if (_impl_.camera_result_ != nullptr) _impl_.camera_result_->Clear(); _impl_._has_bits_[0] &= ~0x00000001u; } -inline const ::mavsdk::rpc::camera::CameraResult& GetVideoStreamInfoResponse::_internal_camera_reuslt() const { +inline const ::mavsdk::rpc::camera::CameraResult& GetVideoStreamInfoResponse::_internal_camera_result() const { PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); - const ::mavsdk::rpc::camera::CameraResult* p = _impl_.camera_reuslt_; + const ::mavsdk::rpc::camera::CameraResult* p = _impl_.camera_result_; return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::camera::_CameraResult_default_instance_); } -inline const ::mavsdk::rpc::camera::CameraResult& GetVideoStreamInfoResponse::camera_reuslt() const ABSL_ATTRIBUTE_LIFETIME_BOUND { - // @@protoc_insertion_point(field_get:mavsdk.rpc.camera.GetVideoStreamInfoResponse.camera_reuslt) - return _internal_camera_reuslt(); +inline const ::mavsdk::rpc::camera::CameraResult& GetVideoStreamInfoResponse::camera_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.camera.GetVideoStreamInfoResponse.camera_result) + return _internal_camera_result(); } -inline void GetVideoStreamInfoResponse::unsafe_arena_set_allocated_camera_reuslt(::mavsdk::rpc::camera::CameraResult* value) { +inline void GetVideoStreamInfoResponse::unsafe_arena_set_allocated_camera_result(::mavsdk::rpc::camera::CameraResult* value) { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (GetArena() == nullptr) { - delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.camera_reuslt_); + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.camera_result_); } - _impl_.camera_reuslt_ = reinterpret_cast<::mavsdk::rpc::camera::CameraResult*>(value); + _impl_.camera_result_ = reinterpret_cast<::mavsdk::rpc::camera::CameraResult*>(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.camera.GetVideoStreamInfoResponse.camera_reuslt) + // @@protoc_insertion_point(field_unsafe_arena_set_allocated:mavsdk.rpc.camera.GetVideoStreamInfoResponse.camera_result) } -inline ::mavsdk::rpc::camera::CameraResult* GetVideoStreamInfoResponse::release_camera_reuslt() { +inline ::mavsdk::rpc::camera::CameraResult* GetVideoStreamInfoResponse::release_camera_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera::CameraResult* released = _impl_.camera_reuslt_; - _impl_.camera_reuslt_ = nullptr; + ::mavsdk::rpc::camera::CameraResult* released = _impl_.camera_result_; + _impl_.camera_result_ = nullptr; #ifdef PROTOBUF_FORCE_COPY_IN_RELEASE auto* old = reinterpret_cast<::google::protobuf::MessageLite*>(released); released = ::google::protobuf::internal::DuplicateIfNonNull(released); @@ -21076,34 +21076,34 @@ inline ::mavsdk::rpc::camera::CameraResult* GetVideoStreamInfoResponse::release_ #endif // !PROTOBUF_FORCE_COPY_IN_RELEASE return released; } -inline ::mavsdk::rpc::camera::CameraResult* GetVideoStreamInfoResponse::unsafe_arena_release_camera_reuslt() { +inline ::mavsdk::rpc::camera::CameraResult* GetVideoStreamInfoResponse::unsafe_arena_release_camera_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); - // @@protoc_insertion_point(field_release:mavsdk.rpc.camera.GetVideoStreamInfoResponse.camera_reuslt) + // @@protoc_insertion_point(field_release:mavsdk.rpc.camera.GetVideoStreamInfoResponse.camera_result) _impl_._has_bits_[0] &= ~0x00000001u; - ::mavsdk::rpc::camera::CameraResult* temp = _impl_.camera_reuslt_; - _impl_.camera_reuslt_ = nullptr; + ::mavsdk::rpc::camera::CameraResult* temp = _impl_.camera_result_; + _impl_.camera_result_ = nullptr; return temp; } -inline ::mavsdk::rpc::camera::CameraResult* GetVideoStreamInfoResponse::_internal_mutable_camera_reuslt() { +inline ::mavsdk::rpc::camera::CameraResult* GetVideoStreamInfoResponse::_internal_mutable_camera_result() { PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); _impl_._has_bits_[0] |= 0x00000001u; - if (_impl_.camera_reuslt_ == nullptr) { + if (_impl_.camera_result_ == nullptr) { auto* p = CreateMaybeMessage<::mavsdk::rpc::camera::CameraResult>(GetArena()); - _impl_.camera_reuslt_ = reinterpret_cast<::mavsdk::rpc::camera::CameraResult*>(p); + _impl_.camera_result_ = reinterpret_cast<::mavsdk::rpc::camera::CameraResult*>(p); } - return _impl_.camera_reuslt_; + return _impl_.camera_result_; } -inline ::mavsdk::rpc::camera::CameraResult* GetVideoStreamInfoResponse::mutable_camera_reuslt() ABSL_ATTRIBUTE_LIFETIME_BOUND { - ::mavsdk::rpc::camera::CameraResult* _msg = _internal_mutable_camera_reuslt(); - // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera.GetVideoStreamInfoResponse.camera_reuslt) +inline ::mavsdk::rpc::camera::CameraResult* GetVideoStreamInfoResponse::mutable_camera_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::camera::CameraResult* _msg = _internal_mutable_camera_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.camera.GetVideoStreamInfoResponse.camera_result) return _msg; } -inline void GetVideoStreamInfoResponse::set_allocated_camera_reuslt(::mavsdk::rpc::camera::CameraResult* value) { +inline void GetVideoStreamInfoResponse::set_allocated_camera_result(::mavsdk::rpc::camera::CameraResult* value) { ::google::protobuf::Arena* message_arena = GetArena(); PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); if (message_arena == nullptr) { - delete reinterpret_cast<::mavsdk::rpc::camera::CameraResult*>(_impl_.camera_reuslt_); + delete reinterpret_cast<::mavsdk::rpc::camera::CameraResult*>(_impl_.camera_result_); } if (value != nullptr) { @@ -21116,8 +21116,8 @@ inline void GetVideoStreamInfoResponse::set_allocated_camera_reuslt(::mavsdk::rp _impl_._has_bits_[0] &= ~0x00000001u; } - _impl_.camera_reuslt_ = reinterpret_cast<::mavsdk::rpc::camera::CameraResult*>(value); - // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera.GetVideoStreamInfoResponse.camera_reuslt) + _impl_.camera_result_ = reinterpret_cast<::mavsdk::rpc::camera::CameraResult*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.camera.GetVideoStreamInfoResponse.camera_result) } // .mavsdk.rpc.camera.VideoStreamInfo video_stream_info = 2; diff --git a/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.cc b/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.cc index e18f439870..fd5df363f6 100644 --- a/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.cc +++ b/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.cc @@ -24,6 +24,7 @@ namespace rpc { namespace param_server { static const char* ParamServerService_method_names[] = { + "/mavsdk.rpc.param_server.ParamServerService/SetProtocol", "/mavsdk.rpc.param_server.ParamServerService/RetrieveParamInt", "/mavsdk.rpc.param_server.ParamServerService/ProvideParamInt", "/mavsdk.rpc.param_server.ParamServerService/RetrieveParamFloat", @@ -43,18 +44,42 @@ std::unique_ptr< ParamServerService::Stub> ParamServerService::NewStub(const std } ParamServerService::Stub::Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options) - : channel_(channel), rpcmethod_RetrieveParamInt_(ParamServerService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_ProvideParamInt_(ParamServerService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_RetrieveParamFloat_(ParamServerService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_ProvideParamFloat_(ParamServerService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_RetrieveParamCustom_(ParamServerService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_ProvideParamCustom_(ParamServerService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_RetrieveAllParams_(ParamServerService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) - , rpcmethod_SubscribeChangedParamInt_(ParamServerService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeChangedParamFloat_(ParamServerService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) - , rpcmethod_SubscribeChangedParamCustom_(ParamServerService_method_names[9], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + : channel_(channel), rpcmethod_SetProtocol_(ParamServerService_method_names[0], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_RetrieveParamInt_(ParamServerService_method_names[1], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_ProvideParamInt_(ParamServerService_method_names[2], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_RetrieveParamFloat_(ParamServerService_method_names[3], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_ProvideParamFloat_(ParamServerService_method_names[4], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_RetrieveParamCustom_(ParamServerService_method_names[5], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_ProvideParamCustom_(ParamServerService_method_names[6], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_RetrieveAllParams_(ParamServerService_method_names[7], options.suffix_for_stats(),::grpc::internal::RpcMethod::NORMAL_RPC, channel) + , rpcmethod_SubscribeChangedParamInt_(ParamServerService_method_names[8], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeChangedParamFloat_(ParamServerService_method_names[9], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) + , rpcmethod_SubscribeChangedParamCustom_(ParamServerService_method_names[10], options.suffix_for_stats(),::grpc::internal::RpcMethod::SERVER_STREAMING, channel) {} +::grpc::Status ParamServerService::Stub::SetProtocol(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest& request, ::mavsdk::rpc::param_server::SetProtocolResponse* response) { + return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::param_server::SetProtocolRequest, ::mavsdk::rpc::param_server::SetProtocolResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_SetProtocol_, context, request, response); +} + +void ParamServerService::Stub::async::SetProtocol(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest* request, ::mavsdk::rpc::param_server::SetProtocolResponse* response, std::function f) { + ::grpc::internal::CallbackUnaryCall< ::mavsdk::rpc::param_server::SetProtocolRequest, ::mavsdk::rpc::param_server::SetProtocolResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetProtocol_, context, request, response, std::move(f)); +} + +void ParamServerService::Stub::async::SetProtocol(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest* request, ::mavsdk::rpc::param_server::SetProtocolResponse* response, ::grpc::ClientUnaryReactor* reactor) { + ::grpc::internal::ClientCallbackUnaryFactory::Create< ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(stub_->channel_.get(), stub_->rpcmethod_SetProtocol_, context, request, response, reactor); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::SetProtocolResponse>* ParamServerService::Stub::PrepareAsyncSetProtocolRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest& request, ::grpc::CompletionQueue* cq) { + return ::grpc::internal::ClientAsyncResponseReaderHelper::Create< ::mavsdk::rpc::param_server::SetProtocolResponse, ::mavsdk::rpc::param_server::SetProtocolRequest, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), cq, rpcmethod_SetProtocol_, context, request); +} + +::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::SetProtocolResponse>* ParamServerService::Stub::AsyncSetProtocolRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest& request, ::grpc::CompletionQueue* cq) { + auto* result = + this->PrepareAsyncSetProtocolRaw(context, request, cq); + result->StartCall(); + return result; +} + ::grpc::Status ParamServerService::Stub::RetrieveParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveParamIntRequest& request, ::mavsdk::rpc::param_server::RetrieveParamIntResponse* response) { return ::grpc::internal::BlockingUnaryCall< ::mavsdk::rpc::param_server::RetrieveParamIntRequest, ::mavsdk::rpc::param_server::RetrieveParamIntResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>(channel_.get(), rpcmethod_RetrieveParamInt_, context, request, response); } @@ -268,6 +293,16 @@ ParamServerService::Service::Service() { AddMethod(new ::grpc::internal::RpcServiceMethod( ParamServerService_method_names[0], ::grpc::internal::RpcMethod::NORMAL_RPC, + new ::grpc::internal::RpcMethodHandler< ParamServerService::Service, ::mavsdk::rpc::param_server::SetProtocolRequest, ::mavsdk::rpc::param_server::SetProtocolResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( + [](ParamServerService::Service* service, + ::grpc::ServerContext* ctx, + const ::mavsdk::rpc::param_server::SetProtocolRequest* req, + ::mavsdk::rpc::param_server::SetProtocolResponse* resp) { + return service->SetProtocol(ctx, req, resp); + }, this))); + AddMethod(new ::grpc::internal::RpcServiceMethod( + ParamServerService_method_names[1], + ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< ParamServerService::Service, ::mavsdk::rpc::param_server::RetrieveParamIntRequest, ::mavsdk::rpc::param_server::RetrieveParamIntResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](ParamServerService::Service* service, ::grpc::ServerContext* ctx, @@ -276,7 +311,7 @@ ParamServerService::Service::Service() { return service->RetrieveParamInt(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - ParamServerService_method_names[1], + ParamServerService_method_names[2], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< ParamServerService::Service, ::mavsdk::rpc::param_server::ProvideParamIntRequest, ::mavsdk::rpc::param_server::ProvideParamIntResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](ParamServerService::Service* service, @@ -286,7 +321,7 @@ ParamServerService::Service::Service() { return service->ProvideParamInt(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - ParamServerService_method_names[2], + ParamServerService_method_names[3], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< ParamServerService::Service, ::mavsdk::rpc::param_server::RetrieveParamFloatRequest, ::mavsdk::rpc::param_server::RetrieveParamFloatResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](ParamServerService::Service* service, @@ -296,7 +331,7 @@ ParamServerService::Service::Service() { return service->RetrieveParamFloat(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - ParamServerService_method_names[3], + ParamServerService_method_names[4], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< ParamServerService::Service, ::mavsdk::rpc::param_server::ProvideParamFloatRequest, ::mavsdk::rpc::param_server::ProvideParamFloatResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](ParamServerService::Service* service, @@ -306,7 +341,7 @@ ParamServerService::Service::Service() { return service->ProvideParamFloat(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - ParamServerService_method_names[4], + ParamServerService_method_names[5], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< ParamServerService::Service, ::mavsdk::rpc::param_server::RetrieveParamCustomRequest, ::mavsdk::rpc::param_server::RetrieveParamCustomResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](ParamServerService::Service* service, @@ -316,7 +351,7 @@ ParamServerService::Service::Service() { return service->RetrieveParamCustom(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - ParamServerService_method_names[5], + ParamServerService_method_names[6], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< ParamServerService::Service, ::mavsdk::rpc::param_server::ProvideParamCustomRequest, ::mavsdk::rpc::param_server::ProvideParamCustomResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](ParamServerService::Service* service, @@ -326,7 +361,7 @@ ParamServerService::Service::Service() { return service->ProvideParamCustom(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - ParamServerService_method_names[6], + ParamServerService_method_names[7], ::grpc::internal::RpcMethod::NORMAL_RPC, new ::grpc::internal::RpcMethodHandler< ParamServerService::Service, ::mavsdk::rpc::param_server::RetrieveAllParamsRequest, ::mavsdk::rpc::param_server::RetrieveAllParamsResponse, ::grpc::protobuf::MessageLite, ::grpc::protobuf::MessageLite>( [](ParamServerService::Service* service, @@ -336,7 +371,7 @@ ParamServerService::Service::Service() { return service->RetrieveAllParams(ctx, req, resp); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - ParamServerService_method_names[7], + ParamServerService_method_names[8], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< ParamServerService::Service, ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest, ::mavsdk::rpc::param_server::ChangedParamIntResponse>( [](ParamServerService::Service* service, @@ -346,7 +381,7 @@ ParamServerService::Service::Service() { return service->SubscribeChangedParamInt(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - ParamServerService_method_names[8], + ParamServerService_method_names[9], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< ParamServerService::Service, ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest, ::mavsdk::rpc::param_server::ChangedParamFloatResponse>( [](ParamServerService::Service* service, @@ -356,7 +391,7 @@ ParamServerService::Service::Service() { return service->SubscribeChangedParamFloat(ctx, req, writer); }, this))); AddMethod(new ::grpc::internal::RpcServiceMethod( - ParamServerService_method_names[9], + ParamServerService_method_names[10], ::grpc::internal::RpcMethod::SERVER_STREAMING, new ::grpc::internal::ServerStreamingHandler< ParamServerService::Service, ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest, ::mavsdk::rpc::param_server::ChangedParamCustomResponse>( [](ParamServerService::Service* service, @@ -370,6 +405,13 @@ ParamServerService::Service::Service() { ParamServerService::Service::~Service() { } +::grpc::Status ParamServerService::Service::SetProtocol(::grpc::ServerContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest* request, ::mavsdk::rpc::param_server::SetProtocolResponse* response) { + (void) context; + (void) request; + (void) response; + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); +} + ::grpc::Status ParamServerService::Service::RetrieveParamInt(::grpc::ServerContext* context, const ::mavsdk::rpc::param_server::RetrieveParamIntRequest* request, ::mavsdk::rpc::param_server::RetrieveParamIntResponse* response) { (void) context; (void) request; diff --git a/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.h b/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.h index 930d5c223c..396d6d53a0 100644 --- a/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.h +++ b/src/mavsdk_server/src/generated/param_server/param_server.grpc.pb.h @@ -39,6 +39,19 @@ class ParamServerService final { public: virtual ~StubInterface() {} // + // Set param protocol. + // + // The extended param protocol is used by default. This allows to use the previous/normal one. + // + // Note that camera definition files are meant to implement/use the extended protocol. + virtual ::grpc::Status SetProtocol(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest& request, ::mavsdk::rpc::param_server::SetProtocolResponse* response) = 0; + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::param_server::SetProtocolResponse>> AsyncSetProtocol(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::param_server::SetProtocolResponse>>(AsyncSetProtocolRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::param_server::SetProtocolResponse>> PrepareAsyncSetProtocol(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::param_server::SetProtocolResponse>>(PrepareAsyncSetProtocolRaw(context, request, cq)); + } + // // Retrieve an int parameter. // // If the type is wrong, the result will be `WRONG_TYPE`. @@ -147,6 +160,14 @@ class ParamServerService final { public: virtual ~async_interface() {} // + // Set param protocol. + // + // The extended param protocol is used by default. This allows to use the previous/normal one. + // + // Note that camera definition files are meant to implement/use the extended protocol. + virtual void SetProtocol(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest* request, ::mavsdk::rpc::param_server::SetProtocolResponse* response, std::function) = 0; + virtual void SetProtocol(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest* request, ::mavsdk::rpc::param_server::SetProtocolResponse* response, ::grpc::ClientUnaryReactor* reactor) = 0; + // // Retrieve an int parameter. // // If the type is wrong, the result will be `WRONG_TYPE`. @@ -197,6 +218,8 @@ class ParamServerService final { virtual class async_interface* async() { return nullptr; } class async_interface* experimental_async() { return async(); } private: + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::param_server::SetProtocolResponse>* AsyncSetProtocolRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest& request, ::grpc::CompletionQueue* cq) = 0; + virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::param_server::SetProtocolResponse>* PrepareAsyncSetProtocolRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::param_server::RetrieveParamIntResponse>* AsyncRetrieveParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveParamIntRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::param_server::RetrieveParamIntResponse>* PrepareAsyncRetrieveParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveParamIntRequest& request, ::grpc::CompletionQueue* cq) = 0; virtual ::grpc::ClientAsyncResponseReaderInterface< ::mavsdk::rpc::param_server::ProvideParamIntResponse>* AsyncProvideParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::ProvideParamIntRequest& request, ::grpc::CompletionQueue* cq) = 0; @@ -224,6 +247,13 @@ class ParamServerService final { class Stub final : public StubInterface { public: Stub(const std::shared_ptr< ::grpc::ChannelInterface>& channel, const ::grpc::StubOptions& options = ::grpc::StubOptions()); + ::grpc::Status SetProtocol(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest& request, ::mavsdk::rpc::param_server::SetProtocolResponse* response) override; + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::SetProtocolResponse>> AsyncSetProtocol(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::SetProtocolResponse>>(AsyncSetProtocolRaw(context, request, cq)); + } + std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::SetProtocolResponse>> PrepareAsyncSetProtocol(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest& request, ::grpc::CompletionQueue* cq) { + return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::SetProtocolResponse>>(PrepareAsyncSetProtocolRaw(context, request, cq)); + } ::grpc::Status RetrieveParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveParamIntRequest& request, ::mavsdk::rpc::param_server::RetrieveParamIntResponse* response) override; std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::RetrieveParamIntResponse>> AsyncRetrieveParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveParamIntRequest& request, ::grpc::CompletionQueue* cq) { return std::unique_ptr< ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::RetrieveParamIntResponse>>(AsyncRetrieveParamIntRaw(context, request, cq)); @@ -303,6 +333,8 @@ class ParamServerService final { class async final : public StubInterface::async_interface { public: + void SetProtocol(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest* request, ::mavsdk::rpc::param_server::SetProtocolResponse* response, std::function) override; + void SetProtocol(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest* request, ::mavsdk::rpc::param_server::SetProtocolResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void RetrieveParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveParamIntRequest* request, ::mavsdk::rpc::param_server::RetrieveParamIntResponse* response, std::function) override; void RetrieveParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveParamIntRequest* request, ::mavsdk::rpc::param_server::RetrieveParamIntResponse* response, ::grpc::ClientUnaryReactor* reactor) override; void ProvideParamInt(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::ProvideParamIntRequest* request, ::mavsdk::rpc::param_server::ProvideParamIntResponse* response, std::function) override; @@ -331,6 +363,8 @@ class ParamServerService final { private: std::shared_ptr< ::grpc::ChannelInterface> channel_; class async async_stub_{this}; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::SetProtocolResponse>* AsyncSetProtocolRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest& request, ::grpc::CompletionQueue* cq) override; + ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::SetProtocolResponse>* PrepareAsyncSetProtocolRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::RetrieveParamIntResponse>* AsyncRetrieveParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveParamIntRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::RetrieveParamIntResponse>* PrepareAsyncRetrieveParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::RetrieveParamIntRequest& request, ::grpc::CompletionQueue* cq) override; ::grpc::ClientAsyncResponseReader< ::mavsdk::rpc::param_server::ProvideParamIntResponse>* AsyncProvideParamIntRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::ProvideParamIntRequest& request, ::grpc::CompletionQueue* cq) override; @@ -354,6 +388,7 @@ class ParamServerService final { ::grpc::ClientReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* SubscribeChangedParamCustomRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* AsyncSubscribeChangedParamCustomRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request, ::grpc::CompletionQueue* cq, void* tag) override; ::grpc::ClientAsyncReader< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* PrepareAsyncSubscribeChangedParamCustomRaw(::grpc::ClientContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest& request, ::grpc::CompletionQueue* cq) override; + const ::grpc::internal::RpcMethod rpcmethod_SetProtocol_; const ::grpc::internal::RpcMethod rpcmethod_RetrieveParamInt_; const ::grpc::internal::RpcMethod rpcmethod_ProvideParamInt_; const ::grpc::internal::RpcMethod rpcmethod_RetrieveParamFloat_; @@ -372,6 +407,13 @@ class ParamServerService final { Service(); virtual ~Service(); // + // Set param protocol. + // + // The extended param protocol is used by default. This allows to use the previous/normal one. + // + // Note that camera definition files are meant to implement/use the extended protocol. + virtual ::grpc::Status SetProtocol(::grpc::ServerContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest* request, ::mavsdk::rpc::param_server::SetProtocolResponse* response); + // // Retrieve an int parameter. // // If the type is wrong, the result will be `WRONG_TYPE`. @@ -412,12 +454,32 @@ class ParamServerService final { virtual ::grpc::Status SubscribeChangedParamCustom(::grpc::ServerContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* request, ::grpc::ServerWriter< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* writer); }; template + class WithAsyncMethod_SetProtocol : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithAsyncMethod_SetProtocol() { + ::grpc::Service::MarkMethodAsync(0); + } + ~WithAsyncMethod_SetProtocol() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetProtocol(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SetProtocolRequest* /*request*/, ::mavsdk::rpc::param_server::SetProtocolResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSetProtocol(::grpc::ServerContext* context, ::mavsdk::rpc::param_server::SetProtocolRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::param_server::SetProtocolResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { + ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithAsyncMethod_RetrieveParamInt : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RetrieveParamInt() { - ::grpc::Service::MarkMethodAsync(0); + ::grpc::Service::MarkMethodAsync(1); } ~WithAsyncMethod_RetrieveParamInt() override { BaseClassMustBeDerivedFromService(this); @@ -428,7 +490,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRetrieveParamInt(::grpc::ServerContext* context, ::mavsdk::rpc::param_server::RetrieveParamIntRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::param_server::RetrieveParamIntResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(0, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -437,7 +499,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_ProvideParamInt() { - ::grpc::Service::MarkMethodAsync(1); + ::grpc::Service::MarkMethodAsync(2); } ~WithAsyncMethod_ProvideParamInt() override { BaseClassMustBeDerivedFromService(this); @@ -448,7 +510,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestProvideParamInt(::grpc::ServerContext* context, ::mavsdk::rpc::param_server::ProvideParamIntRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::param_server::ProvideParamIntResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -457,7 +519,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RetrieveParamFloat() { - ::grpc::Service::MarkMethodAsync(2); + ::grpc::Service::MarkMethodAsync(3); } ~WithAsyncMethod_RetrieveParamFloat() override { BaseClassMustBeDerivedFromService(this); @@ -468,7 +530,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRetrieveParamFloat(::grpc::ServerContext* context, ::mavsdk::rpc::param_server::RetrieveParamFloatRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::param_server::RetrieveParamFloatResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -477,7 +539,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_ProvideParamFloat() { - ::grpc::Service::MarkMethodAsync(3); + ::grpc::Service::MarkMethodAsync(4); } ~WithAsyncMethod_ProvideParamFloat() override { BaseClassMustBeDerivedFromService(this); @@ -488,7 +550,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestProvideParamFloat(::grpc::ServerContext* context, ::mavsdk::rpc::param_server::ProvideParamFloatRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::param_server::ProvideParamFloatResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(4, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -497,7 +559,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RetrieveParamCustom() { - ::grpc::Service::MarkMethodAsync(4); + ::grpc::Service::MarkMethodAsync(5); } ~WithAsyncMethod_RetrieveParamCustom() override { BaseClassMustBeDerivedFromService(this); @@ -508,7 +570,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRetrieveParamCustom(::grpc::ServerContext* context, ::mavsdk::rpc::param_server::RetrieveParamCustomRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::param_server::RetrieveParamCustomResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(4, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(5, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -517,7 +579,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_ProvideParamCustom() { - ::grpc::Service::MarkMethodAsync(5); + ::grpc::Service::MarkMethodAsync(6); } ~WithAsyncMethod_ProvideParamCustom() override { BaseClassMustBeDerivedFromService(this); @@ -528,7 +590,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestProvideParamCustom(::grpc::ServerContext* context, ::mavsdk::rpc::param_server::ProvideParamCustomRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::param_server::ProvideParamCustomResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(5, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(6, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -537,7 +599,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_RetrieveAllParams() { - ::grpc::Service::MarkMethodAsync(6); + ::grpc::Service::MarkMethodAsync(7); } ~WithAsyncMethod_RetrieveAllParams() override { BaseClassMustBeDerivedFromService(this); @@ -548,7 +610,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRetrieveAllParams(::grpc::ServerContext* context, ::mavsdk::rpc::param_server::RetrieveAllParamsRequest* request, ::grpc::ServerAsyncResponseWriter< ::mavsdk::rpc::param_server::RetrieveAllParamsResponse>* response, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncUnary(6, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(7, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -557,7 +619,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeChangedParamInt() { - ::grpc::Service::MarkMethodAsync(7); + ::grpc::Service::MarkMethodAsync(8); } ~WithAsyncMethod_SubscribeChangedParamInt() override { BaseClassMustBeDerivedFromService(this); @@ -568,7 +630,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeChangedParamInt(::grpc::ServerContext* context, ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::param_server::ChangedParamIntResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -577,7 +639,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeChangedParamFloat() { - ::grpc::Service::MarkMethodAsync(8); + ::grpc::Service::MarkMethodAsync(9); } ~WithAsyncMethod_SubscribeChangedParamFloat() override { BaseClassMustBeDerivedFromService(this); @@ -588,7 +650,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeChangedParamFloat(::grpc::ServerContext* context, ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::param_server::ChangedParamFloatResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -597,7 +659,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithAsyncMethod_SubscribeChangedParamCustom() { - ::grpc::Service::MarkMethodAsync(9); + ::grpc::Service::MarkMethodAsync(10); } ~WithAsyncMethod_SubscribeChangedParamCustom() override { BaseClassMustBeDerivedFromService(this); @@ -608,23 +670,50 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeChangedParamCustom(::grpc::ServerContext* context, ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* request, ::grpc::ServerAsyncWriter< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(10, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + typedef WithAsyncMethod_SetProtocol > > > > > > > > > > AsyncService; + template + class WithCallbackMethod_SetProtocol : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithCallbackMethod_SetProtocol() { + ::grpc::Service::MarkMethodCallback(0, + new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::SetProtocolRequest, ::mavsdk::rpc::param_server::SetProtocolResponse>( + [this]( + ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::param_server::SetProtocolRequest* request, ::mavsdk::rpc::param_server::SetProtocolResponse* response) { return this->SetProtocol(context, request, response); }));} + void SetMessageAllocatorFor_SetProtocol( + ::grpc::MessageAllocator< ::mavsdk::rpc::param_server::SetProtocolRequest, ::mavsdk::rpc::param_server::SetProtocolResponse>* allocator) { + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(0); + static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::SetProtocolRequest, ::mavsdk::rpc::param_server::SetProtocolResponse>*>(handler) + ->SetMessageAllocator(allocator); + } + ~WithCallbackMethod_SetProtocol() override { + BaseClassMustBeDerivedFromService(this); } + // disable synchronous version of this method + ::grpc::Status SetProtocol(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SetProtocolRequest* /*request*/, ::mavsdk::rpc::param_server::SetProtocolResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + virtual ::grpc::ServerUnaryReactor* SetProtocol( + ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::param_server::SetProtocolRequest* /*request*/, ::mavsdk::rpc::param_server::SetProtocolResponse* /*response*/) { return nullptr; } }; - typedef WithAsyncMethod_RetrieveParamInt > > > > > > > > > AsyncService; template class WithCallbackMethod_RetrieveParamInt : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RetrieveParamInt() { - ::grpc::Service::MarkMethodCallback(0, + ::grpc::Service::MarkMethodCallback(1, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::RetrieveParamIntRequest, ::mavsdk::rpc::param_server::RetrieveParamIntResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::param_server::RetrieveParamIntRequest* request, ::mavsdk::rpc::param_server::RetrieveParamIntResponse* response) { return this->RetrieveParamInt(context, request, response); }));} void SetMessageAllocatorFor_RetrieveParamInt( ::grpc::MessageAllocator< ::mavsdk::rpc::param_server::RetrieveParamIntRequest, ::mavsdk::rpc::param_server::RetrieveParamIntResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(0); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(1); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::RetrieveParamIntRequest, ::mavsdk::rpc::param_server::RetrieveParamIntResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -645,13 +734,13 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_ProvideParamInt() { - ::grpc::Service::MarkMethodCallback(1, + ::grpc::Service::MarkMethodCallback(2, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::ProvideParamIntRequest, ::mavsdk::rpc::param_server::ProvideParamIntResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::param_server::ProvideParamIntRequest* request, ::mavsdk::rpc::param_server::ProvideParamIntResponse* response) { return this->ProvideParamInt(context, request, response); }));} void SetMessageAllocatorFor_ProvideParamInt( ::grpc::MessageAllocator< ::mavsdk::rpc::param_server::ProvideParamIntRequest, ::mavsdk::rpc::param_server::ProvideParamIntResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(1); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(2); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::ProvideParamIntRequest, ::mavsdk::rpc::param_server::ProvideParamIntResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -672,13 +761,13 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RetrieveParamFloat() { - ::grpc::Service::MarkMethodCallback(2, + ::grpc::Service::MarkMethodCallback(3, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::RetrieveParamFloatRequest, ::mavsdk::rpc::param_server::RetrieveParamFloatResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::param_server::RetrieveParamFloatRequest* request, ::mavsdk::rpc::param_server::RetrieveParamFloatResponse* response) { return this->RetrieveParamFloat(context, request, response); }));} void SetMessageAllocatorFor_RetrieveParamFloat( ::grpc::MessageAllocator< ::mavsdk::rpc::param_server::RetrieveParamFloatRequest, ::mavsdk::rpc::param_server::RetrieveParamFloatResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(2); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(3); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::RetrieveParamFloatRequest, ::mavsdk::rpc::param_server::RetrieveParamFloatResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -699,13 +788,13 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_ProvideParamFloat() { - ::grpc::Service::MarkMethodCallback(3, + ::grpc::Service::MarkMethodCallback(4, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::ProvideParamFloatRequest, ::mavsdk::rpc::param_server::ProvideParamFloatResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::param_server::ProvideParamFloatRequest* request, ::mavsdk::rpc::param_server::ProvideParamFloatResponse* response) { return this->ProvideParamFloat(context, request, response); }));} void SetMessageAllocatorFor_ProvideParamFloat( ::grpc::MessageAllocator< ::mavsdk::rpc::param_server::ProvideParamFloatRequest, ::mavsdk::rpc::param_server::ProvideParamFloatResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(3); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(4); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::ProvideParamFloatRequest, ::mavsdk::rpc::param_server::ProvideParamFloatResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -726,13 +815,13 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RetrieveParamCustom() { - ::grpc::Service::MarkMethodCallback(4, + ::grpc::Service::MarkMethodCallback(5, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::RetrieveParamCustomRequest, ::mavsdk::rpc::param_server::RetrieveParamCustomResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::param_server::RetrieveParamCustomRequest* request, ::mavsdk::rpc::param_server::RetrieveParamCustomResponse* response) { return this->RetrieveParamCustom(context, request, response); }));} void SetMessageAllocatorFor_RetrieveParamCustom( ::grpc::MessageAllocator< ::mavsdk::rpc::param_server::RetrieveParamCustomRequest, ::mavsdk::rpc::param_server::RetrieveParamCustomResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(4); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(5); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::RetrieveParamCustomRequest, ::mavsdk::rpc::param_server::RetrieveParamCustomResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -753,13 +842,13 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_ProvideParamCustom() { - ::grpc::Service::MarkMethodCallback(5, + ::grpc::Service::MarkMethodCallback(6, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::ProvideParamCustomRequest, ::mavsdk::rpc::param_server::ProvideParamCustomResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::param_server::ProvideParamCustomRequest* request, ::mavsdk::rpc::param_server::ProvideParamCustomResponse* response) { return this->ProvideParamCustom(context, request, response); }));} void SetMessageAllocatorFor_ProvideParamCustom( ::grpc::MessageAllocator< ::mavsdk::rpc::param_server::ProvideParamCustomRequest, ::mavsdk::rpc::param_server::ProvideParamCustomResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(5); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(6); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::ProvideParamCustomRequest, ::mavsdk::rpc::param_server::ProvideParamCustomResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -780,13 +869,13 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_RetrieveAllParams() { - ::grpc::Service::MarkMethodCallback(6, + ::grpc::Service::MarkMethodCallback(7, new ::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::RetrieveAllParamsRequest, ::mavsdk::rpc::param_server::RetrieveAllParamsResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::param_server::RetrieveAllParamsRequest* request, ::mavsdk::rpc::param_server::RetrieveAllParamsResponse* response) { return this->RetrieveAllParams(context, request, response); }));} void SetMessageAllocatorFor_RetrieveAllParams( ::grpc::MessageAllocator< ::mavsdk::rpc::param_server::RetrieveAllParamsRequest, ::mavsdk::rpc::param_server::RetrieveAllParamsResponse>* allocator) { - ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(6); + ::grpc::internal::MethodHandler* const handler = ::grpc::Service::GetHandler(7); static_cast<::grpc::internal::CallbackUnaryHandler< ::mavsdk::rpc::param_server::RetrieveAllParamsRequest, ::mavsdk::rpc::param_server::RetrieveAllParamsResponse>*>(handler) ->SetMessageAllocator(allocator); } @@ -807,7 +896,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeChangedParamInt() { - ::grpc::Service::MarkMethodCallback(7, + ::grpc::Service::MarkMethodCallback(8, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest, ::mavsdk::rpc::param_server::ChangedParamIntResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest* request) { return this->SubscribeChangedParamInt(context, request); })); @@ -829,7 +918,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeChangedParamFloat() { - ::grpc::Service::MarkMethodCallback(8, + ::grpc::Service::MarkMethodCallback(9, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest, ::mavsdk::rpc::param_server::ChangedParamFloatResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest* request) { return this->SubscribeChangedParamFloat(context, request); })); @@ -851,7 +940,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithCallbackMethod_SubscribeChangedParamCustom() { - ::grpc::Service::MarkMethodCallback(9, + ::grpc::Service::MarkMethodCallback(10, new ::grpc::internal::CallbackServerStreamingHandler< ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest, ::mavsdk::rpc::param_server::ChangedParamCustomResponse>( [this]( ::grpc::CallbackServerContext* context, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* request) { return this->SubscribeChangedParamCustom(context, request); })); @@ -867,15 +956,32 @@ class ParamServerService final { virtual ::grpc::ServerWriteReactor< ::mavsdk::rpc::param_server::ChangedParamCustomResponse>* SubscribeChangedParamCustom( ::grpc::CallbackServerContext* /*context*/, const ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest* /*request*/) { return nullptr; } }; - typedef WithCallbackMethod_RetrieveParamInt > > > > > > > > > CallbackService; + typedef WithCallbackMethod_SetProtocol > > > > > > > > > > CallbackService; typedef CallbackService ExperimentalCallbackService; template + class WithGenericMethod_SetProtocol : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithGenericMethod_SetProtocol() { + ::grpc::Service::MarkMethodGeneric(0); + } + ~WithGenericMethod_SetProtocol() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetProtocol(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SetProtocolRequest* /*request*/, ::mavsdk::rpc::param_server::SetProtocolResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + }; + template class WithGenericMethod_RetrieveParamInt : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RetrieveParamInt() { - ::grpc::Service::MarkMethodGeneric(0); + ::grpc::Service::MarkMethodGeneric(1); } ~WithGenericMethod_RetrieveParamInt() override { BaseClassMustBeDerivedFromService(this); @@ -892,7 +998,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_ProvideParamInt() { - ::grpc::Service::MarkMethodGeneric(1); + ::grpc::Service::MarkMethodGeneric(2); } ~WithGenericMethod_ProvideParamInt() override { BaseClassMustBeDerivedFromService(this); @@ -909,7 +1015,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RetrieveParamFloat() { - ::grpc::Service::MarkMethodGeneric(2); + ::grpc::Service::MarkMethodGeneric(3); } ~WithGenericMethod_RetrieveParamFloat() override { BaseClassMustBeDerivedFromService(this); @@ -926,7 +1032,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_ProvideParamFloat() { - ::grpc::Service::MarkMethodGeneric(3); + ::grpc::Service::MarkMethodGeneric(4); } ~WithGenericMethod_ProvideParamFloat() override { BaseClassMustBeDerivedFromService(this); @@ -943,7 +1049,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RetrieveParamCustom() { - ::grpc::Service::MarkMethodGeneric(4); + ::grpc::Service::MarkMethodGeneric(5); } ~WithGenericMethod_RetrieveParamCustom() override { BaseClassMustBeDerivedFromService(this); @@ -960,7 +1066,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_ProvideParamCustom() { - ::grpc::Service::MarkMethodGeneric(5); + ::grpc::Service::MarkMethodGeneric(6); } ~WithGenericMethod_ProvideParamCustom() override { BaseClassMustBeDerivedFromService(this); @@ -977,7 +1083,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_RetrieveAllParams() { - ::grpc::Service::MarkMethodGeneric(6); + ::grpc::Service::MarkMethodGeneric(7); } ~WithGenericMethod_RetrieveAllParams() override { BaseClassMustBeDerivedFromService(this); @@ -994,7 +1100,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeChangedParamInt() { - ::grpc::Service::MarkMethodGeneric(7); + ::grpc::Service::MarkMethodGeneric(8); } ~WithGenericMethod_SubscribeChangedParamInt() override { BaseClassMustBeDerivedFromService(this); @@ -1011,7 +1117,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeChangedParamFloat() { - ::grpc::Service::MarkMethodGeneric(8); + ::grpc::Service::MarkMethodGeneric(9); } ~WithGenericMethod_SubscribeChangedParamFloat() override { BaseClassMustBeDerivedFromService(this); @@ -1028,7 +1134,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithGenericMethod_SubscribeChangedParamCustom() { - ::grpc::Service::MarkMethodGeneric(9); + ::grpc::Service::MarkMethodGeneric(10); } ~WithGenericMethod_SubscribeChangedParamCustom() override { BaseClassMustBeDerivedFromService(this); @@ -1040,12 +1146,32 @@ class ParamServerService final { } }; template + class WithRawMethod_SetProtocol : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawMethod_SetProtocol() { + ::grpc::Service::MarkMethodRaw(0); + } + ~WithRawMethod_SetProtocol() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetProtocol(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SetProtocolRequest* /*request*/, ::mavsdk::rpc::param_server::SetProtocolResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + void RequestSetProtocol(::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(0, context, request, response, new_call_cq, notification_cq, tag); + } + }; + template class WithRawMethod_RetrieveParamInt : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RetrieveParamInt() { - ::grpc::Service::MarkMethodRaw(0); + ::grpc::Service::MarkMethodRaw(1); } ~WithRawMethod_RetrieveParamInt() override { BaseClassMustBeDerivedFromService(this); @@ -1056,7 +1182,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRetrieveParamInt(::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(0, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(1, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1065,7 +1191,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_ProvideParamInt() { - ::grpc::Service::MarkMethodRaw(1); + ::grpc::Service::MarkMethodRaw(2); } ~WithRawMethod_ProvideParamInt() override { BaseClassMustBeDerivedFromService(this); @@ -1076,7 +1202,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestProvideParamInt(::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(1, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(2, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1085,7 +1211,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RetrieveParamFloat() { - ::grpc::Service::MarkMethodRaw(2); + ::grpc::Service::MarkMethodRaw(3); } ~WithRawMethod_RetrieveParamFloat() override { BaseClassMustBeDerivedFromService(this); @@ -1096,7 +1222,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRetrieveParamFloat(::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(2, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(3, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1105,7 +1231,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_ProvideParamFloat() { - ::grpc::Service::MarkMethodRaw(3); + ::grpc::Service::MarkMethodRaw(4); } ~WithRawMethod_ProvideParamFloat() override { BaseClassMustBeDerivedFromService(this); @@ -1116,7 +1242,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestProvideParamFloat(::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(3, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(4, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1125,7 +1251,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RetrieveParamCustom() { - ::grpc::Service::MarkMethodRaw(4); + ::grpc::Service::MarkMethodRaw(5); } ~WithRawMethod_RetrieveParamCustom() override { BaseClassMustBeDerivedFromService(this); @@ -1136,7 +1262,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRetrieveParamCustom(::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(4, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(5, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1145,7 +1271,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_ProvideParamCustom() { - ::grpc::Service::MarkMethodRaw(5); + ::grpc::Service::MarkMethodRaw(6); } ~WithRawMethod_ProvideParamCustom() override { BaseClassMustBeDerivedFromService(this); @@ -1156,7 +1282,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestProvideParamCustom(::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(5, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(6, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1165,7 +1291,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_RetrieveAllParams() { - ::grpc::Service::MarkMethodRaw(6); + ::grpc::Service::MarkMethodRaw(7); } ~WithRawMethod_RetrieveAllParams() override { BaseClassMustBeDerivedFromService(this); @@ -1176,7 +1302,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestRetrieveAllParams(::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(6, context, request, response, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncUnary(7, context, request, response, new_call_cq, notification_cq, tag); } }; template @@ -1185,7 +1311,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeChangedParamInt() { - ::grpc::Service::MarkMethodRaw(7); + ::grpc::Service::MarkMethodRaw(8); } ~WithRawMethod_SubscribeChangedParamInt() override { BaseClassMustBeDerivedFromService(this); @@ -1196,7 +1322,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeChangedParamInt(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(7, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1205,7 +1331,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeChangedParamFloat() { - ::grpc::Service::MarkMethodRaw(8); + ::grpc::Service::MarkMethodRaw(9); } ~WithRawMethod_SubscribeChangedParamFloat() override { BaseClassMustBeDerivedFromService(this); @@ -1216,7 +1342,7 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeChangedParamFloat(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(8, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); } }; template @@ -1225,7 +1351,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawMethod_SubscribeChangedParamCustom() { - ::grpc::Service::MarkMethodRaw(9); + ::grpc::Service::MarkMethodRaw(10); } ~WithRawMethod_SubscribeChangedParamCustom() override { BaseClassMustBeDerivedFromService(this); @@ -1236,8 +1362,30 @@ class ParamServerService final { return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } void RequestSubscribeChangedParamCustom(::grpc::ServerContext* context, ::grpc::ByteBuffer* request, ::grpc::ServerAsyncWriter< ::grpc::ByteBuffer>* writer, ::grpc::CompletionQueue* new_call_cq, ::grpc::ServerCompletionQueue* notification_cq, void *tag) { - ::grpc::Service::RequestAsyncServerStreaming(9, context, request, writer, new_call_cq, notification_cq, tag); + ::grpc::Service::RequestAsyncServerStreaming(10, context, request, writer, new_call_cq, notification_cq, tag); + } + }; + template + class WithRawCallbackMethod_SetProtocol : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithRawCallbackMethod_SetProtocol() { + ::grpc::Service::MarkMethodRawCallback(0, + new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( + [this]( + ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->SetProtocol(context, request, response); })); + } + ~WithRawCallbackMethod_SetProtocol() override { + BaseClassMustBeDerivedFromService(this); + } + // disable synchronous version of this method + ::grpc::Status SetProtocol(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SetProtocolRequest* /*request*/, ::mavsdk::rpc::param_server::SetProtocolResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); } + virtual ::grpc::ServerUnaryReactor* SetProtocol( + ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/, ::grpc::ByteBuffer* /*response*/) { return nullptr; } }; template class WithRawCallbackMethod_RetrieveParamInt : public BaseClass { @@ -1245,7 +1393,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RetrieveParamInt() { - ::grpc::Service::MarkMethodRawCallback(0, + ::grpc::Service::MarkMethodRawCallback(1, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RetrieveParamInt(context, request, response); })); @@ -1267,7 +1415,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_ProvideParamInt() { - ::grpc::Service::MarkMethodRawCallback(1, + ::grpc::Service::MarkMethodRawCallback(2, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->ProvideParamInt(context, request, response); })); @@ -1289,7 +1437,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RetrieveParamFloat() { - ::grpc::Service::MarkMethodRawCallback(2, + ::grpc::Service::MarkMethodRawCallback(3, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RetrieveParamFloat(context, request, response); })); @@ -1311,7 +1459,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_ProvideParamFloat() { - ::grpc::Service::MarkMethodRawCallback(3, + ::grpc::Service::MarkMethodRawCallback(4, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->ProvideParamFloat(context, request, response); })); @@ -1333,7 +1481,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RetrieveParamCustom() { - ::grpc::Service::MarkMethodRawCallback(4, + ::grpc::Service::MarkMethodRawCallback(5, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->RetrieveParamCustom(context, request, response); })); @@ -1355,7 +1503,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_ProvideParamCustom() { - ::grpc::Service::MarkMethodRawCallback(5, + ::grpc::Service::MarkMethodRawCallback(6, new ::grpc::internal::CallbackUnaryHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const ::grpc::ByteBuffer* request, ::grpc::ByteBuffer* response) { return this->ProvideParamCustom(context, request, response); })); @@ -1377,7 +1525,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_RetrieveAllParams() { - ::grpc::Service::MarkMethodRawCallback(6, + ::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->RetrieveAllParams(context, request, response); })); @@ -1399,7 +1547,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeChangedParamInt() { - ::grpc::Service::MarkMethodRawCallback(7, + ::grpc::Service::MarkMethodRawCallback(8, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeChangedParamInt(context, request); })); @@ -1421,7 +1569,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeChangedParamFloat() { - ::grpc::Service::MarkMethodRawCallback(8, + ::grpc::Service::MarkMethodRawCallback(9, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeChangedParamFloat(context, request); })); @@ -1443,7 +1591,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithRawCallbackMethod_SubscribeChangedParamCustom() { - ::grpc::Service::MarkMethodRawCallback(9, + ::grpc::Service::MarkMethodRawCallback(10, new ::grpc::internal::CallbackServerStreamingHandler< ::grpc::ByteBuffer, ::grpc::ByteBuffer>( [this]( ::grpc::CallbackServerContext* context, const::grpc::ByteBuffer* request) { return this->SubscribeChangedParamCustom(context, request); })); @@ -1460,12 +1608,39 @@ class ParamServerService final { ::grpc::CallbackServerContext* /*context*/, const ::grpc::ByteBuffer* /*request*/) { return nullptr; } }; template + class WithStreamedUnaryMethod_SetProtocol : public BaseClass { + private: + void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} + public: + WithStreamedUnaryMethod_SetProtocol() { + ::grpc::Service::MarkMethodStreamed(0, + new ::grpc::internal::StreamedUnaryHandler< + ::mavsdk::rpc::param_server::SetProtocolRequest, ::mavsdk::rpc::param_server::SetProtocolResponse>( + [this](::grpc::ServerContext* context, + ::grpc::ServerUnaryStreamer< + ::mavsdk::rpc::param_server::SetProtocolRequest, ::mavsdk::rpc::param_server::SetProtocolResponse>* streamer) { + return this->StreamedSetProtocol(context, + streamer); + })); + } + ~WithStreamedUnaryMethod_SetProtocol() override { + BaseClassMustBeDerivedFromService(this); + } + // disable regular version of this method + ::grpc::Status SetProtocol(::grpc::ServerContext* /*context*/, const ::mavsdk::rpc::param_server::SetProtocolRequest* /*request*/, ::mavsdk::rpc::param_server::SetProtocolResponse* /*response*/) override { + abort(); + return ::grpc::Status(::grpc::StatusCode::UNIMPLEMENTED, ""); + } + // replace default version of method with streamed unary + virtual ::grpc::Status StreamedSetProtocol(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::param_server::SetProtocolRequest,::mavsdk::rpc::param_server::SetProtocolResponse>* server_unary_streamer) = 0; + }; + template class WithStreamedUnaryMethod_RetrieveParamInt : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RetrieveParamInt() { - ::grpc::Service::MarkMethodStreamed(0, + ::grpc::Service::MarkMethodStreamed(1, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::param_server::RetrieveParamIntRequest, ::mavsdk::rpc::param_server::RetrieveParamIntResponse>( [this](::grpc::ServerContext* context, @@ -1492,7 +1667,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_ProvideParamInt() { - ::grpc::Service::MarkMethodStreamed(1, + ::grpc::Service::MarkMethodStreamed(2, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::param_server::ProvideParamIntRequest, ::mavsdk::rpc::param_server::ProvideParamIntResponse>( [this](::grpc::ServerContext* context, @@ -1519,7 +1694,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RetrieveParamFloat() { - ::grpc::Service::MarkMethodStreamed(2, + ::grpc::Service::MarkMethodStreamed(3, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::param_server::RetrieveParamFloatRequest, ::mavsdk::rpc::param_server::RetrieveParamFloatResponse>( [this](::grpc::ServerContext* context, @@ -1546,7 +1721,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_ProvideParamFloat() { - ::grpc::Service::MarkMethodStreamed(3, + ::grpc::Service::MarkMethodStreamed(4, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::param_server::ProvideParamFloatRequest, ::mavsdk::rpc::param_server::ProvideParamFloatResponse>( [this](::grpc::ServerContext* context, @@ -1573,7 +1748,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RetrieveParamCustom() { - ::grpc::Service::MarkMethodStreamed(4, + ::grpc::Service::MarkMethodStreamed(5, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::param_server::RetrieveParamCustomRequest, ::mavsdk::rpc::param_server::RetrieveParamCustomResponse>( [this](::grpc::ServerContext* context, @@ -1600,7 +1775,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_ProvideParamCustom() { - ::grpc::Service::MarkMethodStreamed(5, + ::grpc::Service::MarkMethodStreamed(6, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::param_server::ProvideParamCustomRequest, ::mavsdk::rpc::param_server::ProvideParamCustomResponse>( [this](::grpc::ServerContext* context, @@ -1627,7 +1802,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithStreamedUnaryMethod_RetrieveAllParams() { - ::grpc::Service::MarkMethodStreamed(6, + ::grpc::Service::MarkMethodStreamed(7, new ::grpc::internal::StreamedUnaryHandler< ::mavsdk::rpc::param_server::RetrieveAllParamsRequest, ::mavsdk::rpc::param_server::RetrieveAllParamsResponse>( [this](::grpc::ServerContext* context, @@ -1648,14 +1823,14 @@ class ParamServerService final { // replace default version of method with streamed unary virtual ::grpc::Status StreamedRetrieveAllParams(::grpc::ServerContext* context, ::grpc::ServerUnaryStreamer< ::mavsdk::rpc::param_server::RetrieveAllParamsRequest,::mavsdk::rpc::param_server::RetrieveAllParamsResponse>* server_unary_streamer) = 0; }; - typedef WithStreamedUnaryMethod_RetrieveParamInt > > > > > > StreamedUnaryService; + typedef WithStreamedUnaryMethod_SetProtocol > > > > > > > StreamedUnaryService; template class WithSplitStreamingMethod_SubscribeChangedParamInt : public BaseClass { private: void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeChangedParamInt() { - ::grpc::Service::MarkMethodStreamed(7, + ::grpc::Service::MarkMethodStreamed(8, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest, ::mavsdk::rpc::param_server::ChangedParamIntResponse>( [this](::grpc::ServerContext* context, @@ -1682,7 +1857,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeChangedParamFloat() { - ::grpc::Service::MarkMethodStreamed(8, + ::grpc::Service::MarkMethodStreamed(9, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest, ::mavsdk::rpc::param_server::ChangedParamFloatResponse>( [this](::grpc::ServerContext* context, @@ -1709,7 +1884,7 @@ class ParamServerService final { void BaseClassMustBeDerivedFromService(const Service* /*service*/) {} public: WithSplitStreamingMethod_SubscribeChangedParamCustom() { - ::grpc::Service::MarkMethodStreamed(9, + ::grpc::Service::MarkMethodStreamed(10, new ::grpc::internal::SplitServerStreamingHandler< ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest, ::mavsdk::rpc::param_server::ChangedParamCustomResponse>( [this](::grpc::ServerContext* context, @@ -1731,7 +1906,7 @@ class ParamServerService final { virtual ::grpc::Status StreamedSubscribeChangedParamCustom(::grpc::ServerContext* context, ::grpc::ServerSplitStreamer< ::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest,::mavsdk::rpc::param_server::ChangedParamCustomResponse>* server_split_streamer) = 0; }; typedef WithSplitStreamingMethod_SubscribeChangedParamInt > > SplitStreamedService; - typedef WithStreamedUnaryMethod_RetrieveParamInt > > > > > > > > > StreamedService; + typedef WithStreamedUnaryMethod_SetProtocol > > > > > > > > > > StreamedService; }; } // namespace param_server diff --git a/src/mavsdk_server/src/generated/param_server/param_server.pb.cc b/src/mavsdk_server/src/generated/param_server/param_server.pb.cc index d73273358c..659ab660a8 100644 --- a/src/mavsdk_server/src/generated/param_server/param_server.pb.cc +++ b/src/mavsdk_server/src/generated/param_server/param_server.pb.cc @@ -60,6 +60,25 @@ struct SubscribeChangedParamCustomRequestDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SubscribeChangedParamCustomRequestDefaultTypeInternal _SubscribeChangedParamCustomRequest_default_instance_; +inline constexpr SetProtocolRequest::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : extended_protocol_{false}, + _cached_size_{0} {} + +template +PROTOBUF_CONSTEXPR SetProtocolRequest::SetProtocolRequest(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct SetProtocolRequestDefaultTypeInternal { + PROTOBUF_CONSTEXPR SetProtocolRequestDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SetProtocolRequestDefaultTypeInternal() {} + union { + SetProtocolRequest _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetProtocolRequestDefaultTypeInternal _SetProtocolRequest_default_instance_; + inline constexpr RetrieveParamIntRequest::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : name_( @@ -293,6 +312,25 @@ struct CustomParamDefaultTypeInternal { PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 CustomParamDefaultTypeInternal _CustomParam_default_instance_; +inline constexpr SetProtocolResponse::Impl_::Impl_( + ::_pbi::ConstantInitialized) noexcept + : _cached_size_{0}, + param_server_result_{nullptr} {} + +template +PROTOBUF_CONSTEXPR SetProtocolResponse::SetProtocolResponse(::_pbi::ConstantInitialized) + : _impl_(::_pbi::ConstantInitialized()) {} +struct SetProtocolResponseDefaultTypeInternal { + PROTOBUF_CONSTEXPR SetProtocolResponseDefaultTypeInternal() : _instance(::_pbi::ConstantInitialized{}) {} + ~SetProtocolResponseDefaultTypeInternal() {} + union { + SetProtocolResponse _instance; + }; +}; + +PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT + PROTOBUF_ATTRIBUTE_INIT_PRIORITY1 SetProtocolResponseDefaultTypeInternal _SetProtocolResponse_default_instance_; + inline constexpr RetrieveParamIntResponse::Impl_::Impl_( ::_pbi::ConstantInitialized) noexcept : _cached_size_{0}, @@ -511,13 +549,32 @@ PROTOBUF_ATTRIBUTE_NO_DESTROY PROTOBUF_CONSTINIT } // namespace param_server } // namespace rpc } // namespace mavsdk -static ::_pb::Metadata file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[25]; +static ::_pb::Metadata file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[27]; static const ::_pb::EnumDescriptor* file_level_enum_descriptors_param_5fserver_2fparam_5fserver_2eproto[1]; static constexpr const ::_pb::ServiceDescriptor** file_level_service_descriptors_param_5fserver_2fparam_5fserver_2eproto = nullptr; const ::uint32_t TableStruct_param_5fserver_2fparam_5fserver_2eproto::offsets[] PROTOBUF_SECTION_VARIABLE( protodesc_cold) = { ~0u, // no _has_bits_ + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::param_server::SetProtocolRequest, _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::param_server::SetProtocolRequest, _impl_.extended_protocol_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::param_server::SetProtocolResponse, _impl_._has_bits_), + PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::param_server::SetProtocolResponse, _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::param_server::SetProtocolResponse, _impl_.param_server_result_), + 0, + ~0u, // no _has_bits_ PROTOBUF_FIELD_OFFSET(::mavsdk::rpc::param_server::RetrieveParamIntRequest, _internal_metadata_), ~0u, // no _extensions_ ~0u, // no _oneof_case_ @@ -767,34 +824,38 @@ const ::uint32_t TableStruct_param_5fserver_2fparam_5fserver_2eproto::offsets[] static const ::_pbi::MigrationSchema schemas[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { - {0, -1, -1, sizeof(::mavsdk::rpc::param_server::RetrieveParamIntRequest)}, - {9, 19, -1, sizeof(::mavsdk::rpc::param_server::RetrieveParamIntResponse)}, - {21, -1, -1, sizeof(::mavsdk::rpc::param_server::ProvideParamIntRequest)}, - {31, 40, -1, sizeof(::mavsdk::rpc::param_server::ProvideParamIntResponse)}, - {41, -1, -1, sizeof(::mavsdk::rpc::param_server::RetrieveParamFloatRequest)}, - {50, 60, -1, sizeof(::mavsdk::rpc::param_server::RetrieveParamFloatResponse)}, - {62, -1, -1, sizeof(::mavsdk::rpc::param_server::ProvideParamFloatRequest)}, - {72, 81, -1, sizeof(::mavsdk::rpc::param_server::ProvideParamFloatResponse)}, - {82, -1, -1, sizeof(::mavsdk::rpc::param_server::RetrieveParamCustomRequest)}, - {91, 101, -1, sizeof(::mavsdk::rpc::param_server::RetrieveParamCustomResponse)}, - {103, -1, -1, sizeof(::mavsdk::rpc::param_server::ProvideParamCustomRequest)}, - {113, 122, -1, sizeof(::mavsdk::rpc::param_server::ProvideParamCustomResponse)}, - {123, -1, -1, sizeof(::mavsdk::rpc::param_server::RetrieveAllParamsRequest)}, - {131, 140, -1, sizeof(::mavsdk::rpc::param_server::RetrieveAllParamsResponse)}, - {141, -1, -1, sizeof(::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest)}, - {149, 158, -1, sizeof(::mavsdk::rpc::param_server::ChangedParamIntResponse)}, - {159, -1, -1, sizeof(::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest)}, - {167, 176, -1, sizeof(::mavsdk::rpc::param_server::ChangedParamFloatResponse)}, - {177, -1, -1, sizeof(::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest)}, - {185, 194, -1, sizeof(::mavsdk::rpc::param_server::ChangedParamCustomResponse)}, - {195, -1, -1, sizeof(::mavsdk::rpc::param_server::IntParam)}, - {205, -1, -1, sizeof(::mavsdk::rpc::param_server::FloatParam)}, - {215, -1, -1, sizeof(::mavsdk::rpc::param_server::CustomParam)}, - {225, -1, -1, sizeof(::mavsdk::rpc::param_server::AllParams)}, - {236, -1, -1, sizeof(::mavsdk::rpc::param_server::ParamServerResult)}, + {0, -1, -1, sizeof(::mavsdk::rpc::param_server::SetProtocolRequest)}, + {9, 18, -1, sizeof(::mavsdk::rpc::param_server::SetProtocolResponse)}, + {19, -1, -1, sizeof(::mavsdk::rpc::param_server::RetrieveParamIntRequest)}, + {28, 38, -1, sizeof(::mavsdk::rpc::param_server::RetrieveParamIntResponse)}, + {40, -1, -1, sizeof(::mavsdk::rpc::param_server::ProvideParamIntRequest)}, + {50, 59, -1, sizeof(::mavsdk::rpc::param_server::ProvideParamIntResponse)}, + {60, -1, -1, sizeof(::mavsdk::rpc::param_server::RetrieveParamFloatRequest)}, + {69, 79, -1, sizeof(::mavsdk::rpc::param_server::RetrieveParamFloatResponse)}, + {81, -1, -1, sizeof(::mavsdk::rpc::param_server::ProvideParamFloatRequest)}, + {91, 100, -1, sizeof(::mavsdk::rpc::param_server::ProvideParamFloatResponse)}, + {101, -1, -1, sizeof(::mavsdk::rpc::param_server::RetrieveParamCustomRequest)}, + {110, 120, -1, sizeof(::mavsdk::rpc::param_server::RetrieveParamCustomResponse)}, + {122, -1, -1, sizeof(::mavsdk::rpc::param_server::ProvideParamCustomRequest)}, + {132, 141, -1, sizeof(::mavsdk::rpc::param_server::ProvideParamCustomResponse)}, + {142, -1, -1, sizeof(::mavsdk::rpc::param_server::RetrieveAllParamsRequest)}, + {150, 159, -1, sizeof(::mavsdk::rpc::param_server::RetrieveAllParamsResponse)}, + {160, -1, -1, sizeof(::mavsdk::rpc::param_server::SubscribeChangedParamIntRequest)}, + {168, 177, -1, sizeof(::mavsdk::rpc::param_server::ChangedParamIntResponse)}, + {178, -1, -1, sizeof(::mavsdk::rpc::param_server::SubscribeChangedParamFloatRequest)}, + {186, 195, -1, sizeof(::mavsdk::rpc::param_server::ChangedParamFloatResponse)}, + {196, -1, -1, sizeof(::mavsdk::rpc::param_server::SubscribeChangedParamCustomRequest)}, + {204, 213, -1, sizeof(::mavsdk::rpc::param_server::ChangedParamCustomResponse)}, + {214, -1, -1, sizeof(::mavsdk::rpc::param_server::IntParam)}, + {224, -1, -1, sizeof(::mavsdk::rpc::param_server::FloatParam)}, + {234, -1, -1, sizeof(::mavsdk::rpc::param_server::CustomParam)}, + {244, -1, -1, sizeof(::mavsdk::rpc::param_server::AllParams)}, + {255, -1, -1, sizeof(::mavsdk::rpc::param_server::ParamServerResult)}, }; static const ::_pb::Message* const file_default_instances[] = { + &::mavsdk::rpc::param_server::_SetProtocolRequest_default_instance_._instance, + &::mavsdk::rpc::param_server::_SetProtocolResponse_default_instance_._instance, &::mavsdk::rpc::param_server::_RetrieveParamIntRequest_default_instance_._instance, &::mavsdk::rpc::param_server::_RetrieveParamIntResponse_default_instance_._instance, &::mavsdk::rpc::param_server::_ProvideParamIntRequest_default_instance_._instance, @@ -824,93 +885,100 @@ static const ::_pb::Message* const file_default_instances[] = { const char descriptor_table_protodef_param_5fserver_2fparam_5fserver_2eproto[] PROTOBUF_SECTION_VARIABLE(protodesc_cold) = { "\n\037param_server/param_server.proto\022\027mavsd" "k.rpc.param_server\032\024mavsdk_options.proto" - "\"\'\n\027RetrieveParamIntRequest\022\014\n\004name\030\001 \001(" - "\t\"r\n\030RetrieveParamIntResponse\022G\n\023param_s" - "erver_result\030\001 \001(\0132*.mavsdk.rpc.param_se" - "rver.ParamServerResult\022\r\n\005value\030\002 \001(\005\"5\n" - "\026ProvideParamIntRequest\022\014\n\004name\030\001 \001(\t\022\r\n" - "\005value\030\002 \001(\005\"b\n\027ProvideParamIntResponse\022" - "G\n\023param_server_result\030\001 \001(\0132*.mavsdk.rp" - "c.param_server.ParamServerResult\")\n\031Retr" - "ieveParamFloatRequest\022\014\n\004name\030\001 \001(\t\"t\n\032R" - "etrieveParamFloatResponse\022G\n\023param_serve" - "r_result\030\001 \001(\0132*.mavsdk.rpc.param_server" - ".ParamServerResult\022\r\n\005value\030\002 \001(\002\"7\n\030Pro" - "videParamFloatRequest\022\014\n\004name\030\001 \001(\t\022\r\n\005v" - "alue\030\002 \001(\002\"d\n\031ProvideParamFloatResponse\022" - "G\n\023param_server_result\030\001 \001(\0132*.mavsdk.rp" - "c.param_server.ParamServerResult\"*\n\032Retr" - "ieveParamCustomRequest\022\014\n\004name\030\001 \001(\t\"u\n\033" - "RetrieveParamCustomResponse\022G\n\023param_ser" - "ver_result\030\001 \001(\0132*.mavsdk.rpc.param_serv" - "er.ParamServerResult\022\r\n\005value\030\002 \001(\t\"8\n\031P" - "rovideParamCustomRequest\022\014\n\004name\030\001 \001(\t\022\r" - "\n\005value\030\002 \001(\t\"e\n\032ProvideParamCustomRespo" - "nse\022G\n\023param_server_result\030\001 \001(\0132*.mavsd" - "k.rpc.param_server.ParamServerResult\"\032\n\030" - "RetrieveAllParamsRequest\"O\n\031RetrieveAllP" - "aramsResponse\0222\n\006params\030\001 \001(\0132\".mavsdk.r" - "pc.param_server.AllParams\"!\n\037SubscribeCh" - "angedParamIntRequest\"K\n\027ChangedParamIntR" - "esponse\0220\n\005param\030\001 \001(\0132!.mavsdk.rpc.para" - "m_server.IntParam\"#\n!SubscribeChangedPar" - "amFloatRequest\"O\n\031ChangedParamFloatRespo" - "nse\0222\n\005param\030\001 \001(\0132#.mavsdk.rpc.param_se" - "rver.FloatParam\"$\n\"SubscribeChangedParam" - "CustomRequest\"Q\n\032ChangedParamCustomRespo" - "nse\0223\n\005param\030\001 \001(\0132$.mavsdk.rpc.param_se" - "rver.CustomParam\"\'\n\010IntParam\022\014\n\004name\030\001 \001" - "(\t\022\r\n\005value\030\002 \001(\005\")\n\nFloatParam\022\014\n\004name\030" - "\001 \001(\t\022\r\n\005value\030\002 \001(\002\"*\n\013CustomParam\022\014\n\004n" - "ame\030\001 \001(\t\022\r\n\005value\030\002 \001(\t\"\272\001\n\tAllParams\0225" - "\n\nint_params\030\001 \003(\0132!.mavsdk.rpc.param_se" - "rver.IntParam\0229\n\014float_params\030\002 \003(\0132#.ma" - "vsdk.rpc.param_server.FloatParam\022;\n\rcust" - "om_params\030\003 \003(\0132$.mavsdk.rpc.param_serve" - "r.CustomParam\"\241\002\n\021ParamServerResult\022A\n\006r" - "esult\030\001 \001(\01621.mavsdk.rpc.param_server.Pa" - "ramServerResult.Result\022\022\n\nresult_str\030\002 \001" - "(\t\"\264\001\n\006Result\022\022\n\016RESULT_UNKNOWN\020\000\022\022\n\016RES" - "ULT_SUCCESS\020\001\022\024\n\020RESULT_NOT_FOUND\020\002\022\025\n\021R" - "ESULT_WRONG_TYPE\020\003\022\036\n\032RESULT_PARAM_NAME_" - "TOO_LONG\020\004\022\024\n\020RESULT_NO_SYSTEM\020\005\022\037\n\033RESU" - "LT_PARAM_VALUE_TOO_LONG\020\0062\354\n\n\022ParamServe" - "rService\022}\n\020RetrieveParamInt\0220.mavsdk.rp" - "c.param_server.RetrieveParamIntRequest\0321" - ".mavsdk.rpc.param_server.RetrieveParamIn" - "tResponse\"\004\200\265\030\001\022z\n\017ProvideParamInt\022/.mav" - "sdk.rpc.param_server.ProvideParamIntRequ" - "est\0320.mavsdk.rpc.param_server.ProvidePar" - "amIntResponse\"\004\200\265\030\001\022\203\001\n\022RetrieveParamFlo" - "at\0222.mavsdk.rpc.param_server.RetrievePar" - "amFloatRequest\0323.mavsdk.rpc.param_server" - ".RetrieveParamFloatResponse\"\004\200\265\030\001\022\200\001\n\021Pr" - "ovideParamFloat\0221.mavsdk.rpc.param_serve" - "r.ProvideParamFloatRequest\0322.mavsdk.rpc." - "param_server.ProvideParamFloatResponse\"\004" - "\200\265\030\001\022\206\001\n\023RetrieveParamCustom\0223.mavsdk.rp" - "c.param_server.RetrieveParamCustomReques" - "t\0324.mavsdk.rpc.param_server.RetrievePara" - "mCustomResponse\"\004\200\265\030\001\022\203\001\n\022ProvideParamCu" - "stom\0222.mavsdk.rpc.param_server.ProvidePa" - "ramCustomRequest\0323.mavsdk.rpc.param_serv" - "er.ProvideParamCustomResponse\"\004\200\265\030\001\022\200\001\n\021" - "RetrieveAllParams\0221.mavsdk.rpc.param_ser" - "ver.RetrieveAllParamsRequest\0322.mavsdk.rp" - "c.param_server.RetrieveAllParamsResponse" - "\"\004\200\265\030\001\022\216\001\n\030SubscribeChangedParamInt\0228.ma" - "vsdk.rpc.param_server.SubscribeChangedPa" - "ramIntRequest\0320.mavsdk.rpc.param_server." - "ChangedParamIntResponse\"\004\200\265\030\0000\001\022\224\001\n\032Subs" - "cribeChangedParamFloat\022:.mavsdk.rpc.para" - "m_server.SubscribeChangedParamFloatReque" - "st\0322.mavsdk.rpc.param_server.ChangedPara" - "mFloatResponse\"\004\200\265\030\0000\001\022\227\001\n\033SubscribeChan" - "gedParamCustom\022;.mavsdk.rpc.param_server" - ".SubscribeChangedParamCustomRequest\0323.ma" - "vsdk.rpc.param_server.ChangedParamCustom" - "Response\"\004\200\265\030\0000\001B*\n\026io.mavsdk.param_serv" - "erB\020ParamServerProtob\006proto3" + "\"/\n\022SetProtocolRequest\022\031\n\021extended_proto" + "col\030\001 \001(\010\"^\n\023SetProtocolResponse\022G\n\023para" + "m_server_result\030\001 \001(\0132*.mavsdk.rpc.param" + "_server.ParamServerResult\"\'\n\027RetrievePar" + "amIntRequest\022\014\n\004name\030\001 \001(\t\"r\n\030RetrievePa" + "ramIntResponse\022G\n\023param_server_result\030\001 " + "\001(\0132*.mavsdk.rpc.param_server.ParamServe" + "rResult\022\r\n\005value\030\002 \001(\005\"5\n\026ProvideParamIn" + "tRequest\022\014\n\004name\030\001 \001(\t\022\r\n\005value\030\002 \001(\005\"b\n" + "\027ProvideParamIntResponse\022G\n\023param_server" + "_result\030\001 \001(\0132*.mavsdk.rpc.param_server." + "ParamServerResult\")\n\031RetrieveParamFloatR" + "equest\022\014\n\004name\030\001 \001(\t\"t\n\032RetrieveParamFlo" + "atResponse\022G\n\023param_server_result\030\001 \001(\0132" + "*.mavsdk.rpc.param_server.ParamServerRes" + "ult\022\r\n\005value\030\002 \001(\002\"7\n\030ProvideParamFloatR" + "equest\022\014\n\004name\030\001 \001(\t\022\r\n\005value\030\002 \001(\002\"d\n\031P" + "rovideParamFloatResponse\022G\n\023param_server" + "_result\030\001 \001(\0132*.mavsdk.rpc.param_server." + "ParamServerResult\"*\n\032RetrieveParamCustom" + "Request\022\014\n\004name\030\001 \001(\t\"u\n\033RetrieveParamCu" + "stomResponse\022G\n\023param_server_result\030\001 \001(" + "\0132*.mavsdk.rpc.param_server.ParamServerR" + "esult\022\r\n\005value\030\002 \001(\t\"8\n\031ProvideParamCust" + "omRequest\022\014\n\004name\030\001 \001(\t\022\r\n\005value\030\002 \001(\t\"e" + "\n\032ProvideParamCustomResponse\022G\n\023param_se" + "rver_result\030\001 \001(\0132*.mavsdk.rpc.param_ser" + "ver.ParamServerResult\"\032\n\030RetrieveAllPara" + "msRequest\"O\n\031RetrieveAllParamsResponse\0222" + "\n\006params\030\001 \001(\0132\".mavsdk.rpc.param_server" + ".AllParams\"!\n\037SubscribeChangedParamIntRe" + "quest\"K\n\027ChangedParamIntResponse\0220\n\005para" + "m\030\001 \001(\0132!.mavsdk.rpc.param_server.IntPar" + "am\"#\n!SubscribeChangedParamFloatRequest\"" + "O\n\031ChangedParamFloatResponse\0222\n\005param\030\001 " + "\001(\0132#.mavsdk.rpc.param_server.FloatParam" + "\"$\n\"SubscribeChangedParamCustomRequest\"Q" + "\n\032ChangedParamCustomResponse\0223\n\005param\030\001 " + "\001(\0132$.mavsdk.rpc.param_server.CustomPara" + "m\"\'\n\010IntParam\022\014\n\004name\030\001 \001(\t\022\r\n\005value\030\002 \001" + "(\005\")\n\nFloatParam\022\014\n\004name\030\001 \001(\t\022\r\n\005value\030" + "\002 \001(\002\"*\n\013CustomParam\022\014\n\004name\030\001 \001(\t\022\r\n\005va" + "lue\030\002 \001(\t\"\272\001\n\tAllParams\0225\n\nint_params\030\001 " + "\003(\0132!.mavsdk.rpc.param_server.IntParam\0229" + "\n\014float_params\030\002 \003(\0132#.mavsdk.rpc.param_" + "server.FloatParam\022;\n\rcustom_params\030\003 \003(\013" + "2$.mavsdk.rpc.param_server.CustomParam\"\241" + "\002\n\021ParamServerResult\022A\n\006result\030\001 \001(\01621.m" + "avsdk.rpc.param_server.ParamServerResult" + ".Result\022\022\n\nresult_str\030\002 \001(\t\"\264\001\n\006Result\022\022" + "\n\016RESULT_UNKNOWN\020\000\022\022\n\016RESULT_SUCCESS\020\001\022\024" + "\n\020RESULT_NOT_FOUND\020\002\022\025\n\021RESULT_WRONG_TYP" + "E\020\003\022\036\n\032RESULT_PARAM_NAME_TOO_LONG\020\004\022\024\n\020R" + "ESULT_NO_SYSTEM\020\005\022\037\n\033RESULT_PARAM_VALUE_" + "TOO_LONG\020\0062\334\013\n\022ParamServerService\022n\n\013Set" + "Protocol\022+.mavsdk.rpc.param_server.SetPr" + "otocolRequest\032,.mavsdk.rpc.param_server." + "SetProtocolResponse\"\004\200\265\030\001\022}\n\020RetrievePar" + "amInt\0220.mavsdk.rpc.param_server.Retrieve" + "ParamIntRequest\0321.mavsdk.rpc.param_serve" + "r.RetrieveParamIntResponse\"\004\200\265\030\001\022z\n\017Prov" + "ideParamInt\022/.mavsdk.rpc.param_server.Pr" + "ovideParamIntRequest\0320.mavsdk.rpc.param_" + "server.ProvideParamIntResponse\"\004\200\265\030\001\022\203\001\n" + "\022RetrieveParamFloat\0222.mavsdk.rpc.param_s" + "erver.RetrieveParamFloatRequest\0323.mavsdk" + ".rpc.param_server.RetrieveParamFloatResp" + "onse\"\004\200\265\030\001\022\200\001\n\021ProvideParamFloat\0221.mavsd" + "k.rpc.param_server.ProvideParamFloatRequ" + "est\0322.mavsdk.rpc.param_server.ProvidePar" + "amFloatResponse\"\004\200\265\030\001\022\206\001\n\023RetrieveParamC" + "ustom\0223.mavsdk.rpc.param_server.Retrieve" + "ParamCustomRequest\0324.mavsdk.rpc.param_se" + "rver.RetrieveParamCustomResponse\"\004\200\265\030\001\022\203" + "\001\n\022ProvideParamCustom\0222.mavsdk.rpc.param" + "_server.ProvideParamCustomRequest\0323.mavs" + "dk.rpc.param_server.ProvideParamCustomRe" + "sponse\"\004\200\265\030\001\022\200\001\n\021RetrieveAllParams\0221.mav" + "sdk.rpc.param_server.RetrieveAllParamsRe" + "quest\0322.mavsdk.rpc.param_server.Retrieve" + "AllParamsResponse\"\004\200\265\030\001\022\216\001\n\030SubscribeCha" + "ngedParamInt\0228.mavsdk.rpc.param_server.S" + "ubscribeChangedParamIntRequest\0320.mavsdk." + "rpc.param_server.ChangedParamIntResponse" + "\"\004\200\265\030\0000\001\022\224\001\n\032SubscribeChangedParamFloat\022" + ":.mavsdk.rpc.param_server.SubscribeChang" + "edParamFloatRequest\0322.mavsdk.rpc.param_s" + "erver.ChangedParamFloatResponse\"\004\200\265\030\0000\001\022" + "\227\001\n\033SubscribeChangedParamCustom\022;.mavsdk" + ".rpc.param_server.SubscribeChangedParamC" + "ustomRequest\0323.mavsdk.rpc.param_server.C" + "hangedParamCustomResponse\"\004\200\265\030\0000\001B*\n\026io." + "mavsdk.param_serverB\020ParamServerProtob\006p" + "roto3" }; static const ::_pbi::DescriptorTable* const descriptor_table_param_5fserver_2fparam_5fserver_2eproto_deps[1] = { @@ -920,13 +988,13 @@ static ::absl::once_flag descriptor_table_param_5fserver_2fparam_5fserver_2eprot const ::_pbi::DescriptorTable descriptor_table_param_5fserver_2fparam_5fserver_2eproto = { false, false, - 3548, + 3805, descriptor_table_protodef_param_5fserver_2fparam_5fserver_2eproto, "param_server/param_server.proto", &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, descriptor_table_param_5fserver_2fparam_5fserver_2eproto_deps, 1, - 25, + 27, schemas, file_default_instances, TableStruct_param_5fserver_2fparam_5fserver_2eproto::offsets, @@ -982,6 +1050,382 @@ constexpr int ParamServerResult::Result_ARRAYSIZE; // (!defined(_MSC_VER) || (_MSC_VER >= 1900 && _MSC_VER < 1912)) // =================================================================== +class SetProtocolRequest::_Internal { + public: +}; + +SetProtocolRequest::SetProtocolRequest(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.param_server.SetProtocolRequest) +} +SetProtocolRequest::SetProtocolRequest( + ::google::protobuf::Arena* arena, const SetProtocolRequest& from) + : SetProtocolRequest(arena) { + MergeFrom(from); +} +inline PROTOBUF_NDEBUG_INLINE SetProtocolRequest::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void SetProtocolRequest::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.extended_protocol_ = {}; +} +SetProtocolRequest::~SetProtocolRequest() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.param_server.SetProtocolRequest) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void SetProtocolRequest::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void SetProtocolRequest::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.param_server.SetProtocolRequest) + 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_.extended_protocol_ = false; + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* SetProtocolRequest::_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> SetProtocolRequest::_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 + &_SetProtocolRequest_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // bool extended_protocol = 1; + {::_pbi::TcParser::SingularVarintNoZag1(), + {8, 63, 0, PROTOBUF_FIELD_OFFSET(SetProtocolRequest, _impl_.extended_protocol_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // bool extended_protocol = 1; + {PROTOBUF_FIELD_OFFSET(SetProtocolRequest, _impl_.extended_protocol_), 0, 0, + (0 | ::_fl::kFcSingular | ::_fl::kBool)}, + }}, + // no aux_entries + {{ + }}, +}; + +::uint8_t* SetProtocolRequest::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.param_server.SetProtocolRequest) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + // bool extended_protocol = 1; + if (this->_internal_extended_protocol() != 0) { + target = stream->EnsureSpace(target); + target = ::_pbi::WireFormatLite::WriteBoolToArray( + 1, this->_internal_extended_protocol(), 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.param_server.SetProtocolRequest) + return target; +} + +::size_t SetProtocolRequest::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.param_server.SetProtocolRequest) + ::size_t total_size = 0; + + ::uint32_t cached_has_bits = 0; + // Prevent compiler warnings about cached_has_bits being unused + (void) cached_has_bits; + + // bool extended_protocol = 1; + if (this->_internal_extended_protocol() != 0) { + total_size += 2; + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData SetProtocolRequest::_class_data_ = { + SetProtocolRequest::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* SetProtocolRequest::GetClassData() const { + return &_class_data_; +} + +void SetProtocolRequest::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.param_server.SetProtocolRequest) + ABSL_DCHECK_NE(&from, _this); + ::uint32_t cached_has_bits = 0; + (void) cached_has_bits; + + if (from._internal_extended_protocol() != 0) { + _this->_internal_set_extended_protocol(from._internal_extended_protocol()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void SetProtocolRequest::CopyFrom(const SetProtocolRequest& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.param_server.SetProtocolRequest) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool SetProtocolRequest::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* SetProtocolRequest::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void SetProtocolRequest::InternalSwap(SetProtocolRequest* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_.extended_protocol_, other->_impl_.extended_protocol_); +} + +::google::protobuf::Metadata SetProtocolRequest::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[0]); +} +// =================================================================== + +class SetProtocolResponse::_Internal { + public: + using HasBits = decltype(std::declval()._impl_._has_bits_); + static constexpr ::int32_t kHasBitsOffset = + 8 * PROTOBUF_FIELD_OFFSET(SetProtocolResponse, _impl_._has_bits_); + static const ::mavsdk::rpc::param_server::ParamServerResult& param_server_result(const SetProtocolResponse* msg); + static void set_has_param_server_result(HasBits* has_bits) { + (*has_bits)[0] |= 1u; + } +}; + +const ::mavsdk::rpc::param_server::ParamServerResult& SetProtocolResponse::_Internal::param_server_result(const SetProtocolResponse* msg) { + return *msg->_impl_.param_server_result_; +} +SetProtocolResponse::SetProtocolResponse(::google::protobuf::Arena* arena) + : ::google::protobuf::Message(arena) { + SharedCtor(arena); + // @@protoc_insertion_point(arena_constructor:mavsdk.rpc.param_server.SetProtocolResponse) +} +inline PROTOBUF_NDEBUG_INLINE SetProtocolResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, ::google::protobuf::Arena* arena, + const Impl_& from) + : _has_bits_{from._has_bits_}, + _cached_size_{0} {} + +SetProtocolResponse::SetProtocolResponse( + ::google::protobuf::Arena* arena, + const SetProtocolResponse& from) + : ::google::protobuf::Message(arena) { + SetProtocolResponse* 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_.param_server_result_ = (cached_has_bits & 0x00000001u) + ? CreateMaybeMessage<::mavsdk::rpc::param_server::ParamServerResult>(arena, *from._impl_.param_server_result_) + : nullptr; + + // @@protoc_insertion_point(copy_constructor:mavsdk.rpc.param_server.SetProtocolResponse) +} +inline PROTOBUF_NDEBUG_INLINE SetProtocolResponse::Impl_::Impl_( + ::google::protobuf::internal::InternalVisibility visibility, + ::google::protobuf::Arena* arena) + : _cached_size_{0} {} + +inline void SetProtocolResponse::SharedCtor(::_pb::Arena* arena) { + new (&_impl_) Impl_(internal_visibility(), arena); + _impl_.param_server_result_ = {}; +} +SetProtocolResponse::~SetProtocolResponse() { + // @@protoc_insertion_point(destructor:mavsdk.rpc.param_server.SetProtocolResponse) + _internal_metadata_.Delete<::google::protobuf::UnknownFieldSet>(); + SharedDtor(); +} +inline void SetProtocolResponse::SharedDtor() { + ABSL_DCHECK(GetArena() == nullptr); + delete _impl_.param_server_result_; + _impl_.~Impl_(); +} + +PROTOBUF_NOINLINE void SetProtocolResponse::Clear() { +// @@protoc_insertion_point(message_clear_start:mavsdk.rpc.param_server.SetProtocolResponse) + 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_.param_server_result_ != nullptr); + _impl_.param_server_result_->Clear(); + } + _impl_._has_bits_.Clear(); + _internal_metadata_.Clear<::google::protobuf::UnknownFieldSet>(); +} + +const char* SetProtocolResponse::_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> SetProtocolResponse::_table_ = { + { + PROTOBUF_FIELD_OFFSET(SetProtocolResponse, _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), + &_SetProtocolResponse_default_instance_._instance, + ::_pbi::TcParser::GenericFallback, // fallback + }, {{ + // .mavsdk.rpc.param_server.ParamServerResult param_server_result = 1; + {::_pbi::TcParser::FastMtS1, + {10, 0, 0, PROTOBUF_FIELD_OFFSET(SetProtocolResponse, _impl_.param_server_result_)}}, + }}, {{ + 65535, 65535 + }}, {{ + // .mavsdk.rpc.param_server.ParamServerResult param_server_result = 1; + {PROTOBUF_FIELD_OFFSET(SetProtocolResponse, _impl_.param_server_result_), _Internal::kHasBitsOffset + 0, 0, + (0 | ::_fl::kFcOptional | ::_fl::kMessage | ::_fl::kTvTable)}, + }}, {{ + {::_pbi::TcParser::GetTable<::mavsdk::rpc::param_server::ParamServerResult>()}, + }}, {{ + }}, +}; + +::uint8_t* SetProtocolResponse::_InternalSerialize( + ::uint8_t* target, + ::google::protobuf::io::EpsCopyOutputStream* stream) const { + // @@protoc_insertion_point(serialize_to_array_start:mavsdk.rpc.param_server.SetProtocolResponse) + ::uint32_t cached_has_bits = 0; + (void)cached_has_bits; + + cached_has_bits = _impl_._has_bits_[0]; + // .mavsdk.rpc.param_server.ParamServerResult param_server_result = 1; + if (cached_has_bits & 0x00000001u) { + target = ::google::protobuf::internal::WireFormatLite::InternalWriteMessage( + 1, _Internal::param_server_result(this), + _Internal::param_server_result(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.param_server.SetProtocolResponse) + return target; +} + +::size_t SetProtocolResponse::ByteSizeLong() const { +// @@protoc_insertion_point(message_byte_size_start:mavsdk.rpc.param_server.SetProtocolResponse) + ::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.param_server.ParamServerResult param_server_result = 1; + cached_has_bits = _impl_._has_bits_[0]; + if (cached_has_bits & 0x00000001u) { + total_size += + 1 + ::google::protobuf::internal::WireFormatLite::MessageSize(*_impl_.param_server_result_); + } + + return MaybeComputeUnknownFieldsSize(total_size, &_impl_._cached_size_); +} + +const ::google::protobuf::Message::ClassData SetProtocolResponse::_class_data_ = { + SetProtocolResponse::MergeImpl, + nullptr, // OnDemandRegisterArenaDtor +}; +const ::google::protobuf::Message::ClassData* SetProtocolResponse::GetClassData() const { + return &_class_data_; +} + +void SetProtocolResponse::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.param_server.SetProtocolResponse) + 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_param_server_result()->::mavsdk::rpc::param_server::ParamServerResult::MergeFrom( + from._internal_param_server_result()); + } + _this->_internal_metadata_.MergeFrom<::google::protobuf::UnknownFieldSet>(from._internal_metadata_); +} + +void SetProtocolResponse::CopyFrom(const SetProtocolResponse& from) { +// @@protoc_insertion_point(class_specific_copy_from_start:mavsdk.rpc.param_server.SetProtocolResponse) + if (&from == this) return; + Clear(); + MergeFrom(from); +} + +PROTOBUF_NOINLINE bool SetProtocolResponse::IsInitialized() const { + return true; +} + +::_pbi::CachedSize* SetProtocolResponse::AccessCachedSize() const { + return &_impl_._cached_size_; +} +void SetProtocolResponse::InternalSwap(SetProtocolResponse* PROTOBUF_RESTRICT other) { + using std::swap; + _internal_metadata_.InternalSwap(&other->_internal_metadata_); + swap(_impl_._has_bits_[0], other->_impl_._has_bits_[0]); + swap(_impl_.param_server_result_, other->_impl_.param_server_result_); +} + +::google::protobuf::Metadata SetProtocolResponse::GetMetadata() const { + return ::_pbi::AssignDescriptors( + &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[1]); +} +// =================================================================== + class RetrieveParamIntRequest::_Internal { public: }; @@ -1168,7 +1612,7 @@ void RetrieveParamIntRequest::InternalSwap(RetrieveParamIntRequest* PROTOBUF_RES ::google::protobuf::Metadata RetrieveParamIntRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[0]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[2]); } // =================================================================== @@ -1409,7 +1853,7 @@ void RetrieveParamIntResponse::InternalSwap(RetrieveParamIntResponse* PROTOBUF_R ::google::protobuf::Metadata RetrieveParamIntResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[1]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[3]); } // =================================================================== @@ -1625,7 +2069,7 @@ void ProvideParamIntRequest::InternalSwap(ProvideParamIntRequest* PROTOBUF_RESTR ::google::protobuf::Metadata ProvideParamIntRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[2]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[4]); } // =================================================================== @@ -1832,7 +2276,7 @@ void ProvideParamIntResponse::InternalSwap(ProvideParamIntResponse* PROTOBUF_RES ::google::protobuf::Metadata ProvideParamIntResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[3]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[5]); } // =================================================================== @@ -2022,7 +2466,7 @@ void RetrieveParamFloatRequest::InternalSwap(RetrieveParamFloatRequest* PROTOBUF ::google::protobuf::Metadata RetrieveParamFloatRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[4]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[6]); } // =================================================================== @@ -2277,7 +2721,7 @@ void RetrieveParamFloatResponse::InternalSwap(RetrieveParamFloatResponse* PROTOB ::google::protobuf::Metadata RetrieveParamFloatResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[5]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[7]); } // =================================================================== @@ -2507,7 +2951,7 @@ void ProvideParamFloatRequest::InternalSwap(ProvideParamFloatRequest* PROTOBUF_R ::google::protobuf::Metadata ProvideParamFloatRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[6]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[8]); } // =================================================================== @@ -2714,7 +3158,7 @@ void ProvideParamFloatResponse::InternalSwap(ProvideParamFloatResponse* PROTOBUF ::google::protobuf::Metadata ProvideParamFloatResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[7]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[9]); } // =================================================================== @@ -2904,7 +3348,7 @@ void RetrieveParamCustomRequest::InternalSwap(RetrieveParamCustomRequest* PROTOB ::google::protobuf::Metadata RetrieveParamCustomRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[8]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[10]); } // =================================================================== @@ -3144,7 +3588,7 @@ void RetrieveParamCustomResponse::InternalSwap(RetrieveParamCustomResponse* PROT ::google::protobuf::Metadata RetrieveParamCustomResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[9]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[11]); } // =================================================================== @@ -3363,7 +3807,7 @@ void ProvideParamCustomRequest::InternalSwap(ProvideParamCustomRequest* PROTOBUF ::google::protobuf::Metadata ProvideParamCustomRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[10]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[12]); } // =================================================================== @@ -3570,7 +4014,7 @@ void ProvideParamCustomResponse::InternalSwap(ProvideParamCustomResponse* PROTOB ::google::protobuf::Metadata ProvideParamCustomResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[11]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[13]); } // =================================================================== @@ -3605,7 +4049,7 @@ RetrieveAllParamsRequest::RetrieveAllParamsRequest( ::google::protobuf::Metadata RetrieveAllParamsRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[12]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[14]); } // =================================================================== @@ -3812,7 +4256,7 @@ void RetrieveAllParamsResponse::InternalSwap(RetrieveAllParamsResponse* PROTOBUF ::google::protobuf::Metadata RetrieveAllParamsResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[13]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[15]); } // =================================================================== @@ -3847,7 +4291,7 @@ SubscribeChangedParamIntRequest::SubscribeChangedParamIntRequest( ::google::protobuf::Metadata SubscribeChangedParamIntRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[14]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[16]); } // =================================================================== @@ -4054,7 +4498,7 @@ void ChangedParamIntResponse::InternalSwap(ChangedParamIntResponse* PROTOBUF_RES ::google::protobuf::Metadata ChangedParamIntResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[15]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[17]); } // =================================================================== @@ -4089,7 +4533,7 @@ SubscribeChangedParamFloatRequest::SubscribeChangedParamFloatRequest( ::google::protobuf::Metadata SubscribeChangedParamFloatRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[16]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[18]); } // =================================================================== @@ -4296,7 +4740,7 @@ void ChangedParamFloatResponse::InternalSwap(ChangedParamFloatResponse* PROTOBUF ::google::protobuf::Metadata ChangedParamFloatResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[17]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[19]); } // =================================================================== @@ -4331,7 +4775,7 @@ SubscribeChangedParamCustomRequest::SubscribeChangedParamCustomRequest( ::google::protobuf::Metadata SubscribeChangedParamCustomRequest::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[18]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[20]); } // =================================================================== @@ -4538,7 +4982,7 @@ void ChangedParamCustomResponse::InternalSwap(ChangedParamCustomResponse* PROTOB ::google::protobuf::Metadata ChangedParamCustomResponse::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[19]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[21]); } // =================================================================== @@ -4754,7 +5198,7 @@ void IntParam::InternalSwap(IntParam* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata IntParam::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[20]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[22]); } // =================================================================== @@ -4984,7 +5428,7 @@ void FloatParam::InternalSwap(FloatParam* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata FloatParam::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[21]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[23]); } // =================================================================== @@ -5203,7 +5647,7 @@ void CustomParam::InternalSwap(CustomParam* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata CustomParam::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[22]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[24]); } // =================================================================== @@ -5441,7 +5885,7 @@ void AllParams::InternalSwap(AllParams* PROTOBUF_RESTRICT other) { ::google::protobuf::Metadata AllParams::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[23]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[25]); } // =================================================================== @@ -5657,7 +6101,7 @@ void ParamServerResult::InternalSwap(ParamServerResult* PROTOBUF_RESTRICT other) ::google::protobuf::Metadata ParamServerResult::GetMetadata() const { return ::_pbi::AssignDescriptors( &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_getter, &descriptor_table_param_5fserver_2fparam_5fserver_2eproto_once, - file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[24]); + file_level_metadata_param_5fserver_2fparam_5fserver_2eproto[26]); } // @@protoc_insertion_point(namespace_scope) } // namespace param_server diff --git a/src/mavsdk_server/src/generated/param_server/param_server.pb.h b/src/mavsdk_server/src/generated/param_server/param_server.pb.h index 1703d0c815..26bd1a0226 100644 --- a/src/mavsdk_server/src/generated/param_server/param_server.pb.h +++ b/src/mavsdk_server/src/generated/param_server/param_server.pb.h @@ -127,6 +127,12 @@ extern RetrieveParamIntRequestDefaultTypeInternal _RetrieveParamIntRequest_defau class RetrieveParamIntResponse; struct RetrieveParamIntResponseDefaultTypeInternal; extern RetrieveParamIntResponseDefaultTypeInternal _RetrieveParamIntResponse_default_instance_; +class SetProtocolRequest; +struct SetProtocolRequestDefaultTypeInternal; +extern SetProtocolRequestDefaultTypeInternal _SetProtocolRequest_default_instance_; +class SetProtocolResponse; +struct SetProtocolResponseDefaultTypeInternal; +extern SetProtocolResponseDefaultTypeInternal _SetProtocolResponse_default_instance_; class SubscribeChangedParamCustomRequest; struct SubscribeChangedParamCustomRequestDefaultTypeInternal; extern SubscribeChangedParamCustomRequestDefaultTypeInternal _SubscribeChangedParamCustomRequest_default_instance_; @@ -249,7 +255,7 @@ class SubscribeChangedParamIntRequest final : &_SubscribeChangedParamIntRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 14; + 16; friend void swap(SubscribeChangedParamIntRequest& a, SubscribeChangedParamIntRequest& b) { a.Swap(&b); @@ -385,7 +391,7 @@ class SubscribeChangedParamFloatRequest final : &_SubscribeChangedParamFloatRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 16; + 18; friend void swap(SubscribeChangedParamFloatRequest& a, SubscribeChangedParamFloatRequest& b) { a.Swap(&b); @@ -521,7 +527,7 @@ class SubscribeChangedParamCustomRequest final : &_SubscribeChangedParamCustomRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 18; + 20; friend void swap(SubscribeChangedParamCustomRequest& a, SubscribeChangedParamCustomRequest& b) { a.Swap(&b); @@ -599,6 +605,181 @@ class SubscribeChangedParamCustomRequest final : friend struct ::TableStruct_param_5fserver_2fparam_5fserver_2eproto; };// ------------------------------------------------------------------- +class SetProtocolRequest final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.SetProtocolRequest) */ { + public: + inline SetProtocolRequest() : SetProtocolRequest(nullptr) {} + ~SetProtocolRequest() override; + template + explicit PROTOBUF_CONSTEXPR SetProtocolRequest(::google::protobuf::internal::ConstantInitialized); + + inline SetProtocolRequest(const SetProtocolRequest& from) + : SetProtocolRequest(nullptr, from) {} + SetProtocolRequest(SetProtocolRequest&& from) noexcept + : SetProtocolRequest() { + *this = ::std::move(from); + } + + inline SetProtocolRequest& operator=(const SetProtocolRequest& from) { + CopyFrom(from); + return *this; + } + inline SetProtocolRequest& operator=(SetProtocolRequest&& 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 SetProtocolRequest& default_instance() { + return *internal_default_instance(); + } + static inline const SetProtocolRequest* internal_default_instance() { + return reinterpret_cast( + &_SetProtocolRequest_default_instance_); + } + static constexpr int kIndexInFileMessages = + 0; + + friend void swap(SetProtocolRequest& a, SetProtocolRequest& b) { + a.Swap(&b); + } + inline void Swap(SetProtocolRequest* 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(SetProtocolRequest* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SetProtocolRequest* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const SetProtocolRequest& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const SetProtocolRequest& from) { + SetProtocolRequest::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(SetProtocolRequest* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.param_server.SetProtocolRequest"; + } + protected: + explicit SetProtocolRequest(::google::protobuf::Arena* arena); + SetProtocolRequest(::google::protobuf::Arena* arena, const SetProtocolRequest& 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 { + kExtendedProtocolFieldNumber = 1, + }; + // bool extended_protocol = 1; + void clear_extended_protocol() ; + bool extended_protocol() const; + void set_extended_protocol(bool value); + + private: + bool _internal_extended_protocol() const; + void _internal_set_extended_protocol(bool value); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.param_server.SetProtocolRequest) + 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 + 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); + bool extended_protocol_; + mutable ::google::protobuf::internal::CachedSize _cached_size_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_param_5fserver_2fparam_5fserver_2eproto; +};// ------------------------------------------------------------------- + class RetrieveParamIntRequest final : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.RetrieveParamIntRequest) */ { public: @@ -658,7 +839,7 @@ class RetrieveParamIntRequest final : &_RetrieveParamIntRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 0; + 2; friend void swap(RetrieveParamIntRequest& a, RetrieveParamIntRequest& b) { a.Swap(&b); @@ -839,7 +1020,7 @@ class RetrieveParamFloatRequest final : &_RetrieveParamFloatRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 4; + 6; friend void swap(RetrieveParamFloatRequest& a, RetrieveParamFloatRequest& b) { a.Swap(&b); @@ -1020,7 +1201,7 @@ class RetrieveParamCustomRequest final : &_RetrieveParamCustomRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 8; + 10; friend void swap(RetrieveParamCustomRequest& a, RetrieveParamCustomRequest& b) { a.Swap(&b); @@ -1200,7 +1381,7 @@ class RetrieveAllParamsRequest final : &_RetrieveAllParamsRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 12; + 14; friend void swap(RetrieveAllParamsRequest& a, RetrieveAllParamsRequest& b) { a.Swap(&b); @@ -1337,7 +1518,7 @@ class ProvideParamIntRequest final : &_ProvideParamIntRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 2; + 4; friend void swap(ProvideParamIntRequest& a, ProvideParamIntRequest& b) { a.Swap(&b); @@ -1530,7 +1711,7 @@ class ProvideParamFloatRequest final : &_ProvideParamFloatRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 6; + 8; friend void swap(ProvideParamFloatRequest& a, ProvideParamFloatRequest& b) { a.Swap(&b); @@ -1723,7 +1904,7 @@ class ProvideParamCustomRequest final : &_ProvideParamCustomRequest_default_instance_); } static constexpr int kIndexInFileMessages = - 10; + 12; friend void swap(ProvideParamCustomRequest& a, ProvideParamCustomRequest& b) { a.Swap(&b); @@ -1922,7 +2103,7 @@ class ParamServerResult final : &_ParamServerResult_default_instance_); } static constexpr int kIndexInFileMessages = - 24; + 26; friend void swap(ParamServerResult& a, ParamServerResult& b) { a.Swap(&b); @@ -2140,7 +2321,7 @@ class IntParam final : &_IntParam_default_instance_); } static constexpr int kIndexInFileMessages = - 20; + 22; friend void swap(IntParam& a, IntParam& b) { a.Swap(&b); @@ -2333,7 +2514,7 @@ class FloatParam final : &_FloatParam_default_instance_); } static constexpr int kIndexInFileMessages = - 21; + 23; friend void swap(FloatParam& a, FloatParam& b) { a.Swap(&b); @@ -2526,7 +2707,7 @@ class CustomParam final : &_CustomParam_default_instance_); } static constexpr int kIndexInFileMessages = - 22; + 24; friend void swap(CustomParam& a, CustomParam& b) { a.Swap(&b); @@ -2666,6 +2847,187 @@ class CustomParam final : friend struct ::TableStruct_param_5fserver_2fparam_5fserver_2eproto; };// ------------------------------------------------------------------- +class SetProtocolResponse final : + public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.SetProtocolResponse) */ { + public: + inline SetProtocolResponse() : SetProtocolResponse(nullptr) {} + ~SetProtocolResponse() override; + template + explicit PROTOBUF_CONSTEXPR SetProtocolResponse(::google::protobuf::internal::ConstantInitialized); + + inline SetProtocolResponse(const SetProtocolResponse& from) + : SetProtocolResponse(nullptr, from) {} + SetProtocolResponse(SetProtocolResponse&& from) noexcept + : SetProtocolResponse() { + *this = ::std::move(from); + } + + inline SetProtocolResponse& operator=(const SetProtocolResponse& from) { + CopyFrom(from); + return *this; + } + inline SetProtocolResponse& operator=(SetProtocolResponse&& 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 SetProtocolResponse& default_instance() { + return *internal_default_instance(); + } + static inline const SetProtocolResponse* internal_default_instance() { + return reinterpret_cast( + &_SetProtocolResponse_default_instance_); + } + static constexpr int kIndexInFileMessages = + 1; + + friend void swap(SetProtocolResponse& a, SetProtocolResponse& b) { + a.Swap(&b); + } + inline void Swap(SetProtocolResponse* 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(SetProtocolResponse* other) { + if (other == this) return; + ABSL_DCHECK(GetArena() == other->GetArena()); + InternalSwap(other); + } + + // implements Message ---------------------------------------------- + + SetProtocolResponse* New(::google::protobuf::Arena* arena = nullptr) const final { + return CreateMaybeMessage(arena); + } + using ::google::protobuf::Message::CopyFrom; + void CopyFrom(const SetProtocolResponse& from); + using ::google::protobuf::Message::MergeFrom; + void MergeFrom( const SetProtocolResponse& from) { + SetProtocolResponse::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(SetProtocolResponse* other); + + private: + friend class ::google::protobuf::internal::AnyMetadata; + static ::absl::string_view FullMessageName() { + return "mavsdk.rpc.param_server.SetProtocolResponse"; + } + protected: + explicit SetProtocolResponse(::google::protobuf::Arena* arena); + SetProtocolResponse(::google::protobuf::Arena* arena, const SetProtocolResponse& 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 { + kParamServerResultFieldNumber = 1, + }; + // .mavsdk.rpc.param_server.ParamServerResult param_server_result = 1; + bool has_param_server_result() const; + void clear_param_server_result() ; + const ::mavsdk::rpc::param_server::ParamServerResult& param_server_result() const; + PROTOBUF_NODISCARD ::mavsdk::rpc::param_server::ParamServerResult* release_param_server_result(); + ::mavsdk::rpc::param_server::ParamServerResult* mutable_param_server_result(); + void set_allocated_param_server_result(::mavsdk::rpc::param_server::ParamServerResult* value); + void unsafe_arena_set_allocated_param_server_result(::mavsdk::rpc::param_server::ParamServerResult* value); + ::mavsdk::rpc::param_server::ParamServerResult* unsafe_arena_release_param_server_result(); + + private: + const ::mavsdk::rpc::param_server::ParamServerResult& _internal_param_server_result() const; + ::mavsdk::rpc::param_server::ParamServerResult* _internal_mutable_param_server_result(); + + public: + // @@protoc_insertion_point(class_scope:mavsdk.rpc.param_server.SetProtocolResponse) + 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::param_server::ParamServerResult* param_server_result_; + PROTOBUF_TSAN_DECLARE_MEMBER + }; + union { Impl_ _impl_; }; + friend struct ::TableStruct_param_5fserver_2fparam_5fserver_2eproto; +};// ------------------------------------------------------------------- + class RetrieveParamIntResponse final : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:mavsdk.rpc.param_server.RetrieveParamIntResponse) */ { public: @@ -2725,7 +3087,7 @@ class RetrieveParamIntResponse final : &_RetrieveParamIntResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 1; + 3; friend void swap(RetrieveParamIntResponse& a, RetrieveParamIntResponse& b) { a.Swap(&b); @@ -2918,7 +3280,7 @@ class RetrieveParamFloatResponse final : &_RetrieveParamFloatResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 5; + 7; friend void swap(RetrieveParamFloatResponse& a, RetrieveParamFloatResponse& b) { a.Swap(&b); @@ -3111,7 +3473,7 @@ class RetrieveParamCustomResponse final : &_RetrieveParamCustomResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 9; + 11; friend void swap(RetrieveParamCustomResponse& a, RetrieveParamCustomResponse& b) { a.Swap(&b); @@ -3310,7 +3672,7 @@ class ProvideParamIntResponse final : &_ProvideParamIntResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 3; + 5; friend void swap(ProvideParamIntResponse& a, ProvideParamIntResponse& b) { a.Swap(&b); @@ -3491,7 +3853,7 @@ class ProvideParamFloatResponse final : &_ProvideParamFloatResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 7; + 9; friend void swap(ProvideParamFloatResponse& a, ProvideParamFloatResponse& b) { a.Swap(&b); @@ -3672,7 +4034,7 @@ class ProvideParamCustomResponse final : &_ProvideParamCustomResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 11; + 13; friend void swap(ProvideParamCustomResponse& a, ProvideParamCustomResponse& b) { a.Swap(&b); @@ -3853,7 +4215,7 @@ class ChangedParamIntResponse final : &_ChangedParamIntResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 15; + 17; friend void swap(ChangedParamIntResponse& a, ChangedParamIntResponse& b) { a.Swap(&b); @@ -4034,7 +4396,7 @@ class ChangedParamFloatResponse final : &_ChangedParamFloatResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 17; + 19; friend void swap(ChangedParamFloatResponse& a, ChangedParamFloatResponse& b) { a.Swap(&b); @@ -4215,7 +4577,7 @@ class ChangedParamCustomResponse final : &_ChangedParamCustomResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 19; + 21; friend void swap(ChangedParamCustomResponse& a, ChangedParamCustomResponse& b) { a.Swap(&b); @@ -4396,7 +4758,7 @@ class AllParams final : &_AllParams_default_instance_); } static constexpr int kIndexInFileMessages = - 23; + 25; friend void swap(AllParams& a, AllParams& b) { a.Swap(&b); @@ -4619,7 +4981,7 @@ class RetrieveAllParamsResponse final : &_RetrieveAllParamsResponse_default_instance_); } static constexpr int kIndexInFileMessages = - 13; + 15; friend void swap(RetrieveAllParamsResponse& a, RetrieveAllParamsResponse& b) { a.Swap(&b); @@ -4755,6 +5117,133 @@ class RetrieveAllParamsResponse final : #endif // __GNUC__ // ------------------------------------------------------------------- +// SetProtocolRequest + +// bool extended_protocol = 1; +inline void SetProtocolRequest::clear_extended_protocol() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_.extended_protocol_ = false; +} +inline bool SetProtocolRequest::extended_protocol() const { + // @@protoc_insertion_point(field_get:mavsdk.rpc.param_server.SetProtocolRequest.extended_protocol) + return _internal_extended_protocol(); +} +inline void SetProtocolRequest::set_extended_protocol(bool value) { + _internal_set_extended_protocol(value); + // @@protoc_insertion_point(field_set:mavsdk.rpc.param_server.SetProtocolRequest.extended_protocol) +} +inline bool SetProtocolRequest::_internal_extended_protocol() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + return _impl_.extended_protocol_; +} +inline void SetProtocolRequest::_internal_set_extended_protocol(bool value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + ; + _impl_.extended_protocol_ = value; +} + +// ------------------------------------------------------------------- + +// SetProtocolResponse + +// .mavsdk.rpc.param_server.ParamServerResult param_server_result = 1; +inline bool SetProtocolResponse::has_param_server_result() const { + bool value = (_impl_._has_bits_[0] & 0x00000001u) != 0; + PROTOBUF_ASSUME(!value || _impl_.param_server_result_ != nullptr); + return value; +} +inline void SetProtocolResponse::clear_param_server_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (_impl_.param_server_result_ != nullptr) _impl_.param_server_result_->Clear(); + _impl_._has_bits_[0] &= ~0x00000001u; +} +inline const ::mavsdk::rpc::param_server::ParamServerResult& SetProtocolResponse::_internal_param_server_result() const { + PROTOBUF_TSAN_READ(&_impl_._tsan_detect_race); + const ::mavsdk::rpc::param_server::ParamServerResult* p = _impl_.param_server_result_; + return p != nullptr ? *p : reinterpret_cast(::mavsdk::rpc::param_server::_ParamServerResult_default_instance_); +} +inline const ::mavsdk::rpc::param_server::ParamServerResult& SetProtocolResponse::param_server_result() const ABSL_ATTRIBUTE_LIFETIME_BOUND { + // @@protoc_insertion_point(field_get:mavsdk.rpc.param_server.SetProtocolResponse.param_server_result) + return _internal_param_server_result(); +} +inline void SetProtocolResponse::unsafe_arena_set_allocated_param_server_result(::mavsdk::rpc::param_server::ParamServerResult* value) { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (GetArena() == nullptr) { + delete reinterpret_cast<::google::protobuf::MessageLite*>(_impl_.param_server_result_); + } + _impl_.param_server_result_ = reinterpret_cast<::mavsdk::rpc::param_server::ParamServerResult*>(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.param_server.SetProtocolResponse.param_server_result) +} +inline ::mavsdk::rpc::param_server::ParamServerResult* SetProtocolResponse::release_param_server_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::param_server::ParamServerResult* released = _impl_.param_server_result_; + _impl_.param_server_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::param_server::ParamServerResult* SetProtocolResponse::unsafe_arena_release_param_server_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + // @@protoc_insertion_point(field_release:mavsdk.rpc.param_server.SetProtocolResponse.param_server_result) + + _impl_._has_bits_[0] &= ~0x00000001u; + ::mavsdk::rpc::param_server::ParamServerResult* temp = _impl_.param_server_result_; + _impl_.param_server_result_ = nullptr; + return temp; +} +inline ::mavsdk::rpc::param_server::ParamServerResult* SetProtocolResponse::_internal_mutable_param_server_result() { + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + _impl_._has_bits_[0] |= 0x00000001u; + if (_impl_.param_server_result_ == nullptr) { + auto* p = CreateMaybeMessage<::mavsdk::rpc::param_server::ParamServerResult>(GetArena()); + _impl_.param_server_result_ = reinterpret_cast<::mavsdk::rpc::param_server::ParamServerResult*>(p); + } + return _impl_.param_server_result_; +} +inline ::mavsdk::rpc::param_server::ParamServerResult* SetProtocolResponse::mutable_param_server_result() ABSL_ATTRIBUTE_LIFETIME_BOUND { + ::mavsdk::rpc::param_server::ParamServerResult* _msg = _internal_mutable_param_server_result(); + // @@protoc_insertion_point(field_mutable:mavsdk.rpc.param_server.SetProtocolResponse.param_server_result) + return _msg; +} +inline void SetProtocolResponse::set_allocated_param_server_result(::mavsdk::rpc::param_server::ParamServerResult* value) { + ::google::protobuf::Arena* message_arena = GetArena(); + PROTOBUF_TSAN_WRITE(&_impl_._tsan_detect_race); + if (message_arena == nullptr) { + delete reinterpret_cast<::mavsdk::rpc::param_server::ParamServerResult*>(_impl_.param_server_result_); + } + + if (value != nullptr) { + ::google::protobuf::Arena* submessage_arena = reinterpret_cast<::mavsdk::rpc::param_server::ParamServerResult*>(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_.param_server_result_ = reinterpret_cast<::mavsdk::rpc::param_server::ParamServerResult*>(value); + // @@protoc_insertion_point(field_set_allocated:mavsdk.rpc.param_server.SetProtocolResponse.param_server_result) +} + +// ------------------------------------------------------------------- + // RetrieveParamIntRequest // string name = 1; diff --git a/src/mavsdk_server/src/plugins/param_server/param_server_service_impl.h b/src/mavsdk_server/src/plugins/param_server/param_server_service_impl.h index abd5931988..86f1540932 100644 --- a/src/mavsdk_server/src/plugins/param_server/param_server_service_impl.h +++ b/src/mavsdk_server/src/plugins/param_server/param_server_service_impl.h @@ -210,6 +210,36 @@ class ParamServerServiceImpl final : public rpc::param_server::ParamServerServic } } + grpc::Status SetProtocol( + grpc::ServerContext* /* context */, + const rpc::param_server::SetProtocolRequest* request, + rpc::param_server::SetProtocolResponse* response) override + { + if (_lazy_plugin.maybe_plugin() == nullptr) { + if (response != nullptr) { + // For server plugins, this should never happen, they should always be + // constructible. + auto result = mavsdk::ParamServer::Result::Unknown; + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + + if (request == nullptr) { + LogWarn() << "SetProtocol sent with a null request! Ignoring..."; + return grpc::Status::OK; + } + + auto result = _lazy_plugin.maybe_plugin()->set_protocol(request->extended_protocol()); + + if (response != nullptr) { + fillResponseWithResult(response, result); + } + + return grpc::Status::OK; + } + grpc::Status RetrieveParamInt( grpc::ServerContext* /* context */, const rpc::param_server::RetrieveParamIntRequest* request, diff --git a/src/system_tests/CMakeLists.txt b/src/system_tests/CMakeLists.txt index 683c471017..2db98a1588 100644 --- a/src/system_tests/CMakeLists.txt +++ b/src/system_tests/CMakeLists.txt @@ -1,7 +1,7 @@ add_executable(system_tests_runner camera_take_photo.cpp camera_format_storage.cpp - camera_definition.cpp + camera_settings.cpp camera_list_cameras.cpp component_metadata.cpp action_arm_disarm.cpp diff --git a/src/system_tests/camera_definition.cpp b/src/system_tests/camera_definition.cpp deleted file mode 100644 index 4fd4af95ba..0000000000 --- a/src/system_tests/camera_definition.cpp +++ /dev/null @@ -1,101 +0,0 @@ -#include "mavsdk.h" -#include "plugins/camera/camera.h" -#include "plugins/camera_server/camera_server.h" -#include "plugins/ftp_server/ftp_server.h" -#include -#include -#include -#include -#include - -using namespace mavsdk; - -TEST(SystemTest, CameraDefinition) -{ - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; - - Mavsdk mavsdk_camera{Mavsdk::Configuration{ComponentType::Camera}}; - - ASSERT_EQ( - mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:17000"), - ConnectionResult::Success); - ASSERT_EQ( - mavsdk_camera.add_any_connection("udpout://127.0.0.1:17000"), ConnectionResult::Success); - - auto ftp_server = FtpServer{mavsdk_camera.server_component()}; - - EXPECT_EQ(ftp_server.set_root_dir("src/mavsdk/plugins/camera/"), FtpServer::Result::Success); - - auto camera_server = CameraServer{mavsdk_camera.server_component()}; - - CameraServer::Information information{}; - information.vendor_name = "UVC"; - information.model_name = "Logitech C270HD Webcam"; - information.firmware_version = "4.0.0"; - information.definition_file_version = 2; - information.definition_file_uri = "mavlinkftp://uvc_camera.xml"; - EXPECT_EQ(camera_server.set_information(information), CameraServer::Result::Success); - - auto param_server = ParamServer{mavsdk_camera.server_component()}; - EXPECT_EQ(param_server.provide_param_int("CAM_MODE", 0), ParamServer::Result::Success); - EXPECT_EQ(param_server.provide_param_int("BRIGHTNESS", 128), ParamServer::Result::Success); - EXPECT_EQ(param_server.provide_param_int("CONTRAST", 32), ParamServer::Result::Success); - EXPECT_EQ(param_server.provide_param_int("SATURATION", 32), ParamServer::Result::Success); - EXPECT_EQ(param_server.provide_param_int("GAIN", 64), ParamServer::Result::Success); - EXPECT_EQ(param_server.provide_param_int("SHARPNESS", 24), ParamServer::Result::Success); - EXPECT_EQ(param_server.provide_param_int("BACKLIGHT", 0), ParamServer::Result::Success); - EXPECT_EQ(param_server.provide_param_int("POWER_MODE", 0), ParamServer::Result::Success); - - // Don't use the default for these two. - EXPECT_EQ(param_server.provide_param_int("WB_MODE", 0), ParamServer::Result::Success); - EXPECT_EQ(param_server.provide_param_int("WB_TEMP", 5000), ParamServer::Result::Success); - - EXPECT_EQ(param_server.provide_param_int("EXP_MODE", 3), ParamServer::Result::Success); - EXPECT_EQ(param_server.provide_param_int("EXP_ABSOLUTE", 166), ParamServer::Result::Success); - EXPECT_EQ(param_server.provide_param_int("EXP_PRIORITY", 1), ParamServer::Result::Success); - - auto prom = std::promise>(); - auto fut = prom.get_future(); - std::once_flag flag; - - auto handle = mavsdk_groundstation.subscribe_on_new_system([&]() { - const auto system = mavsdk_groundstation.systems().back(); - if (system->is_connected() && system->has_camera()) { - std::call_once(flag, [&]() { prom.set_value(system); }); - } - }); - - ASSERT_EQ(fut.wait_for(std::chrono::seconds(5)), std::future_status::ready); - mavsdk_groundstation.unsubscribe_on_new_system(handle); - auto system = fut.get(); - - auto camera = Camera{system}; - - std::this_thread::sleep_for(std::chrono::seconds(5)); - EXPECT_EQ(camera.camera_list().cameras.size(), 1); - auto possible_setting_options = camera.get_possible_setting_options(1); - ASSERT_EQ(possible_setting_options.first, Camera::Result::Success); - - auto wb_mode = camera.get_setting(1, Camera::Setting{"WB_MODE"}); - EXPECT_EQ(wb_mode.first, Camera::Result::Success); - EXPECT_EQ(wb_mode.second.option.option_id, "0"); - - EXPECT_EQ(possible_setting_options.second.size(), 11); - - auto current_setting = camera.get_current_settings(1); - EXPECT_EQ(current_setting.first, Camera::Result::Success); - EXPECT_EQ(current_setting.second.size(), 11); - - // Now we change a setting which means the WB_TEMP param is now excluded from our options. - Camera::Setting new_setting{}; - new_setting.setting_id = "WB_MODE"; - new_setting.option = Camera::Option{"1"}; - EXPECT_EQ(camera.set_setting(1, new_setting), Camera::Result::Success); - - possible_setting_options = camera.get_possible_setting_options(1); - EXPECT_EQ(possible_setting_options.second.size(), 10); - - current_setting = camera.get_current_settings(1); - EXPECT_EQ(current_setting.first, Camera::Result::Success); - EXPECT_EQ(current_setting.second.size(), 10); -} diff --git a/src/system_tests/camera_settings.cpp b/src/system_tests/camera_settings.cpp new file mode 100644 index 0000000000..22552aba02 --- /dev/null +++ b/src/system_tests/camera_settings.cpp @@ -0,0 +1,223 @@ +#include "mavsdk.h" +#include "plugins/camera/camera.h" +#include "plugins/camera_server/camera_server.h" +#include "plugins/ftp_server/ftp_server.h" +#include +#include +#include +#include +#include + +using namespace mavsdk; + +TEST(SystemTest, CameraSettings) +{ + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; + Mavsdk mavsdk_camera{Mavsdk::Configuration{ComponentType::Camera}}; + + ASSERT_EQ( + mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:17000"), + ConnectionResult::Success); + ASSERT_EQ( + mavsdk_camera.add_any_connection("udpout://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{mavsdk_camera.server_component()}; + + EXPECT_EQ(ftp_server.set_root_dir("src/mavsdk/plugins/camera/"), FtpServer::Result::Success); + + auto camera_server = CameraServer{mavsdk_camera.server_component()}; + + CameraServer::Information information{}; + information.vendor_name = "UVC"; + information.model_name = "Logitech C270HD Webcam"; + information.firmware_version = "4.0.0"; + information.definition_file_version = 2; + information.definition_file_uri = "mavlinkftp://uvc_camera.xml"; + EXPECT_EQ(camera_server.set_information(information), CameraServer::Result::Success); + + auto param_server = ParamServer{mavsdk_camera.server_component()}; + + const auto reset_params = [&]() { + EXPECT_EQ(param_server.provide_param_int("CAM_MODE", 0), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("BRIGHTNESS", 128), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("CONTRAST", 32), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("SATURATION", 32), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("GAIN", 64), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("SHARPNESS", 24), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("BACKLIGHT", 0), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("POWER_MODE", 0), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("WB_MODE", 1), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("EXP_MODE", 3), ParamServer::Result::Success); + EXPECT_EQ( + param_server.provide_param_int("EXP_ABSOLUTE", 166), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("WB_TEMP", 4000), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("EXP_PRIORITY", 1), ParamServer::Result::Success); + }; + reset_params(); + + // Don't use the default for these two. + EXPECT_EQ(param_server.provide_param_int("WB_MODE", 0), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("WB_TEMP", 5000), ParamServer::Result::Success); + + auto prom = std::promise>(); + auto fut = prom.get_future(); + std::once_flag flag; + + auto handle = mavsdk_groundstation.subscribe_on_new_system([&]() { + const auto system = mavsdk_groundstation.systems().back(); + if (system->is_connected() && system->has_camera()) { + std::call_once(flag, [&]() { prom.set_value(system); }); + } + }); + + ASSERT_EQ(fut.wait_for(std::chrono::seconds(2)), std::future_status::ready); + mavsdk_groundstation.unsubscribe_on_new_system(handle); + auto system = fut.get(); + + auto camera = Camera{system}; + + std::this_thread::sleep_for(std::chrono::milliseconds(500)); + EXPECT_EQ(camera.camera_list().cameras.size(), 1); + auto possible_setting_options = camera.get_possible_setting_options(1); + ASSERT_EQ(possible_setting_options.first, Camera::Result::Success); + + auto wb_mode = camera.get_setting(1, Camera::Setting{"WB_MODE"}); + EXPECT_EQ(wb_mode.first, Camera::Result::Success); + EXPECT_EQ(wb_mode.second.option.option_id, "0"); + + EXPECT_EQ(possible_setting_options.second.size(), 11); + + auto current_setting = camera.get_current_settings(1); + EXPECT_EQ(current_setting.first, Camera::Result::Success); + EXPECT_EQ(current_setting.second.size(), 11); + + // Now we change a setting which means the WB_TEMP param is now excluded from our options. + Camera::Setting new_setting{}; + new_setting.setting_id = "WB_MODE"; + new_setting.option = Camera::Option{"1"}; + EXPECT_EQ(camera.set_setting(1, new_setting), Camera::Result::Success); + + possible_setting_options = camera.get_possible_setting_options(1); + EXPECT_EQ(possible_setting_options.second.size(), 10); + + current_setting = camera.get_current_settings(1); + EXPECT_EQ(current_setting.first, Camera::Result::Success); + EXPECT_EQ(current_setting.second.size(), 10); + + camera_server.subscribe_reset_settings([&](uint32_t) { + reset_params(); + EXPECT_EQ( + camera_server.respond_reset_settings(CameraServer::CameraFeedback::Ok), + CameraServer::Result::Success); + }); + + // And reset settings again. + EXPECT_EQ(camera.reset_settings(1), Camera::Result::Success); + + std::this_thread::sleep_for(std::chrono::milliseconds(500)); + + auto wb_temp = camera.get_setting(1, Camera::Setting{"WB_TEMP"}); + EXPECT_EQ(wb_temp.first, Camera::Result::Success); + EXPECT_EQ(wb_temp.second.option.option_id, "4000"); +} +TEST(SystemTest, CameraSettingsAsync) +{ + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; + Mavsdk mavsdk_camera{Mavsdk::Configuration{ComponentType::Camera}}; + + ASSERT_EQ( + mavsdk_groundstation.add_any_connection("udpin://0.0.0.0:17000"), + ConnectionResult::Success); + ASSERT_EQ( + mavsdk_camera.add_any_connection("udpout://127.0.0.1:17000"), ConnectionResult::Success); + + auto ftp_server = FtpServer{mavsdk_camera.server_component()}; + + EXPECT_EQ(ftp_server.set_root_dir("src/mavsdk/plugins/camera/"), FtpServer::Result::Success); + + auto camera_server = CameraServer{mavsdk_camera.server_component()}; + + CameraServer::Information information{}; + information.vendor_name = "UVC"; + information.model_name = "Logitech C270HD Webcam"; + information.firmware_version = "4.0.0"; + information.definition_file_version = 2; + information.definition_file_uri = "mavlinkftp://uvc_camera.xml"; + EXPECT_EQ(camera_server.set_information(information), CameraServer::Result::Success); + + auto param_server = ParamServer{mavsdk_camera.server_component()}; + + const auto reset_params = [&]() { + EXPECT_EQ(param_server.provide_param_int("CAM_MODE", 0), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("BRIGHTNESS", 128), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("CONTRAST", 32), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("SATURATION", 32), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("GAIN", 64), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("SHARPNESS", 24), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("BACKLIGHT", 0), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("POWER_MODE", 0), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("WB_MODE", 1), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("EXP_MODE", 3), ParamServer::Result::Success); + EXPECT_EQ( + param_server.provide_param_int("EXP_ABSOLUTE", 166), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("WB_TEMP", 4000), ParamServer::Result::Success); + EXPECT_EQ(param_server.provide_param_int("EXP_PRIORITY", 1), ParamServer::Result::Success); + }; + reset_params(); + + auto prom = std::promise>(); + auto fut = prom.get_future(); + std::once_flag flag; + + auto handle = mavsdk_groundstation.subscribe_on_new_system([&]() { + const auto system = mavsdk_groundstation.systems().back(); + if (system->is_connected() && system->has_camera()) { + std::call_once(flag, [&]() { prom.set_value(system); }); + } + }); + + ASSERT_EQ(fut.wait_for(std::chrono::seconds(3)), std::future_status::ready); + mavsdk_groundstation.unsubscribe_on_new_system(handle); + auto system = fut.get(); + + auto camera = Camera{system}; + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + EXPECT_EQ(camera.camera_list().cameras.size(), 1); + + bool found_wb_temp = false; + camera.subscribe_current_settings([&](const Camera::CurrentSettingsUpdate& update) { + for (auto& setting : update.current_settings) { + // std::cout << "setting: " << setting << "\n"; + if (setting.setting_id == "WB_TEMP") { + found_wb_temp = true; + } + } + }); + + // Set white balance mode to manual, so we have the WB_TEMP param available. + Camera::Setting setting{}; + setting.setting_id = "WB_MODE"; + setting.option.option_id = "0"; + EXPECT_EQ(camera.set_setting(1, setting), Camera::Result::Success); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + EXPECT_TRUE(found_wb_temp); + + bool found_exp_absolute = false; + camera.subscribe_possible_setting_options( + [&](const Camera::PossibleSettingOptionsUpdate& update) { + for (auto& setting_options : update.setting_options) { + if (setting_options.setting_id == "EXP_ABSOLUTE") { + found_exp_absolute = true; + } + } + }); + + // Set exposure mode to manual to have EXP_ABSOLUTE show up. + setting.setting_id = "EXP_MODE"; + setting.option.option_id = "1"; + EXPECT_EQ(camera.set_setting(1, setting), Camera::Result::Success); + + std::this_thread::sleep_for(std::chrono::milliseconds(100)); + EXPECT_TRUE(found_exp_absolute); +} \ No newline at end of file