From ea2db2c201ed110ff15ba41fd8ae51878f7099ba Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sat, 5 Oct 2024 10:08:51 +1300 Subject: [PATCH] core: consolidate component types I doesn't make sense to have this in two places, so I pulled it out. --- .../arm_authorizer_server.cpp | 3 +- .../autopilot_server/autopilot_server.cpp | 4 +-- examples/calibrate/calibrate.cpp | 2 +- examples/camera/camera.cpp | 2 +- examples/camera_server/camera_client.cpp | 3 +- examples/camera_server/camera_server.cpp | 2 +- examples/camera_settings/camera_settings.cpp | 2 +- examples/camera_zoom/camera_zoom.cpp | 2 +- .../component_metadata/component_metadata.cpp | 2 +- examples/disconnect/disconnect.cpp | 5 ++- examples/distance_sensor/distance_sensor.cpp | 2 +- examples/events/events.cpp | 2 +- examples/fly_mission/fly_mission.cpp | 2 +- .../fly_multiple_drones.cpp | 2 +- examples/fly_qgc_mission/fly_qgc_mission.cpp | 2 +- examples/follow_me/follow_me.cpp | 2 +- examples/ftp_client/ftp_client.cpp | 2 +- examples/ftp_server/ftp_server.cpp | 2 +- examples/geofence/geofence.cpp | 2 +- examples/gimbal/gimbal.cpp | 2 +- .../gimbal_device_tester.cpp | 2 +- .../gimbal_full_control.cpp | 2 +- examples/log_callback/log_callback.cpp | 2 +- examples/log_streaming/log_streaming.cpp | 2 +- .../logfile_download/logfile_download.cpp | 2 +- examples/manual_control/manual_control.cpp | 2 +- .../mavlink_forwarding/mavlink_forwarding.cpp | 2 +- examples/mavshell/mavshell.cpp | 2 +- examples/multiple_drones/multiple_drones.cpp | 2 +- examples/offboard/offboard.cpp | 2 +- examples/set_actuator/set_actuator.cpp | 2 +- examples/sniffer/sniffer.cpp | 2 +- examples/system_info/system_info.cpp | 2 +- .../takeoff_and_land/takeoff_and_land.cpp | 2 +- examples/terminate/terminate.cpp | 2 +- examples/transponder/transponder.cpp | 2 +- examples/tune/tune.cpp | 2 +- examples/vtol_transition/vtol_transition.cpp | 2 +- examples/winch/winch.cpp | 2 +- src/integration_tests/action_goto.cpp | 2 +- src/integration_tests/action_hold.cpp | 2 +- src/integration_tests/action_hover_async.cpp | 2 +- src/integration_tests/action_hover_sync.cpp | 4 +-- .../action_takeoff_and_kill.cpp | 2 +- ...ction_transition_multicopter_fixedwing.cpp | 2 +- src/integration_tests/calibration.cpp | 14 ++++---- src/integration_tests/camera_capture_info.cpp | 2 +- src/integration_tests/camera_format.cpp | 2 +- src/integration_tests/camera_mode.cpp | 4 +-- .../camera_reset_settings.cpp | 2 +- src/integration_tests/camera_settings.cpp | 8 ++--- src/integration_tests/camera_status.cpp | 2 +- src/integration_tests/camera_take_photo.cpp | 6 ++-- .../camera_take_photo_interval.cpp | 2 +- src/integration_tests/connection.cpp | 4 +-- src/integration_tests/follow_me.cpp | 4 +-- src/integration_tests/geofence.cpp | 2 +- src/integration_tests/info.cpp | 2 +- src/integration_tests/log_files.cpp | 6 ++-- src/integration_tests/logging.cpp | 2 +- src/integration_tests/mavlink_passthrough.cpp | 2 +- src/integration_tests/mission.cpp | 2 +- .../mission_cancellation.cpp | 4 +-- .../mission_change_speed.cpp | 2 +- .../mission_raw_import_and_fly.cpp | 4 +-- .../mission_raw_mission_changed.cpp | 2 +- src/integration_tests/mission_rtl.cpp | 2 +- src/integration_tests/mission_set_current.cpp | 2 +- .../mission_takeoff_land.cpp | 2 +- .../mission_transfer_lossy.cpp | 2 +- src/integration_tests/mission_transition.cpp | 2 +- .../offboard_acceleration.cpp | 2 +- src/integration_tests/offboard_attitude.cpp | 2 +- src/integration_tests/offboard_position.cpp | 2 +- src/integration_tests/offboard_velocity.cpp | 4 +-- src/integration_tests/param.cpp | 8 ++--- src/integration_tests/statustext.cpp | 4 +-- .../system_connection_async.cpp | 2 +- .../system_multi_components.cpp | 2 +- src/integration_tests/telemetry_async.cpp | 2 +- .../telemetry_gps_origin.cpp | 2 +- src/integration_tests/telemetry_health.cpp | 2 +- src/integration_tests/telemetry_modes.cpp | 2 +- src/integration_tests/telemetry_sync.cpp | 2 +- src/mavsdk/core/CMakeLists.txt | 1 + .../core/include/mavsdk/component_type.h | 18 +++++++++++ src/mavsdk/core/include/mavsdk/mavsdk.h | 15 ++------- src/mavsdk/core/include/mavsdk/system.h | 6 +--- src/mavsdk/core/lazy_server_plugin.h | 2 +- src/mavsdk/core/mavsdk.cpp | 14 ++++---- src/mavsdk/core/mavsdk_impl.cpp | 32 +++++++++---------- src/mavsdk/core/mavsdk_impl.h | 5 +-- src/mavsdk/core/mavsdk_test.cpp | 2 +- src/mavsdk/core/system_impl.cpp | 21 ++++++++---- src/mavsdk/core/system_impl.h | 6 ++-- src/mavsdk_server/src/mavsdk_server.cpp | 2 +- src/system_tests/action_arm_disarm.cpp | 4 +-- src/system_tests/camera_take_photo.cpp | 4 +-- src/system_tests/component_metadata.cpp | 4 +-- src/system_tests/ftp_compare_files.cpp | 4 +-- src/system_tests/ftp_create_dir.cpp | 4 +-- src/system_tests/ftp_download_file.cpp | 20 ++++++------ src/system_tests/ftp_download_file_burst.cpp | 20 ++++++------ src/system_tests/ftp_list_dir.cpp | 4 +-- src/system_tests/ftp_remove_dir.cpp | 8 ++--- src/system_tests/ftp_remove_file.cpp | 12 +++---- src/system_tests/ftp_rename_file.cpp | 4 +-- src/system_tests/ftp_upload_file.cpp | 20 ++++++------ src/system_tests/mission_raw_upload.cpp | 4 +-- src/system_tests/param_custom_set_and_get.cpp | 8 ++--- src/system_tests/param_get_all.cpp | 8 ++--- src/system_tests/param_set_and_get.cpp | 8 ++--- src/system_tests/telemetry_subscription.cpp | 4 +-- 113 files changed, 248 insertions(+), 239 deletions(-) create mode 100644 src/mavsdk/core/include/mavsdk/component_type.h diff --git a/examples/arm_authorizer_server/arm_authorizer_server.cpp b/examples/arm_authorizer_server/arm_authorizer_server.cpp index 410fcbd6ae..901c1304da 100644 --- a/examples/arm_authorizer_server/arm_authorizer_server.cpp +++ b/examples/arm_authorizer_server/arm_authorizer_server.cpp @@ -18,8 +18,7 @@ int main(int argc, char** argv) } // Create mavlink component with CompanionComputer id - mavsdk::Mavsdk mavsdk{ - mavsdk::Mavsdk::Configuration{mavsdk::Mavsdk::ComponentType::GroundStation}}; + mavsdk::Mavsdk mavsdk{mavsdk::Mavsdk::Configuration{mavsdk::ComponentType::GroundStation}}; auto result = mavsdk.add_any_connection(argv[1]); diff --git a/examples/autopilot_server/autopilot_server.cpp b/examples/autopilot_server/autopilot_server.cpp index c08f78a0af..0366b62cf5 100644 --- a/examples/autopilot_server/autopilot_server.cpp +++ b/examples/autopilot_server/autopilot_server.cpp @@ -59,7 +59,7 @@ int main(int argc, char** argv) // thread as a ground station. std::thread autopilotThread([]() { mavsdk::Mavsdk mavsdkTester{ - mavsdk::Mavsdk::Configuration{mavsdk::Mavsdk::ComponentType::Autopilot}}; + mavsdk::Mavsdk::Configuration{mavsdk::ComponentType::Autopilot}}; auto result = mavsdkTester.add_any_connection("udp://127.0.0.1:14551"); if (result == mavsdk::ConnectionResult::Success) { @@ -152,7 +152,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::Configuration{Mavsdk::ComponentType::GroundStation}}; + mavsdk::Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; auto result = mavsdk.add_any_connection("udpin://0.0.0.0:14551"); if (result == mavsdk::ConnectionResult::Success) { diff --git a/examples/calibrate/calibrate.cpp b/examples/calibrate/calibrate.cpp index 48dd86fae4..d7436fd5a5 100644 --- a/examples/calibrate/calibrate.cpp +++ b/examples/calibrate/calibrate.cpp @@ -37,7 +37,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/camera/camera.cpp b/examples/camera/camera.cpp index c7e0c1844d..f7cac0e675 100644 --- a/examples/camera/camera.cpp +++ b/examples/camera/camera.cpp @@ -33,7 +33,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/camera_server/camera_client.cpp b/examples/camera_server/camera_client.cpp index 6dda0fdc2e..e115485d68 100644 --- a/examples/camera_server/camera_client.cpp +++ b/examples/camera_server/camera_client.cpp @@ -12,8 +12,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{mavsdk::Mavsdk::ComponentType::GroundStation}}; + mavsdk::Mavsdk mavsdk{mavsdk::Mavsdk::Configuration{mavsdk::ComponentType::GroundStation}}; auto result = mavsdk.add_any_connection("udp://:14030"); if (result == mavsdk::ConnectionResult::Success) { diff --git a/examples/camera_server/camera_server.cpp b/examples/camera_server/camera_server.cpp index f273d680b7..6d3d420fca 100644 --- a/examples/camera_server/camera_server.cpp +++ b/examples/camera_server/camera_server.cpp @@ -9,7 +9,7 @@ static void subscribe_camera_operation(mavsdk::CameraServer& camera_server); int main(int argc, char** argv) { - mavsdk::Mavsdk mavsdk{mavsdk::Mavsdk::Configuration{mavsdk::Mavsdk::ComponentType::Camera}}; + mavsdk::Mavsdk mavsdk{mavsdk::Mavsdk::Configuration{mavsdk::ComponentType::Camera}}; // 14030 is the default camera port for PX4 SITL auto result = mavsdk.add_any_connection("udp://127.0.0.1:14030"); diff --git a/examples/camera_settings/camera_settings.cpp b/examples/camera_settings/camera_settings.cpp index b2d6c527b5..cfe91f82b0 100644 --- a/examples/camera_settings/camera_settings.cpp +++ b/examples/camera_settings/camera_settings.cpp @@ -197,7 +197,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/camera_zoom/camera_zoom.cpp b/examples/camera_zoom/camera_zoom.cpp index 86a0e99267..ee2f4d4cf0 100644 --- a/examples/camera_zoom/camera_zoom.cpp +++ b/examples/camera_zoom/camera_zoom.cpp @@ -32,7 +32,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/component_metadata/component_metadata.cpp b/examples/component_metadata/component_metadata.cpp index 31c949850f..7912db52d0 100644 --- a/examples/component_metadata/component_metadata.cpp +++ b/examples/component_metadata/component_metadata.cpp @@ -28,7 +28,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/disconnect/disconnect.cpp b/examples/disconnect/disconnect.cpp index 162529c98a..7ad408fe74 100644 --- a/examples/disconnect/disconnect.cpp +++ b/examples/disconnect/disconnect.cpp @@ -70,7 +70,7 @@ int main(int argc, char** argv) std::unique_ptr mavsdk; - mavsdk = std::make_unique(Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); + mavsdk = std::make_unique(Mavsdk::Configuration{ComponentType::GroundStation}); while (true) { if (connect(mavsdk.get(), connection_url)) { @@ -82,8 +82,7 @@ int main(int argc, char** argv) wait_for_disconnect(mavsdk.get()); // Destruct and construct Mavsdk. - mavsdk = - std::make_unique(Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}); + mavsdk = std::make_unique(Mavsdk::Configuration{ComponentType::GroundStation}); } return 0; diff --git a/examples/distance_sensor/distance_sensor.cpp b/examples/distance_sensor/distance_sensor.cpp index 61c774bb33..2e00fa966e 100644 --- a/examples/distance_sensor/distance_sensor.cpp +++ b/examples/distance_sensor/distance_sensor.cpp @@ -36,7 +36,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/events/events.cpp b/examples/events/events.cpp index d8446a7a7c..461cad6969 100644 --- a/examples/events/events.cpp +++ b/examples/events/events.cpp @@ -41,7 +41,7 @@ int main(int argc, char** argv) } } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/fly_mission/fly_mission.cpp b/examples/fly_mission/fly_mission.cpp index 34574f813e..b3f92c003e 100644 --- a/examples/fly_mission/fly_mission.cpp +++ b/examples/fly_mission/fly_mission.cpp @@ -56,7 +56,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/fly_multiple_drones/fly_multiple_drones.cpp b/examples/fly_multiple_drones/fly_multiple_drones.cpp index ec3379903b..2b71ee950a 100644 --- a/examples/fly_multiple_drones/fly_multiple_drones.cpp +++ b/examples/fly_multiple_drones/fly_multiple_drones.cpp @@ -85,7 +85,7 @@ int main(int argc, char* argv[]) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; // Half of argc is how many udp ports is being used size_t total_ports_used = argc / 2; diff --git a/examples/fly_qgc_mission/fly_qgc_mission.cpp b/examples/fly_qgc_mission/fly_qgc_mission.cpp index 2df237a385..6bbe94a79e 100644 --- a/examples/fly_qgc_mission/fly_qgc_mission.cpp +++ b/examples/fly_qgc_mission/fly_qgc_mission.cpp @@ -48,7 +48,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; const ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/follow_me/follow_me.cpp b/examples/follow_me/follow_me.cpp index 79d8e5a66f..3786396035 100644 --- a/examples/follow_me/follow_me.cpp +++ b/examples/follow_me/follow_me.cpp @@ -37,7 +37,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/ftp_client/ftp_client.cpp b/examples/ftp_client/ftp_client.cpp index 1898b0ec36..04dca3c3b7 100644 --- a/examples/ftp_client/ftp_client.cpp +++ b/examples/ftp_client/ftp_client.cpp @@ -184,7 +184,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/ftp_server/ftp_server.cpp b/examples/ftp_server/ftp_server.cpp index e32d450a73..36daf161c7 100644 --- a/examples/ftp_server/ftp_server.cpp +++ b/examples/ftp_server/ftp_server.cpp @@ -25,7 +25,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::CompanionComputer}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::CompanionComputer}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { std::cerr << "Error setting up Mavlink FTP server.\n"; diff --git a/examples/geofence/geofence.cpp b/examples/geofence/geofence.cpp index 193ba4064d..bd04dd526b 100644 --- a/examples/geofence/geofence.cpp +++ b/examples/geofence/geofence.cpp @@ -38,7 +38,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/gimbal/gimbal.cpp b/examples/gimbal/gimbal.cpp index 3aa07a691f..61eac9cf91 100644 --- a/examples/gimbal/gimbal.cpp +++ b/examples/gimbal/gimbal.cpp @@ -36,7 +36,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/gimbal_device_tester/gimbal_device_tester.cpp b/examples/gimbal_device_tester/gimbal_device_tester.cpp index e5807d7e2b..538e6a4173 100644 --- a/examples/gimbal_device_tester/gimbal_device_tester.cpp +++ b/examples/gimbal_device_tester/gimbal_device_tester.cpp @@ -796,7 +796,7 @@ void usage(const std::string& bin_name) int main(int argc, char** argv) { - Mavsdk::Configuration config(Mavsdk::ComponentType::Autopilot); + Mavsdk::Configuration config(ComponentType::Autopilot); config.set_system_id(own_sysid); Mavsdk mavsdk{config}; std::string connection_url; diff --git a/examples/gimbal_full_control/gimbal_full_control.cpp b/examples/gimbal_full_control/gimbal_full_control.cpp index e4d7bfce27..51fdc83624 100644 --- a/examples/gimbal_full_control/gimbal_full_control.cpp +++ b/examples/gimbal_full_control/gimbal_full_control.cpp @@ -34,7 +34,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/log_callback/log_callback.cpp b/examples/log_callback/log_callback.cpp index 44aaac4a4a..acbc8689db 100644 --- a/examples/log_callback/log_callback.cpp +++ b/examples/log_callback/log_callback.cpp @@ -24,7 +24,7 @@ int main(int, char**) }); // Instantiate Mavsdk after. This will just print the version. - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; return 0; } diff --git a/examples/log_streaming/log_streaming.cpp b/examples/log_streaming/log_streaming.cpp index f83ac1bfdd..8947b655c3 100644 --- a/examples/log_streaming/log_streaming.cpp +++ b/examples/log_streaming/log_streaming.cpp @@ -36,7 +36,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/logfile_download/logfile_download.cpp b/examples/logfile_download/logfile_download.cpp index 0127c6a93b..f7cdc6760e 100644 --- a/examples/logfile_download/logfile_download.cpp +++ b/examples/logfile_download/logfile_download.cpp @@ -48,7 +48,7 @@ int main(int argc, char** argv) } } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/manual_control/manual_control.cpp b/examples/manual_control/manual_control.cpp index a097839dd9..5f0f12c72e 100644 --- a/examples/manual_control/manual_control.cpp +++ b/examples/manual_control/manual_control.cpp @@ -59,7 +59,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/mavlink_forwarding/mavlink_forwarding.cpp b/examples/mavlink_forwarding/mavlink_forwarding.cpp index 750e4ca137..b0d6608d86 100644 --- a/examples/mavlink_forwarding/mavlink_forwarding.cpp +++ b/examples/mavlink_forwarding/mavlink_forwarding.cpp @@ -15,7 +15,7 @@ using namespace mavsdk; int main(int, char**) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection("udp://:12550", ForwardingOption::ForwardingOn); diff --git a/examples/mavshell/mavshell.cpp b/examples/mavshell/mavshell.cpp index 4bc11a4720..e05ef04261 100644 --- a/examples/mavshell/mavshell.cpp +++ b/examples/mavshell/mavshell.cpp @@ -25,7 +25,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/multiple_drones/multiple_drones.cpp b/examples/multiple_drones/multiple_drones.cpp index e39ad2f3e3..f3ae88d552 100644 --- a/examples/multiple_drones/multiple_drones.cpp +++ b/examples/multiple_drones/multiple_drones.cpp @@ -36,7 +36,7 @@ int main(int argc, char* argv[]) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; size_t total_udp_ports = argc - 1; diff --git a/examples/offboard/offboard.cpp b/examples/offboard/offboard.cpp index 30b9dcbd70..d2a97405ea 100644 --- a/examples/offboard/offboard.cpp +++ b/examples/offboard/offboard.cpp @@ -299,7 +299,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/set_actuator/set_actuator.cpp b/examples/set_actuator/set_actuator.cpp index 6b5679b768..3ce834f862 100644 --- a/examples/set_actuator/set_actuator.cpp +++ b/examples/set_actuator/set_actuator.cpp @@ -32,7 +32,7 @@ int main(int argc, char** argv) const int index = std::stod(argv[2]); const float value = std::stof(argv[3]); - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; const ConnectionResult connection_result = mavsdk.add_any_connection(connection_url); if (connection_result != ConnectionResult::Success) { diff --git a/examples/sniffer/sniffer.cpp b/examples/sniffer/sniffer.cpp index 582b9dc381..e805ab75fc 100644 --- a/examples/sniffer/sniffer.cpp +++ b/examples/sniffer/sniffer.cpp @@ -29,7 +29,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/system_info/system_info.cpp b/examples/system_info/system_info.cpp index 906c0de372..7b9e54452a 100644 --- a/examples/system_info/system_info.cpp +++ b/examples/system_info/system_info.cpp @@ -32,7 +32,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/takeoff_and_land/takeoff_and_land.cpp b/examples/takeoff_and_land/takeoff_and_land.cpp index c7c70088b1..e8a7c23521 100644 --- a/examples/takeoff_and_land/takeoff_and_land.cpp +++ b/examples/takeoff_and_land/takeoff_and_land.cpp @@ -33,7 +33,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/terminate/terminate.cpp b/examples/terminate/terminate.cpp index 48a5a7da02..fd32487a27 100644 --- a/examples/terminate/terminate.cpp +++ b/examples/terminate/terminate.cpp @@ -35,7 +35,7 @@ int main(int argc, char* argv[]) const std::string connection_url = argv[1]; - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; std::cout << "Waiting to discover system...\n"; auto prom = std::promise>{}; diff --git a/examples/transponder/transponder.cpp b/examples/transponder/transponder.cpp index 8727ad73a4..e157681e29 100644 --- a/examples/transponder/transponder.cpp +++ b/examples/transponder/transponder.cpp @@ -32,7 +32,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/tune/tune.cpp b/examples/tune/tune.cpp index b0b43b359f..109f02c2b4 100644 --- a/examples/tune/tune.cpp +++ b/examples/tune/tune.cpp @@ -30,7 +30,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/vtol_transition/vtol_transition.cpp b/examples/vtol_transition/vtol_transition.cpp index 0d13b5b3ff..549d1be6d6 100644 --- a/examples/vtol_transition/vtol_transition.cpp +++ b/examples/vtol_transition/vtol_transition.cpp @@ -34,7 +34,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/examples/winch/winch.cpp b/examples/winch/winch.cpp index 75d7721b3f..3eb145aba8 100644 --- a/examples/winch/winch.cpp +++ b/examples/winch/winch.cpp @@ -30,7 +30,7 @@ int main(int argc, char** argv) return 1; } - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult connection_result = mavsdk.add_any_connection(argv[1]); if (connection_result != ConnectionResult::Success) { diff --git a/src/integration_tests/action_goto.cpp b/src/integration_tests/action_goto.cpp index 5ade6ca98f..4ef672f0a2 100644 --- a/src/integration_tests/action_goto.cpp +++ b/src/integration_tests/action_goto.cpp @@ -9,7 +9,7 @@ using namespace mavsdk; TEST(SitlTest, PX4ActionGoto) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/action_hold.cpp b/src/integration_tests/action_hold.cpp index 40bde9ee7a..cb1a2a292b 100644 --- a/src/integration_tests/action_hold.cpp +++ b/src/integration_tests/action_hold.cpp @@ -9,7 +9,7 @@ using namespace mavsdk; TEST(SitlTest, PX4ActionHold) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/action_hover_async.cpp b/src/integration_tests/action_hover_async.cpp index 92d1bc02c1..781d8964ad 100644 --- a/src/integration_tests/action_hover_async.cpp +++ b/src/integration_tests/action_hover_async.cpp @@ -9,7 +9,7 @@ using namespace mavsdk; TEST(SitlTest, ActionHoverAsync) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/action_hover_sync.cpp b/src/integration_tests/action_hover_sync.cpp index fc1a78470d..bf1cb5088d 100644 --- a/src/integration_tests/action_hover_sync.cpp +++ b/src/integration_tests/action_hover_sync.cpp @@ -46,7 +46,7 @@ TEST(SitlTest, APMActionHoverSyncLower) void takeoff_and_hover_at_altitude(float altitude_m) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); @@ -123,7 +123,7 @@ void takeoff_and_hover_at_altitude(float altitude_m) void takeoff_and_hover_at_altitude_apm(float altitude_m) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/action_takeoff_and_kill.cpp b/src/integration_tests/action_takeoff_and_kill.cpp index 9ccf61c09a..9c752788e0 100644 --- a/src/integration_tests/action_takeoff_and_kill.cpp +++ b/src/integration_tests/action_takeoff_and_kill.cpp @@ -9,7 +9,7 @@ using namespace mavsdk; TEST(SitlTest, ActionTakeoffAndKill) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ASSERT_EQ(mavsdk.add_any_connection("udpin://0.0.0.0:14540"), ConnectionResult::Success); { diff --git a/src/integration_tests/action_transition_multicopter_fixedwing.cpp b/src/integration_tests/action_transition_multicopter_fixedwing.cpp index 7b0054ed20..8575c5143b 100644 --- a/src/integration_tests/action_transition_multicopter_fixedwing.cpp +++ b/src/integration_tests/action_transition_multicopter_fixedwing.cpp @@ -10,7 +10,7 @@ using namespace mavsdk; TEST(SitlTest, PX4ActionTransitionSync_standard_vtol) { // Init & connect - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/calibration.cpp b/src/integration_tests/calibration.cpp index 1266e3ae8d..977ad0b263 100644 --- a/src/integration_tests/calibration.cpp +++ b/src/integration_tests/calibration.cpp @@ -16,7 +16,7 @@ static void receive_calibration_callback( TEST(HardwareTest, CalibrationGyro) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); @@ -45,7 +45,7 @@ TEST(HardwareTest, CalibrationGyro) TEST(HardwareTest, CalibrationAccelerometer) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); @@ -74,7 +74,7 @@ TEST(HardwareTest, CalibrationAccelerometer) TEST(HardwareTest, CalibrationMagnetometer) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); @@ -103,7 +103,7 @@ TEST(HardwareTest, CalibrationMagnetometer) TEST(HardwareTest, CalibrationLevelHorizon) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); @@ -132,7 +132,7 @@ TEST(HardwareTest, CalibrationLevelHorizon) TEST(HardwareTest, CalibrationGimbalAccelerometer) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); @@ -161,7 +161,7 @@ TEST(HardwareTest, CalibrationGimbalAccelerometer) TEST(HardwareTest, CalibrationGyroWithTelemetry) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); @@ -204,7 +204,7 @@ TEST(HardwareTest, CalibrationGyroWithTelemetry) TEST(HardwareTest, CalibrationGyroCancelled) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/camera_capture_info.cpp b/src/integration_tests/camera_capture_info.cpp index 0c0b44ee1b..264f30e049 100644 --- a/src/integration_tests/camera_capture_info.cpp +++ b/src/integration_tests/camera_capture_info.cpp @@ -10,7 +10,7 @@ using namespace mavsdk; TEST(CameraTest, CaptureInfo) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/camera_format.cpp b/src/integration_tests/camera_format.cpp index b0a98baa9e..7bfa706666 100644 --- a/src/integration_tests/camera_format.cpp +++ b/src/integration_tests/camera_format.cpp @@ -9,7 +9,7 @@ using namespace mavsdk; TEST(CameraTest, Format) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/camera_mode.cpp b/src/integration_tests/camera_mode.cpp index a2b6afebcf..1fe6a111d8 100644 --- a/src/integration_tests/camera_mode.cpp +++ b/src/integration_tests/camera_mode.cpp @@ -9,7 +9,7 @@ using namespace mavsdk; TEST(CameraTest, SetModeSync) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); @@ -48,7 +48,7 @@ TEST(CameraTest, SetModeSync) TEST(CameraTest, SetModeAsync) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/camera_reset_settings.cpp b/src/integration_tests/camera_reset_settings.cpp index bd4f96ec1c..a5becaaeff 100644 --- a/src/integration_tests/camera_reset_settings.cpp +++ b/src/integration_tests/camera_reset_settings.cpp @@ -9,7 +9,7 @@ using namespace mavsdk; TEST(CameraTest, ResetSettings) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/camera_settings.cpp b/src/integration_tests/camera_settings.cpp index 145a3dda85..d0516df5c4 100644 --- a/src/integration_tests/camera_settings.cpp +++ b/src/integration_tests/camera_settings.cpp @@ -36,7 +36,7 @@ void contains_num_options( TEST(CameraTest, ShowSettingsAndOptions) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); @@ -125,7 +125,7 @@ TEST(CameraTest, ShowSettingsAndOptions) TEST(CameraTest, SetSettings) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + 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); @@ -263,7 +263,7 @@ receive_current_settings(bool& subscription_called, const std::vector _received_result{false}; TEST(CameraTest, TakePhotoInterval) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/connection.cpp b/src/integration_tests/connection.cpp index 27ee59050e..bab6cabeaa 100644 --- a/src/integration_tests/connection.cpp +++ b/src/integration_tests/connection.cpp @@ -28,12 +28,12 @@ static void connection_test(const std::string& client_system_address, const std::string& server_system_address) { // Start instance as a UDP server pretending to be an autopilot - Mavsdk mavsdk_server{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_server{Mavsdk::Configuration{ComponentType::Autopilot}}; ConnectionResult ret_server = mavsdk_server.add_any_connection(server_system_address); ASSERT_EQ(ret_server, ConnectionResult::Success); // Start instance as a UDP client, connecting to the server above - Mavsdk mavsdk_client{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_client{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret_client = mavsdk_client.add_any_connection(client_system_address); ASSERT_EQ(ret_client, ConnectionResult::Success); diff --git a/src/integration_tests/follow_me.cpp b/src/integration_tests/follow_me.cpp index 211340ab8d..1a6b452931 100644 --- a/src/integration_tests/follow_me.cpp +++ b/src/integration_tests/follow_me.cpp @@ -31,7 +31,7 @@ const size_t N_LOCATIONS = 100ul; /* Test FollowMe with a stationary target at one location */ TEST(SitlTest, PX4FollowMeOneLocation) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ConnectionResult::Success, ret); @@ -114,7 +114,7 @@ TEST(SitlTest, PX4FollowMeOneLocation) /* Test FollowMe with a dynamically moving target */ TEST(SitlTest, PX4FollowMeMultiLocationWithConfig) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ConnectionResult::Success, ret); diff --git a/src/integration_tests/geofence.cpp b/src/integration_tests/geofence.cpp index de99a038c2..e8ea243839 100644 --- a/src/integration_tests/geofence.cpp +++ b/src/integration_tests/geofence.cpp @@ -11,7 +11,7 @@ static Geofence::Point add_point(double latitude_deg, double longitude_deg); TEST(SitlTest, PX4GeofenceInclusion) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/info.cpp b/src/integration_tests/info.cpp index 353c4afd87..af126105d5 100644 --- a/src/integration_tests/info.cpp +++ b/src/integration_tests/info.cpp @@ -7,7 +7,7 @@ using namespace mavsdk; TEST(SitlTest, PX4Info) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/log_files.cpp b/src/integration_tests/log_files.cpp index 453aba26f6..4cc13dbd09 100644 --- a/src/integration_tests/log_files.cpp +++ b/src/integration_tests/log_files.cpp @@ -11,7 +11,7 @@ using namespace mavsdk; TEST(HardwareTest, LogFiles) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; // ConnectionResult ret = mavsdk.add_serial_connection("/dev/ttyACM0"); ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); @@ -65,7 +65,7 @@ TEST(HardwareTest, LogFiles) TEST(HardwareTest, LogFilesDownloadFailsIfPathIsDirectory) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; // ConnectionResult ret = mavsdk.add_serial_connection("/dev/ttyACM0"); ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); @@ -120,7 +120,7 @@ TEST(HardwareTest, LogFilesDownloadFailsIfPathIsDirectory) TEST(HardwareTest, LogFilesDownloadFailsIfFileAlreadyExists) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; // ConnectionResult ret = mavsdk.add_serial_connection("/dev/ttyACM0"); ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); diff --git a/src/integration_tests/logging.cpp b/src/integration_tests/logging.cpp index db80f55c05..96ff41f17f 100644 --- a/src/integration_tests/logging.cpp +++ b/src/integration_tests/logging.cpp @@ -7,7 +7,7 @@ using namespace mavsdk; TEST(SitlTest, PX4Logging) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/mavlink_passthrough.cpp b/src/integration_tests/mavlink_passthrough.cpp index 1b568c4199..ed37c4723b 100644 --- a/src/integration_tests/mavlink_passthrough.cpp +++ b/src/integration_tests/mavlink_passthrough.cpp @@ -9,7 +9,7 @@ using namespace mavsdk; TEST(SitlTest, PX4MavlinkPassthrough) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ASSERT_EQ(mavsdk.add_any_connection("udpin://0.0.0.0:14540"), ConnectionResult::Success); { diff --git a/src/integration_tests/mission.cpp b/src/integration_tests/mission.cpp index 26351d31ca..6095c93d9c 100644 --- a/src/integration_tests/mission.cpp +++ b/src/integration_tests/mission.cpp @@ -38,7 +38,7 @@ static std::atomic pause_already_done{false}; TEST(SitlTest, PX4MissionAddWaypointsAndFly) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; { auto prom = std::make_shared>(); diff --git a/src/integration_tests/mission_cancellation.cpp b/src/integration_tests/mission_cancellation.cpp index 4d17082c3c..904fe2dfde 100644 --- a/src/integration_tests/mission_cancellation.cpp +++ b/src/integration_tests/mission_cancellation.cpp @@ -24,7 +24,7 @@ static Mission::MissionItem add_waypoint( TEST(SitlTest, PX4MissionUploadCancellation) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); @@ -80,7 +80,7 @@ TEST(SitlTest, PX4MissionUploadCancellation) TEST(SitlTest, PX4MissionDownloadCancellation) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/mission_change_speed.cpp b/src/integration_tests/mission_change_speed.cpp index 412ff776e0..80c9db98a5 100644 --- a/src/integration_tests/mission_change_speed.cpp +++ b/src/integration_tests/mission_change_speed.cpp @@ -22,7 +22,7 @@ const static float speeds[4] = {10.0f, 3.0f, 8.0f, 5.0f}; // Test to check speed set for mission items. TEST(SitlTest, PX4MissionChangeSpeed) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/mission_raw_import_and_fly.cpp b/src/integration_tests/mission_raw_import_and_fly.cpp index 275c3097fb..3de293d3e5 100644 --- a/src/integration_tests/mission_raw_import_and_fly.cpp +++ b/src/integration_tests/mission_raw_import_and_fly.cpp @@ -28,7 +28,7 @@ void test_mission_raw( TEST(SitlTest, PX4MissionRawImportAndFly) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); @@ -89,7 +89,7 @@ TEST(SitlTest, PX4MissionRawImportAndFly) TEST(SitlTest, APMissionRawImportAndFly) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/mission_raw_mission_changed.cpp b/src/integration_tests/mission_raw_mission_changed.cpp index d112c31cca..6876fec0f7 100644 --- a/src/integration_tests/mission_raw_mission_changed.cpp +++ b/src/integration_tests/mission_raw_mission_changed.cpp @@ -16,7 +16,7 @@ static void validate_items(const std::vector& items); TEST(SitlTest, PX4MissionRawMissionChanged) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/mission_rtl.cpp b/src/integration_tests/mission_rtl.cpp index c9f9eedb0c..cd3da2434f 100644 --- a/src/integration_tests/mission_rtl.cpp +++ b/src/integration_tests/mission_rtl.cpp @@ -34,7 +34,7 @@ TEST(SitlTest, PX4MissionWithRTLHigherAnyway) void do_mission_with_rtl(float mission_altitude_m, float return_altitude_m) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; { auto prom = std::make_shared>(); diff --git a/src/integration_tests/mission_set_current.cpp b/src/integration_tests/mission_set_current.cpp index 4cf3876207..b76b784dfa 100644 --- a/src/integration_tests/mission_set_current.cpp +++ b/src/integration_tests/mission_set_current.cpp @@ -18,7 +18,7 @@ add_waypoint(double latitude_deg, double longitude_deg, float relative_altitude_ // Test to check speed set for mission items. TEST(SitlTest, PX4MissionSetCurrent) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/mission_takeoff_land.cpp b/src/integration_tests/mission_takeoff_land.cpp index a16c98742f..c9d0646e81 100644 --- a/src/integration_tests/mission_takeoff_land.cpp +++ b/src/integration_tests/mission_takeoff_land.cpp @@ -15,7 +15,7 @@ using namespace mavsdk; TEST(SitlTest, MissionTakeoffAndLand) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; float mission_altitude_m = 20; { diff --git a/src/integration_tests/mission_transfer_lossy.cpp b/src/integration_tests/mission_transfer_lossy.cpp index cb7a26af63..8a933e08ae 100644 --- a/src/integration_tests/mission_transfer_lossy.cpp +++ b/src/integration_tests/mission_transfer_lossy.cpp @@ -19,7 +19,7 @@ static std::uniform_real_distribution distribution(0.0, 1.0); TEST(SitlTest, PX4MissionTransferLossy) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ASSERT_EQ(mavsdk.add_any_connection("udpin://0.0.0.0:14540"), ConnectionResult::Success); { diff --git a/src/integration_tests/mission_transition.cpp b/src/integration_tests/mission_transition.cpp index dfde41b234..092b2816f1 100644 --- a/src/integration_tests/mission_transition.cpp +++ b/src/integration_tests/mission_transition.cpp @@ -15,7 +15,7 @@ using namespace mavsdk; TEST(SitlTest, MissionTakeoffTransitionAndLand_standard_vtol) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; float mission_altitude_m = 40; { diff --git a/src/integration_tests/offboard_acceleration.cpp b/src/integration_tests/offboard_acceleration.cpp index 0492f15f70..ab1bf3d43d 100644 --- a/src/integration_tests/offboard_acceleration.cpp +++ b/src/integration_tests/offboard_acceleration.cpp @@ -11,7 +11,7 @@ using namespace mavsdk; TEST(SitlTest, PX4OffboardAccelerationNED) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ConnectionResult::Success, ret); diff --git a/src/integration_tests/offboard_attitude.cpp b/src/integration_tests/offboard_attitude.cpp index 48fa148e4e..927cd5477d 100644 --- a/src/integration_tests/offboard_attitude.cpp +++ b/src/integration_tests/offboard_attitude.cpp @@ -18,7 +18,7 @@ static void turn_yaw(const Offboard& offboard); TEST(SitlTestDisabled, OffboardAttitudeRate) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ConnectionResult::Success, ret); diff --git a/src/integration_tests/offboard_position.cpp b/src/integration_tests/offboard_position.cpp index 130f59e7c6..06f420245c 100644 --- a/src/integration_tests/offboard_position.cpp +++ b/src/integration_tests/offboard_position.cpp @@ -12,7 +12,7 @@ using namespace mavsdk; TEST(SitlTest, OffboardPositionNED) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ConnectionResult::Success, ret); diff --git a/src/integration_tests/offboard_velocity.cpp b/src/integration_tests/offboard_velocity.cpp index 64b0bd3f99..32552f8f79 100644 --- a/src/integration_tests/offboard_velocity.cpp +++ b/src/integration_tests/offboard_velocity.cpp @@ -12,7 +12,7 @@ using namespace mavsdk; TEST(SitlTest, OffboardVelocityNED) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ConnectionResult::Success, ret); @@ -134,7 +134,7 @@ TEST(SitlTest, OffboardVelocityNED) TEST(SitlTest, OffboardVelocityBody) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ConnectionResult::Success, ret); diff --git a/src/integration_tests/param.cpp b/src/integration_tests/param.cpp index d709366df9..e9a1a1d7fd 100644 --- a/src/integration_tests/param.cpp +++ b/src/integration_tests/param.cpp @@ -8,7 +8,7 @@ using namespace mavsdk; TEST(SitlTest, PX4ParamSad) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); @@ -46,7 +46,7 @@ TEST(SitlTest, PX4ParamSad) TEST(SitlTest, PX4ParamHappy) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); @@ -127,7 +127,7 @@ TEST(SitlTest, PX4ParamHappy) TEST(SitlTest, GetAllParams) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); @@ -168,7 +168,7 @@ TEST(SitlTest, GetAllParams) TEST(SitlTest, APParam) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/statustext.cpp b/src/integration_tests/statustext.cpp index a829038585..01b47a761e 100644 --- a/src/integration_tests/statustext.cpp +++ b/src/integration_tests/statustext.cpp @@ -15,10 +15,10 @@ static const auto type = ServerUtility::StatusTextType::Info; TEST(StatusTextTest, TestServer) { - Mavsdk mavsdk_gcs{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_gcs{Mavsdk::Configuration{ComponentType::GroundStation}}; ASSERT_EQ(mavsdk_gcs.add_any_connection("udpin://0.0.0.0:24550"), ConnectionResult::Success); - Mavsdk mavsdk_onboard{Mavsdk::Configuration{Mavsdk::ComponentType::CompanionComputer}}; + Mavsdk mavsdk_onboard{Mavsdk::Configuration{ComponentType::CompanionComputer}}; ASSERT_EQ( mavsdk_onboard.add_any_connection("udpout://127.0.0.1:24550"), ConnectionResult::Success); diff --git a/src/integration_tests/system_connection_async.cpp b/src/integration_tests/system_connection_async.cpp index 8f1e6b65d8..a28e25508f 100644 --- a/src/integration_tests/system_connection_async.cpp +++ b/src/integration_tests/system_connection_async.cpp @@ -14,7 +14,7 @@ static uint8_t _sysid = 0; TEST(SitlTest, SystemConnectionAsync) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ASSERT_EQ(mavsdk.add_any_connection("udpin://0.0.0.0:14540"), ConnectionResult::Success); diff --git a/src/integration_tests/system_multi_components.cpp b/src/integration_tests/system_multi_components.cpp index 31857c76d9..9c0930547a 100644 --- a/src/integration_tests/system_multi_components.cpp +++ b/src/integration_tests/system_multi_components.cpp @@ -25,7 +25,7 @@ using namespace std::chrono; */ TEST(SitlTestMultiple, SystemMultipleComponents) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; // For both Autopilot and Camera ASSERT_EQ(mavsdk.add_any_connection("udpin://0.0.0.0:14540"), ConnectionResult::Success); diff --git a/src/integration_tests/telemetry_async.cpp b/src/integration_tests/telemetry_async.cpp index c649da397a..6a21d4c498 100644 --- a/src/integration_tests/telemetry_async.cpp +++ b/src/integration_tests/telemetry_async.cpp @@ -50,7 +50,7 @@ static bool _received_altitude = false; TEST(SitlTest, PX4TelemetryAsync) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/telemetry_gps_origin.cpp b/src/integration_tests/telemetry_gps_origin.cpp index a70d9223c1..ca9ca70155 100644 --- a/src/integration_tests/telemetry_gps_origin.cpp +++ b/src/integration_tests/telemetry_gps_origin.cpp @@ -6,7 +6,7 @@ using namespace mavsdk; TEST(SitlTestDisabled, TelemetryGpsOrigin) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/telemetry_health.cpp b/src/integration_tests/telemetry_health.cpp index 1faa643f4a..a672185cbf 100644 --- a/src/integration_tests/telemetry_health.cpp +++ b/src/integration_tests/telemetry_health.cpp @@ -10,7 +10,7 @@ void print_rc_status(Telemetry::RcStatus rc_status); TEST(SitlTest, TelemetryHealth) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/telemetry_modes.cpp b/src/integration_tests/telemetry_modes.cpp index 7a9904261a..9b2c580c10 100644 --- a/src/integration_tests/telemetry_modes.cpp +++ b/src/integration_tests/telemetry_modes.cpp @@ -12,7 +12,7 @@ static std::atomic _flight_mode{Telemetry::FlightMode::Un TEST(SitlTestDisabled, TelemetryFlightModes) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/integration_tests/telemetry_sync.cpp b/src/integration_tests/telemetry_sync.cpp index 8f2f356fc3..a165368078 100644 --- a/src/integration_tests/telemetry_sync.cpp +++ b/src/integration_tests/telemetry_sync.cpp @@ -7,7 +7,7 @@ using namespace mavsdk; TEST(SitlTest, PX4TelemetrySync) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ConnectionResult ret = mavsdk.add_any_connection("udpin://0.0.0.0:14540"); ASSERT_EQ(ret, ConnectionResult::Success); diff --git a/src/mavsdk/core/CMakeLists.txt b/src/mavsdk/core/CMakeLists.txt index 4ddc287c38..86f48f348d 100644 --- a/src/mavsdk/core/CMakeLists.txt +++ b/src/mavsdk/core/CMakeLists.txt @@ -159,6 +159,7 @@ install(TARGETS mavsdk install(FILES include/mavsdk/autopilot.h include/mavsdk/base64.h + include/mavsdk/component_type.h include/mavsdk/connection_result.h include/mavsdk/deprecated.h include/mavsdk/handle.h diff --git a/src/mavsdk/core/include/mavsdk/component_type.h b/src/mavsdk/core/include/mavsdk/component_type.h new file mode 100644 index 0000000000..693707153d --- /dev/null +++ b/src/mavsdk/core/include/mavsdk/component_type.h @@ -0,0 +1,18 @@ +#pragma once + +namespace mavsdk { + + /** + * @brief ComponentType of configurations, used for automatic ID setting + */ + enum class ComponentType { + Autopilot, /**< @brief SDK is used as an autopilot. */ + GroundStation, /**< @brief SDK is used as a ground station. */ + CompanionComputer, /**< @brief SDK is used as a companion computer on board the MAV. */ + Camera, /** < @brief SDK is used as a camera. */ + Gimbal, /** < @brief SDK is used as a gimbal. */ + Custom /**< @brief the SDK is used in a custom configuration, no automatic ID will be + provided */ + }; + +} // namespace mavsdk \ No newline at end of file diff --git a/src/mavsdk/core/include/mavsdk/mavsdk.h b/src/mavsdk/core/include/mavsdk/mavsdk.h index e3cfc25346..25efd39042 100644 --- a/src/mavsdk/core/include/mavsdk/mavsdk.h +++ b/src/mavsdk/core/include/mavsdk/mavsdk.h @@ -9,6 +9,7 @@ #include "deprecated.h" #include "handle.h" #include "system.h" +#include "component_type.h" #include "server_component.h" #include "connection_result.h" #include "mavlink_include.h" @@ -145,18 +146,6 @@ class Mavsdk { */ std::optional> first_autopilot(double timeout_s) const; - /** - * @brief ComponentType of configurations, used for automatic ID setting - */ - enum class ComponentType { - Autopilot, /**< @brief SDK is used as an autopilot. */ - GroundStation, /**< @brief SDK is used as a ground station. */ - CompanionComputer, /**< @brief SDK is used as a companion computer on board the MAV. */ - Camera, /** < @brief SDK is used as a camera. */ - Custom /**< @brief the SDK is used in a custom configuration, no automatic ID will be - provided */ - }; - /** * @brief Possible configurations. */ @@ -228,7 +217,7 @@ class Mavsdk { bool _always_send_heartbeats; ComponentType _component_type; - static Mavsdk::ComponentType component_type_for_component_id(uint8_t component_id); + static ComponentType component_type_for_component_id(uint8_t component_id); }; /** diff --git a/src/mavsdk/core/include/mavsdk/system.h b/src/mavsdk/core/include/mavsdk/system.h index c4f034e73f..f3b66ac938 100644 --- a/src/mavsdk/core/include/mavsdk/system.h +++ b/src/mavsdk/core/include/mavsdk/system.h @@ -6,6 +6,7 @@ #include #include "autopilot.h" +#include "component_type.h" #include "deprecated.h" #include "handle.h" @@ -124,11 +125,6 @@ class System { */ void unsubscribe_is_connected(IsConnectedHandle handle); - /** - * @brief Component Types - */ - enum class ComponentType { UNKNOWN, AUTOPILOT, CAMERA, GIMBAL }; - /** * @brief type for component discovery callback */ diff --git a/src/mavsdk/core/lazy_server_plugin.h b/src/mavsdk/core/lazy_server_plugin.h index 4dd847e7ea..e4cea163e2 100644 --- a/src/mavsdk/core/lazy_server_plugin.h +++ b/src/mavsdk/core/lazy_server_plugin.h @@ -16,7 +16,7 @@ template class LazyServerPlugin { std::lock_guard lock(_mutex); if (_server_plugin == nullptr) { _server_plugin = std::make_unique( - _mavsdk.server_component_by_type(Mavsdk::ComponentType::CompanionComputer)); + _mavsdk.server_component_by_type(ComponentType::CompanionComputer)); } return _server_plugin.get(); } diff --git a/src/mavsdk/core/mavsdk.cpp b/src/mavsdk/core/mavsdk.cpp index 3e2314121b..975130866a 100644 --- a/src/mavsdk/core/mavsdk.cpp +++ b/src/mavsdk/core/mavsdk.cpp @@ -87,7 +87,7 @@ Mavsdk::Configuration::Configuration( _component_type(component_type_for_component_id(component_id)) {} -Mavsdk::ComponentType Mavsdk::Configuration::component_type_for_component_id(uint8_t component_id) +ComponentType Mavsdk::Configuration::component_type_for_component_id(uint8_t component_id) { switch (component_id) { case Mavsdk::DEFAULT_COMPONENT_ID_GCS: @@ -110,23 +110,23 @@ Mavsdk::Configuration::Configuration(ComponentType component_type) : _component_type(component_type) { switch (component_type) { - case Mavsdk::ComponentType::GroundStation: + case ComponentType::GroundStation: _system_id = Mavsdk::DEFAULT_SYSTEM_ID_GCS; _component_id = Mavsdk::DEFAULT_COMPONENT_ID_GCS; _always_send_heartbeats = false; break; - case Mavsdk::ComponentType::CompanionComputer: + case ComponentType::CompanionComputer: // TODO implement auto-detection of system ID - maybe from heartbeats? _system_id = Mavsdk::DEFAULT_SYSTEM_ID_CC; _component_id = Mavsdk::DEFAULT_COMPONENT_ID_CC; _always_send_heartbeats = true; break; - case Mavsdk::ComponentType::Autopilot: + case ComponentType::Autopilot: _system_id = Mavsdk::DEFAULT_SYSTEM_ID_AUTOPILOT; _component_id = Mavsdk::DEFAULT_COMPONENT_ID_AUTOPILOT; _always_send_heartbeats = true; break; - case Mavsdk::ComponentType::Camera: + case ComponentType::Camera: _system_id = Mavsdk::DEFAULT_SYSTEM_ID_CAMERA; _component_id = Mavsdk::DEFAULT_COMPONENT_ID_CAMERA; _always_send_heartbeats = true; @@ -166,12 +166,12 @@ void Mavsdk::Configuration::set_always_send_heartbeats(bool always_send_heartbea _always_send_heartbeats = always_send_heartbeats; } -Mavsdk::ComponentType Mavsdk::Configuration::get_component_type() const +ComponentType Mavsdk::Configuration::get_component_type() const { return _component_type; } -void Mavsdk::Configuration::set_component_type(Mavsdk::ComponentType component_type) +void Mavsdk::Configuration::set_component_type(ComponentType component_type) { _component_type = component_type; } diff --git a/src/mavsdk/core/mavsdk_impl.cpp b/src/mavsdk/core/mavsdk_impl.cpp index c286f567d1..947b072d88 100644 --- a/src/mavsdk/core/mavsdk_impl.cpp +++ b/src/mavsdk/core/mavsdk_impl.cpp @@ -181,11 +181,11 @@ std::shared_ptr MavsdkImpl::server_component(unsigned instance) { auto component_type = _configuration.get_component_type(); switch (component_type) { - case Mavsdk::ComponentType::Autopilot: - case Mavsdk::ComponentType::GroundStation: - case Mavsdk::ComponentType::CompanionComputer: - case Mavsdk::ComponentType::Camera: - case Mavsdk::ComponentType::Custom: + case ComponentType::Autopilot: + case ComponentType::GroundStation: + case ComponentType::CompanionComputer: + case ComponentType::Camera: + case ComponentType::Custom: return server_component_by_type(component_type, instance); default: LogErr() << "Unknown component type"; @@ -194,10 +194,10 @@ std::shared_ptr MavsdkImpl::server_component(unsigned instance) } std::shared_ptr -MavsdkImpl::server_component_by_type(Mavsdk::ComponentType server_component_type, unsigned instance) +MavsdkImpl::server_component_by_type(ComponentType server_component_type, unsigned instance) { switch (server_component_type) { - case Mavsdk::ComponentType::Autopilot: + case ComponentType::Autopilot: if (instance == 0) { return server_component_by_id(MAV_COMP_ID_AUTOPILOT1); } else { @@ -205,7 +205,7 @@ MavsdkImpl::server_component_by_type(Mavsdk::ComponentType server_component_type return {}; } - case Mavsdk::ComponentType::GroundStation: + case ComponentType::GroundStation: if (instance == 0) { return server_component_by_id(MAV_COMP_ID_MISSIONPLANNER); } else { @@ -213,7 +213,7 @@ MavsdkImpl::server_component_by_type(Mavsdk::ComponentType server_component_type return {}; } - case Mavsdk::ComponentType::CompanionComputer: + case ComponentType::CompanionComputer: if (instance == 0) { return server_component_by_id(MAV_COMP_ID_ONBOARD_COMPUTER); } else if (instance == 1) { @@ -227,7 +227,7 @@ MavsdkImpl::server_component_by_type(Mavsdk::ComponentType server_component_type return {}; } - case Mavsdk::ComponentType::Camera: + case ComponentType::Camera: if (instance == 0) { return server_component_by_id(MAV_COMP_ID_CAMERA); } else if (instance == 1) { @@ -384,7 +384,7 @@ void MavsdkImpl::receive_message(mavlink_message_t& message, Connection* connect // mavlink instances which leads to existing implementations (including // examples and integration tests) to connect to QGroundControl by accident // instead of PX4 because the check `has_autopilot()` is not used. - if (_configuration.get_component_type() == Mavsdk::ComponentType::GroundStation && + if (_configuration.get_component_type() == ComponentType::GroundStation && message.sysid == 255 && message.compid == MAV_COMP_ID_MISSIONPLANNER) { if (_message_logging_on) { LogDebug() << "Ignoring messages from QGC as we are also a ground station"; @@ -692,19 +692,19 @@ Autopilot MavsdkImpl::autopilot() const uint8_t MavsdkImpl::get_mav_type() const { switch (_configuration.get_component_type()) { - case Mavsdk::ComponentType::Autopilot: + case ComponentType::Autopilot: return MAV_TYPE_GENERIC; - case Mavsdk::ComponentType::GroundStation: + case ComponentType::GroundStation: return MAV_TYPE_GCS; - case Mavsdk::ComponentType::CompanionComputer: + case ComponentType::CompanionComputer: return MAV_TYPE_ONBOARD_CONTROLLER; - case Mavsdk::ComponentType::Camera: + case ComponentType::Camera: return MAV_TYPE_CAMERA; - case Mavsdk::ComponentType::Custom: + case ComponentType::Custom: return MAV_TYPE_GENERIC; default: diff --git a/src/mavsdk/core/mavsdk_impl.h b/src/mavsdk/core/mavsdk_impl.h index 0faedc8bd9..c1fdf1ac95 100644 --- a/src/mavsdk/core/mavsdk_impl.h +++ b/src/mavsdk/core/mavsdk_impl.h @@ -10,6 +10,7 @@ #include "autopilot.h" #include "call_every_handler.h" +#include "component_type.h" #include "connection.h" #include "cli_arg.h" #include "handle_factory.h" @@ -76,7 +77,7 @@ class MavsdkImpl { std::shared_ptr server_component(unsigned instance = 0); std::shared_ptr - server_component_by_type(Mavsdk::ComponentType server_component_type, unsigned instance = 0); + server_component_by_type(ComponentType server_component_type, unsigned instance = 0); std::shared_ptr server_component_by_id(uint8_t component_id); Time time{}; @@ -137,7 +138,7 @@ class MavsdkImpl { CallbackList<> _new_system_callbacks{}; - Mavsdk::Configuration _configuration{Mavsdk::ComponentType::GroundStation}; + Mavsdk::Configuration _configuration{ComponentType::GroundStation}; struct UserCallback { UserCallback() = default; diff --git a/src/mavsdk/core/mavsdk_test.cpp b/src/mavsdk/core/mavsdk_test.cpp index cbb2f140d4..d5b5cf9769 100644 --- a/src/mavsdk/core/mavsdk_test.cpp +++ b/src/mavsdk/core/mavsdk_test.cpp @@ -5,6 +5,6 @@ using namespace mavsdk; TEST(Mavsdk, version) { - Mavsdk mavsdk{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk{Mavsdk::Configuration{ComponentType::GroundStation}}; ASSERT_GT(mavsdk.version().size(), 5); } diff --git a/src/mavsdk/core/system_impl.cpp b/src/mavsdk/core/system_impl.cpp index 8d59b198b3..90b7984e0d 100644 --- a/src/mavsdk/core/system_impl.cpp +++ b/src/mavsdk/core/system_impl.cpp @@ -17,8 +17,8 @@ namespace mavsdk { template class CallbackList; -template class CallbackList; -template class CallbackList; +template class CallbackList; +template class CallbackList; SystemImpl::SystemImpl(MavsdkImpl& mavsdk_impl) : _mavsdk_impl(mavsdk_impl), @@ -329,22 +329,29 @@ std::string SystemImpl::component_name(uint8_t component_id) } } -System::ComponentType SystemImpl::component_type(uint8_t component_id) +ComponentType SystemImpl::component_type(uint8_t component_id) { switch (component_id) { case MAV_COMP_ID_AUTOPILOT1: - return System::ComponentType::AUTOPILOT; + return ComponentType::Autopilot; case MAV_COMP_ID_CAMERA: case MAV_COMP_ID_CAMERA2: case MAV_COMP_ID_CAMERA3: case MAV_COMP_ID_CAMERA4: case MAV_COMP_ID_CAMERA5: case MAV_COMP_ID_CAMERA6: - return System::ComponentType::CAMERA; + return ComponentType::Camera; case MAV_COMP_ID_GIMBAL: - return System::ComponentType::GIMBAL; + return ComponentType::Gimbal; + case MAV_COMP_ID_ONBOARD_COMPUTER: + case MAV_COMP_ID_ONBOARD_COMPUTER2: + case MAV_COMP_ID_ONBOARD_COMPUTER3: + case MAV_COMP_ID_ONBOARD_COMPUTER4: + return ComponentType::CompanionComputer; + case MAV_COMP_ID_MISSIONPLANNER: + return ComponentType::GroundStation; default: - return System::ComponentType::UNKNOWN; + return ComponentType::Custom; } } diff --git a/src/mavsdk/core/system_impl.h b/src/mavsdk/core/system_impl.h index 5b33b93be1..1286123a23 100644 --- a/src/mavsdk/core/system_impl.h +++ b/src/mavsdk/core/system_impl.h @@ -307,7 +307,7 @@ class SystemImpl { void set_disconnected(); static std::string component_name(uint8_t component_id); - static System::ComponentType component_type(uint8_t component_id); + static ComponentType component_type(uint8_t component_id); void system_thread(); @@ -338,8 +338,8 @@ class SystemImpl { const GetParamIntCallback& callback); std::mutex _component_discovered_callback_mutex{}; - CallbackList _component_discovered_callbacks{}; - CallbackList _component_discovered_id_callbacks{}; + CallbackList _component_discovered_callbacks{}; + CallbackList _component_discovered_id_callbacks{}; MavlinkAddress _target_address{}; diff --git a/src/mavsdk_server/src/mavsdk_server.cpp b/src/mavsdk_server/src/mavsdk_server.cpp index 9702fce49f..b9a2b9db48 100644 --- a/src/mavsdk_server/src/mavsdk_server.cpp +++ b/src/mavsdk_server/src/mavsdk_server.cpp @@ -11,7 +11,7 @@ using namespace mavsdk::mavsdk_server; class MavsdkServer::Impl { public: - Impl() : _mavsdk(Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}) {} + Impl() : _mavsdk(Mavsdk::Configuration{ComponentType::GroundStation}) {} ~Impl() {} bool connect(const std::string& connection_url) diff --git a/src/system_tests/action_arm_disarm.cpp b/src/system_tests/action_arm_disarm.cpp index e53159e6de..5b991c1b98 100644 --- a/src/system_tests/action_arm_disarm.cpp +++ b/src/system_tests/action_arm_disarm.cpp @@ -9,9 +9,9 @@ using namespace mavsdk; TEST(SystemTest, ActionArmDisarm) { - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( diff --git a/src/system_tests/camera_take_photo.cpp b/src/system_tests/camera_take_photo.cpp index 6347df3ba5..2b63576d73 100644 --- a/src/system_tests/camera_take_photo.cpp +++ b/src/system_tests/camera_take_photo.cpp @@ -11,9 +11,9 @@ using namespace mavsdk; TEST(SystemTest, CameraTakePhoto) { - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; - Mavsdk mavsdk_camera{Mavsdk::Configuration{Mavsdk::ComponentType::Camera}}; + 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); diff --git a/src/system_tests/component_metadata.cpp b/src/system_tests/component_metadata.cpp index 3503456f60..5ed6f609a8 100644 --- a/src/system_tests/component_metadata.cpp +++ b/src/system_tests/component_metadata.cpp @@ -165,10 +165,10 @@ TEST(SystemTest, ComponentInformationConnect) setenv("MAVSDK_COMPONENT_METADATA_DEBUGGING", "1", 1); #endif - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); - Mavsdk mavsdk_companion{Mavsdk::Configuration{Mavsdk::ComponentType::CompanionComputer}}; + Mavsdk mavsdk_companion{Mavsdk::Configuration{ComponentType::CompanionComputer}}; ASSERT_EQ( mavsdk_companion.add_any_connection("udp://127.0.0.1:17000"), ConnectionResult::Success); diff --git a/src/system_tests/ftp_compare_files.cpp b/src/system_tests/ftp_compare_files.cpp index 8f95102d5d..770c6dd440 100644 --- a/src/system_tests/ftp_compare_files.cpp +++ b/src/system_tests/ftp_compare_files.cpp @@ -29,10 +29,10 @@ TEST(SystemTest, FtpCompareFiles) ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file_same, 1000)); ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file_different, 1000, 42)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); diff --git a/src/system_tests/ftp_create_dir.cpp b/src/system_tests/ftp_create_dir.cpp index 382d7a4345..0f3e46d1e9 100644 --- a/src/system_tests/ftp_create_dir.cpp +++ b/src/system_tests/ftp_create_dir.cpp @@ -21,10 +21,10 @@ static const fs::path temp_dir = "folder"; TEST(SystemTest, FtpCreateDir) { - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); diff --git a/src/system_tests/ftp_download_file.cpp b/src/system_tests/ftp_download_file.cpp index 4ee750d87d..5beed2e56b 100644 --- a/src/system_tests/ftp_download_file.cpp +++ b/src/system_tests/ftp_download_file.cpp @@ -27,10 +27,10 @@ TEST(SystemTest, FtpDownloadFile) ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50)); ASSERT_TRUE(reset_directories(temp_dir_downloaded)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); @@ -98,10 +98,10 @@ TEST(SystemTest, FtpDownloadBigFile) ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50000)); ASSERT_TRUE(reset_directories(temp_dir_downloaded)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); @@ -150,10 +150,10 @@ TEST(SystemTest, FtpDownloadBigFileLossy) ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 10000)); ASSERT_TRUE(reset_directories(temp_dir_downloaded)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); unsigned counter = 0; @@ -213,10 +213,10 @@ TEST(SystemTest, FtpDownloadStopAndTryAgain) ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 1000)); ASSERT_TRUE(reset_directories(temp_dir_downloaded)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); // Once we received half, we want to stop all traffic. @@ -301,10 +301,10 @@ TEST(SystemTest, FtpDownloadFileOutsideOfRoot) ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50)); ASSERT_TRUE(reset_directories(temp_dir_downloaded)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); diff --git a/src/system_tests/ftp_download_file_burst.cpp b/src/system_tests/ftp_download_file_burst.cpp index b808cdc518..bcaeba2740 100644 --- a/src/system_tests/ftp_download_file_burst.cpp +++ b/src/system_tests/ftp_download_file_burst.cpp @@ -27,10 +27,10 @@ TEST(SystemTest, FtpDownloadBurstFile) ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50)); ASSERT_TRUE(reset_directories(temp_dir_downloaded)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); @@ -98,10 +98,10 @@ TEST(SystemTest, FtpDownloadBurstBigFile) ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50000)); ASSERT_TRUE(reset_directories(temp_dir_downloaded)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); @@ -150,10 +150,10 @@ TEST(SystemTest, FtpDownloadBurstBigFileLossy) ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 10000)); ASSERT_TRUE(reset_directories(temp_dir_downloaded)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); unsigned counter = 0; @@ -216,10 +216,10 @@ TEST(SystemTest, FtpDownloadBurstStopAndTryAgain) ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, file_size)); ASSERT_TRUE(reset_directories(temp_dir_downloaded)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); // Once we received half, we want to stop all traffic. @@ -317,10 +317,10 @@ TEST(SystemTest, FtpDownloadBurstFileOutsideOfRoot) ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50)); ASSERT_TRUE(reset_directories(temp_dir_downloaded)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); diff --git a/src/system_tests/ftp_list_dir.cpp b/src/system_tests/ftp_list_dir.cpp index 50eddd6cca..0e96ccd69f 100644 --- a/src/system_tests/ftp_list_dir.cpp +++ b/src/system_tests/ftp_list_dir.cpp @@ -41,10 +41,10 @@ TEST(SystemTest, FtpListDir) std::sort(truth_dirs.begin(), truth_dirs.end()); std::sort(truth_files.begin(), truth_files.end()); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); diff --git a/src/system_tests/ftp_remove_dir.cpp b/src/system_tests/ftp_remove_dir.cpp index 1010afb297..9aa68cf748 100644 --- a/src/system_tests/ftp_remove_dir.cpp +++ b/src/system_tests/ftp_remove_dir.cpp @@ -22,10 +22,10 @@ static const fs::path temp_file = "file.bin"; TEST(SystemTest, FtpRemoveDir) { - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); @@ -63,10 +63,10 @@ TEST(SystemTest, FtpRemoveDirNotEmpty) ASSERT_TRUE(reset_directories(temp_dir_provided / temp_dir)); ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_dir / temp_file, 100)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); diff --git a/src/system_tests/ftp_remove_file.cpp b/src/system_tests/ftp_remove_file.cpp index 31f36f97a9..c0399768c9 100644 --- a/src/system_tests/ftp_remove_file.cpp +++ b/src/system_tests/ftp_remove_file.cpp @@ -24,10 +24,10 @@ TEST(SystemTest, FtpRemoveFile) { ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); @@ -60,10 +60,10 @@ TEST(SystemTest, FtpRemoveFile) TEST(SystemTest, FtpRemoveFileThatDoesNotExist) { - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); @@ -94,10 +94,10 @@ TEST(SystemTest, FtpRemoveFileThatDoesNotExist) TEST(SystemTest, FtpRemoveFileOutsideOfRoot) { - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); diff --git a/src/system_tests/ftp_rename_file.cpp b/src/system_tests/ftp_rename_file.cpp index c1e76cb1ba..bd6c1bb7f7 100644 --- a/src/system_tests/ftp_rename_file.cpp +++ b/src/system_tests/ftp_rename_file.cpp @@ -26,10 +26,10 @@ TEST(SystemTest, FtpRenameFile) ASSERT_TRUE(reset_directories(temp_dir_provided)); ASSERT_TRUE(create_temp_file(temp_dir_provided / temp_file, 50)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); diff --git a/src/system_tests/ftp_upload_file.cpp b/src/system_tests/ftp_upload_file.cpp index e1d05c5bdd..ffc11942ef 100644 --- a/src/system_tests/ftp_upload_file.cpp +++ b/src/system_tests/ftp_upload_file.cpp @@ -29,10 +29,10 @@ TEST(SystemTest, FtpUploadFile) ASSERT_TRUE(create_temp_file(temp_dir_to_upload / temp_file, 50)); ASSERT_TRUE(reset_directories(temp_dir_provided)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); @@ -98,10 +98,10 @@ TEST(SystemTest, FtpUploadBigFile) ASSERT_TRUE(create_temp_file(temp_dir_to_upload / temp_file, 10000)); ASSERT_TRUE(reset_directories(temp_dir_provided)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); @@ -151,10 +151,10 @@ TEST(SystemTest, FtpUploadBigFileLossy) ASSERT_TRUE(create_temp_file(temp_dir_to_upload / temp_file, 10000)); ASSERT_TRUE(reset_directories(temp_dir_provided)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); unsigned counter = 0; @@ -213,10 +213,10 @@ TEST(SystemTest, FtpUploadStopAndTryAgain) ASSERT_TRUE(create_temp_file(temp_dir_to_upload / temp_file, 1000)); ASSERT_TRUE(reset_directories(temp_dir_provided)); - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); // Once we received half, we want to stop all traffic. @@ -302,10 +302,10 @@ TEST(SystemTest, FtpUploadFileOutsideOfRoot) // A test trying to push something into the parent (../) directory which // shouldn't be allowed! - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); diff --git a/src/system_tests/mission_raw_upload.cpp b/src/system_tests/mission_raw_upload.cpp index 000c31f07d..0400ecf333 100644 --- a/src/system_tests/mission_raw_upload.cpp +++ b/src/system_tests/mission_raw_upload.cpp @@ -11,9 +11,9 @@ using namespace mavsdk; TEST(SystemTest, MissionRawUpload) { - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); ASSERT_EQ( diff --git a/src/system_tests/param_custom_set_and_get.cpp b/src/system_tests/param_custom_set_and_get.cpp index 57c6cb2e2c..5eb3b926b5 100644 --- a/src/system_tests/param_custom_set_and_get.cpp +++ b/src/system_tests/param_custom_set_and_get.cpp @@ -29,10 +29,10 @@ static std::string generate_uppercase_ascii(size_t length) TEST(SystemTest, ParamCustomSetAndGet) { - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); @@ -81,10 +81,10 @@ TEST(SystemTest, ParamCustomSetAndGet) TEST(SystemTest, ParamCustomSetAndGetLossy) { - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); // Drop every third message diff --git a/src/system_tests/param_get_all.cpp b/src/system_tests/param_get_all.cpp index 9486fc5e26..80b2961b57 100644 --- a/src/system_tests/param_get_all.cpp +++ b/src/system_tests/param_get_all.cpp @@ -60,10 +60,10 @@ static void assert_equal(const std::map& values, const std::vec TEST(SystemTest, ParamGetAll) { - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); @@ -117,10 +117,10 @@ TEST(SystemTest, ParamGetAll) TEST(SystemTest, ParamGetAllLossy) { - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); // Drop every third message diff --git a/src/system_tests/param_set_and_get.cpp b/src/system_tests/param_set_and_get.cpp index 34129b78d1..16d6915384 100644 --- a/src/system_tests/param_set_and_get.cpp +++ b/src/system_tests/param_set_and_get.cpp @@ -18,10 +18,10 @@ static constexpr double reduced_timeout_s = 0.1; TEST(SystemTest, ParamSetAndGet) { - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); @@ -96,7 +96,7 @@ TEST(SystemTest, ParamSetAndGet) TEST(SystemTest, ParamSetAndGetLossy) { - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; mavsdk_groundstation.set_timeout_s(reduced_timeout_s); // Drop every third message @@ -106,7 +106,7 @@ TEST(SystemTest, ParamSetAndGetLossy) mavsdk_groundstation.intercept_incoming_messages_async(drop_some); mavsdk_groundstation.intercept_incoming_messages_async(drop_some); - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; mavsdk_autopilot.set_timeout_s(reduced_timeout_s); ASSERT_EQ(mavsdk_groundstation.add_any_connection("udp://:17000"), ConnectionResult::Success); diff --git a/src/system_tests/telemetry_subscription.cpp b/src/system_tests/telemetry_subscription.cpp index 44edba2868..85343afc83 100644 --- a/src/system_tests/telemetry_subscription.cpp +++ b/src/system_tests/telemetry_subscription.cpp @@ -10,9 +10,9 @@ using namespace mavsdk; TEST(SystemTest, TelemetrySubscription) { - Mavsdk mavsdk_groundstation{Mavsdk::Configuration{Mavsdk::ComponentType::GroundStation}}; + Mavsdk mavsdk_groundstation{Mavsdk::Configuration{ComponentType::GroundStation}}; - Mavsdk mavsdk_autopilot{Mavsdk::Configuration{Mavsdk::ComponentType::Autopilot}}; + Mavsdk mavsdk_autopilot{Mavsdk::Configuration{ComponentType::Autopilot}}; ASSERT_EQ( mavsdk_groundstation.add_any_connection("tcpin://0.0.0.0:13000"),