From 7e30cfb5b7821bde575781e2ec429aa3b7d115ed Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 31 Oct 2023 08:18:27 +1300 Subject: [PATCH] examples: new component API Signed-off-by: Julian Oes --- examples/autopilot_server/autopilot_server.cpp | 8 +++----- examples/camera_server/camera_client.cpp | 3 +-- examples/camera_server/camera_server.cpp | 4 ++-- examples/ftp_server/ftp_server.cpp | 4 ++-- examples/gimbal_device_tester/gimbal_device_tester.cpp | 2 +- 5 files changed, 9 insertions(+), 12 deletions(-) diff --git a/examples/autopilot_server/autopilot_server.cpp b/examples/autopilot_server/autopilot_server.cpp index 77b31bfab6..8342503582 100644 --- a/examples/autopilot_server/autopilot_server.cpp +++ b/examples/autopilot_server/autopilot_server.cpp @@ -59,8 +59,7 @@ int main(int argc, char** argv) // thread as a ground station. std::thread autopilotThread([]() { mavsdk::Mavsdk mavsdkTester; - mavsdk::Mavsdk::Configuration configuration( - mavsdk::Mavsdk::Configuration::UsageType::Autopilot); + mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::ComponentType::Autopilot); mavsdkTester.set_configuration(configuration); auto result = mavsdkTester.add_any_connection("udp://127.0.0.1:14551"); @@ -69,7 +68,7 @@ int main(int argc, char** argv) } auto server_component = - mavsdkTester.server_component_by_type(Mavsdk::ServerComponentType::Autopilot); + mavsdkTester.server_component_by_type(Mavsdk::ComponentType::Autopilot); // Create server plugins auto paramServer = mavsdk::ParamServer{server_component}; @@ -148,8 +147,7 @@ int main(int argc, char** argv) // Now this is the main thread, we run client plugins to act as the GCS // to communicate with the autopilot server plugins. mavsdk::Mavsdk mavsdk; - mavsdk::Mavsdk::Configuration configuration( - mavsdk::Mavsdk::Configuration::UsageType::GroundStation); + mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::ComponentType::GroundStation); mavsdk.set_configuration(configuration); auto result = mavsdk.add_any_connection("udp://:14551"); diff --git a/examples/camera_server/camera_client.cpp b/examples/camera_server/camera_client.cpp index 58c93583d0..526c983962 100644 --- a/examples/camera_server/camera_client.cpp +++ b/examples/camera_server/camera_client.cpp @@ -10,8 +10,7 @@ int main(int argc, const char* argv[]) // we run client plugins to act as the GCS // to communicate with the camera server plugins. mavsdk::Mavsdk mavsdk; - mavsdk::Mavsdk::Configuration configuration( - mavsdk::Mavsdk::Configuration::UsageType::GroundStation); + mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::ComponentType::GroundStation); mavsdk.set_configuration(configuration); auto result = mavsdk.add_any_connection("udp://:14030"); diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index 573ee544b1..e45821c458 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -6,7 +6,7 @@ int main(int argc, char** argv) { mavsdk::Mavsdk mavsdk; - mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::Configuration::UsageType::Camera); + mavsdk::Mavsdk::Configuration configuration(mavsdk::Mavsdk::ComponentType::Camera); mavsdk.set_configuration(configuration); // 14030 is the default camera port for PX4 SITL @@ -18,7 +18,7 @@ int main(int argc, char** argv) std::cout << "Created camera server connection" << std::endl; auto camera_server = mavsdk::CameraServer{ - mavsdk.server_component_by_type(mavsdk::Mavsdk::ServerComponentType::Camera)}; + mavsdk.server_component_by_type(mavsdk::Mavsdk::ComponentType::Camera)}; // First add all subscriptions. This defines the camera capabilities. diff --git a/examples/ftp_server/ftp_server.cpp b/examples/ftp_server/ftp_server.cpp index be2afabf05..a652874ba4 100644 --- a/examples/ftp_server/ftp_server.cpp +++ b/examples/ftp_server/ftp_server.cpp @@ -29,7 +29,7 @@ int main(int argc, char** argv) } Mavsdk mavsdk; - Mavsdk::Configuration configuration(Mavsdk::Configuration::UsageType::CompanionComputer); + Mavsdk::Configuration configuration(Mavsdk::ComponentType::CompanionComputer); mavsdk.set_configuration(configuration); ConnectionResult connection_result = mavsdk.setup_udp_remote(argv[1], std::stoi(argv[2])); if (connection_result != ConnectionResult::Success) { @@ -38,7 +38,7 @@ int main(int argc, char** argv) } auto component = - mavsdk.server_component_by_type(mavsdk::Mavsdk::ServerComponentType::CompanionComputer); + mavsdk.server_component_by_type(mavsdk::Mavsdk::ComponentType::CompanionComputer); auto ftp_server = FtpServer{component}; ftp_server.set_root_dir(argv[3]); diff --git a/examples/gimbal_device_tester/gimbal_device_tester.cpp b/examples/gimbal_device_tester/gimbal_device_tester.cpp index 259946b0bd..48f1b8e578 100644 --- a/examples/gimbal_device_tester/gimbal_device_tester.cpp +++ b/examples/gimbal_device_tester/gimbal_device_tester.cpp @@ -816,7 +816,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk::Configuration config(Mavsdk::Configuration::UsageType::Autopilot); + Mavsdk::Configuration config(Mavsdk::ComponentType::Autopilot); config.set_system_id(own_sysid); mavsdk.set_configuration(config);