diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index 1a597ad4c3..5570e86df9 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -60,6 +60,8 @@ if (DEFINED EXTERNAL_DIR AND NOT EXTERNAL_DIR STREQUAL "") include_directories(${EXTERNAL_DIR}) endif() +include(cmake/static_analyzers.cmake) + if(BUILD_TESTS) enable_testing() add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/third_party/gtest EXCLUDE_FROM_ALL) diff --git a/src/cmake/static_analyzers.cmake b/src/cmake/static_analyzers.cmake new file mode 100644 index 0000000000..b0eba8955e --- /dev/null +++ b/src/cmake/static_analyzers.cmake @@ -0,0 +1,40 @@ +# Taken from https://github.com/lefticus/cpp_starter_project/blob/master/cmake/StaticAnalyzers.cmake +option(ENABLE_CPPCHECK "Enable static analysis with cppcheck" OFF) +option(ENABLE_CLANG_TIDY "Enable static analysis with clang-tidy" OFF) +option(ENABLE_INCLUDE_WHAT_YOU_USE "Enable static analysis with include-what-you-use" OFF) + +if(ENABLE_CPPCHECK) + find_program(CPPCHECK cppcheck) + if(CPPCHECK) + set(CMAKE_CXX_CPPCHECK + ${CPPCHECK} + --suppress=missingIncludeSystem:missingInclude + --suppress=*:*/src/third_party/* + -Isrc/mavsdk + --inline-suppr + --inconclusive + --std=c++17 + . + ) + else() + message(SEND_ERROR "cppcheck requested but executable not found") + endif() +endif() + +if(ENABLE_CLANG_TIDY) + find_program(CLANGTIDY clang-tidy) + if(CLANGTIDY) + set(CMAKE_CXX_CLANG_TIDY ${CLANGTIDY} -extra-arg=-Wno-unknown-warning-option) + else() + message(SEND_ERROR "clang-tidy requested but executable not found") + endif() +endif() + +if(ENABLE_INCLUDE_WHAT_YOU_USE) + find_program(INCLUDE_WHAT_YOU_USE include-what-you-use) + if(INCLUDE_WHAT_YOU_USE) + set(CMAKE_CXX_INCLUDE_WHAT_YOU_USE ${INCLUDE_WHAT_YOU_USE}) + else() + message(SEND_ERROR "include-what-you-use requested but executable not found") + endif() +endif() \ No newline at end of file diff --git a/src/core/call_every_handler.h b/src/core/call_every_handler.h index 1736071c0f..d134d56ed4 100644 --- a/src/core/call_every_handler.h +++ b/src/core/call_every_handler.h @@ -10,7 +10,7 @@ namespace mavsdk { class CallEveryHandler { public: - CallEveryHandler(Time& time); + explicit CallEveryHandler(Time& time); ~CallEveryHandler(); // delete copy and move constructors and assign operators @@ -30,7 +30,7 @@ class CallEveryHandler { struct Entry { std::function callback{nullptr}; dl_time_t last_time{}; - double interval_s{0.0f}; + double interval_s{0.0}; }; std::unordered_map> _entries{}; diff --git a/src/core/call_every_handler_test.cpp b/src/core/call_every_handler_test.cpp index 6f201d5582..4d296cba88 100644 --- a/src/core/call_every_handler_test.cpp +++ b/src/core/call_every_handler_test.cpp @@ -18,7 +18,7 @@ TEST(CallEveryHandler, Single) int num_called = 0; void* cookie = nullptr; - ceh.add([&num_called]() { ++num_called; }, 0.1f, &cookie); + ceh.add([&num_called]() { ++num_called; }, 0.1, &cookie); for (int i = 0; i < 11; ++i) { time.sleep_for(std::chrono::milliseconds(10)); @@ -37,7 +37,7 @@ TEST(CallEveryHandler, Multiple) int num_called = 0; void* cookie = nullptr; - ceh.add([&num_called]() { ++num_called; }, 0.1f, &cookie); + ceh.add([&num_called]() { ++num_called; }, 0.1, &cookie); for (int i = 0; i < 10; ++i) { ceh.run_once(); @@ -46,7 +46,7 @@ TEST(CallEveryHandler, Multiple) EXPECT_EQ(num_called, 10); num_called = 0; - ceh.change(0.2f, cookie); + ceh.change(0.2, cookie); for (int i = 0; i < 20; ++i) { time.sleep_for(std::chrono::milliseconds(100)); @@ -72,8 +72,8 @@ TEST(CallEveryHandler, InParallel) void* cookie1 = nullptr; void* cookie2 = nullptr; - ceh.add([&num_called1]() { ++num_called1; }, 0.1f, &cookie1); - ceh.add([&num_called2]() { ++num_called2; }, 0.2f, &cookie2); + ceh.add([&num_called1]() { ++num_called1; }, 0.1, &cookie1); + ceh.add([&num_called2]() { ++num_called2; }, 0.2, &cookie2); for (int i = 0; i < 10; ++i) { ceh.run_once(); @@ -86,8 +86,8 @@ TEST(CallEveryHandler, InParallel) num_called1 = 0; num_called2 = 0; - ceh.change(0.4f, cookie1); - ceh.change(0.1f, cookie2); + ceh.change(0.4, cookie1); + ceh.change(0.1, cookie2); for (int i = 0; i < 10; ++i) { ceh.run_once(); @@ -106,7 +106,7 @@ TEST(CallEveryHandler, Reset) int num_called = 0; void* cookie = nullptr; - ceh.add([&num_called]() { ++num_called; }, 0.1f, &cookie); + ceh.add([&num_called]() { ++num_called; }, 0.1, &cookie); for (int i = 0; i < 8; ++i) { ceh.run_once(); @@ -137,7 +137,7 @@ TEST(CallEveryHandler, CallImmediately) int num_called = 0; void* cookie = nullptr; - ceh.add([&num_called]() { ++num_called; }, 0.1f, &cookie); + ceh.add([&num_called]() { ++num_called; }, 0.1, &cookie); for (int i = 0; i < 1; ++i) { ceh.run_once(); diff --git a/src/core/cli_arg.h b/src/core/cli_arg.h index 1838796cb7..aa183031cc 100644 --- a/src/core/cli_arg.h +++ b/src/core/cli_arg.h @@ -10,7 +10,7 @@ class CliArg { bool parse(const std::string& uri); - Protocol get_protocol() { return _protocol; } + Protocol get_protocol() const { return _protocol; } int get_port() const { return _port; } diff --git a/src/core/locked_queue.h b/src/core/locked_queue.h index 5f979ca301..efaf14d723 100644 --- a/src/core/locked_queue.h +++ b/src/core/locked_queue.h @@ -8,8 +8,8 @@ namespace mavsdk { template class LockedQueue { public: - LockedQueue(){}; - ~LockedQueue(){}; + LockedQueue() = default; + ~LockedQueue() = default; void push_back(std::shared_ptr item_ptr) { @@ -34,7 +34,7 @@ template class LockedQueue { // Thus, no one can interfere between the two steps. class Guard { public: - Guard(LockedQueue& locked_queue) : _locked_queue(locked_queue) + explicit Guard(LockedQueue& locked_queue) : _locked_queue(locked_queue) { _locked_queue._mutex.lock(); } diff --git a/src/core/mavlink_channels.h b/src/core/mavlink_channels.h index e15d23992c..f9b2cf5916 100644 --- a/src/core/mavlink_channels.h +++ b/src/core/mavlink_channels.h @@ -39,7 +39,7 @@ class MAVLinkChannels { */ void checkin_used_channel(uint8_t used_channel); - uint8_t get_max_channels() { return MAX_CHANNELS; } + static constexpr uint8_t get_max_channels() { return MAX_CHANNELS; } private: // It is not clear what the limit of the number of channels is, except UINT8_MAX. diff --git a/src/core/mavlink_mission_transfer_test.cpp b/src/core/mavlink_mission_transfer_test.cpp index c67356559f..56ed7fee20 100644 --- a/src/core/mavlink_mission_transfer_test.cpp +++ b/src/core/mavlink_mission_transfer_test.cpp @@ -897,7 +897,7 @@ TEST(MAVLinkMissionTransfer, UploadMissionCanBeCancelled) message_handler.process_message(make_mission_request_int(MAV_MISSION_TYPE_MISSION, 0)); - EXPECT_CALL(mock_sender, send_message(Truly([&items](const mavlink_message_t& message) { + EXPECT_CALL(mock_sender, send_message(Truly([](const mavlink_message_t& message) { return is_correct_mission_ack( MAV_MISSION_TYPE_MISSION, MAV_MISSION_OPERATION_CANCELLED, message); }))); @@ -958,7 +958,7 @@ TEST(MAVLinkMissionTransfer, UploadMissionNacksNonIntCase) }); mmt.do_work(); - EXPECT_CALL(mock_sender, send_message(Truly([&items](const mavlink_message_t& message) { + EXPECT_CALL(mock_sender, send_message(Truly([](const mavlink_message_t& message) { return is_correct_mission_ack( MAV_MISSION_TYPE_FENCE, MAV_MISSION_UNSUPPORTED, message); }))) @@ -1479,7 +1479,7 @@ TEST(MAVLinkMissionTransfer, DownloadMissionCanBeCancelled) message_handler.process_message(make_mission_count(items.size())); message_handler.process_message(make_mission_item(items, 0)); - EXPECT_CALL(mock_sender, send_message(Truly([&items](const mavlink_message_t& message) { + EXPECT_CALL(mock_sender, send_message(Truly([](const mavlink_message_t& message) { return is_correct_mission_ack( MAV_MISSION_TYPE_MISSION, MAV_MISSION_OPERATION_CANCELLED, message); }))); diff --git a/src/core/timeout_handler.h b/src/core/timeout_handler.h index 0202e2dfac..911a2fbd6c 100644 --- a/src/core/timeout_handler.h +++ b/src/core/timeout_handler.h @@ -10,7 +10,7 @@ namespace mavsdk { class TimeoutHandler { public: - TimeoutHandler(Time& time); + explicit TimeoutHandler(Time& time); ~TimeoutHandler(); // delete copy and move constructors and assign operators diff --git a/src/integration_tests/camera_settings.cpp b/src/integration_tests/camera_settings.cpp index 58929cb371..1cdd559579 100644 --- a/src/integration_tests/camera_settings.cpp +++ b/src/integration_tests/camera_settings.cpp @@ -197,7 +197,7 @@ TEST(CameraTest, SetSettings) EXPECT_EQ(camera->set_mode(Camera::Mode::Video), Camera::Result::Success); - settings = camera->possible_setting_options(); + UNUSED(camera->possible_setting_options()); // This should fail in video mode. EXPECT_EQ(set_setting(camera, "CAM_PHOTOQUAL", "1"), Camera::Result::Error); diff --git a/src/integration_tests/camera_status.cpp b/src/integration_tests/camera_status.cpp index ef7b92e06e..af7f21d84c 100644 --- a/src/integration_tests/camera_status.cpp +++ b/src/integration_tests/camera_status.cpp @@ -8,8 +8,8 @@ using namespace mavsdk; using namespace std::placeholders; // for `_1` -static void receive_camera_status(const Camera::Status status); -static void print_camera_status(const Camera::Status status); +static void receive_camera_status(const Camera::Status& status); +static void print_camera_status(const Camera::Status& status); static std::atomic _received_status{false}; @@ -31,13 +31,13 @@ TEST(CameraTest, Status) EXPECT_TRUE(_received_status); } -static void receive_camera_status(const Camera::Status status) +static void receive_camera_status(const Camera::Status& status) { _received_status = true; print_camera_status(status); } -static void print_camera_status(const Camera::Status status) +static void print_camera_status(const Camera::Status& status) { std::string storage_status_str = ""; switch (status.storage_status) { diff --git a/src/integration_tests/camera_test_helpers.cpp b/src/integration_tests/camera_test_helpers.cpp index 44a2054d0e..9d116b3c62 100644 --- a/src/integration_tests/camera_test_helpers.cpp +++ b/src/integration_tests/camera_test_helpers.cpp @@ -35,8 +35,7 @@ void set_mode_async(std::shared_ptr camera, Camera::Mode mode) auto prom = std::make_shared>(); auto ret = prom->get_future(); - - camera->set_mode_async(mode, [mode, prom](Camera::Result result) { + camera->set_mode_async(mode, [prom](Camera::Result result) { EXPECT_EQ(result, Camera::Result::Success); prom->set_value(); }); diff --git a/src/integration_tests/camera_test_helpers.h b/src/integration_tests/camera_test_helpers.h index 695f21a24a..a181d24e3c 100644 --- a/src/integration_tests/camera_test_helpers.h +++ b/src/integration_tests/camera_test_helpers.h @@ -7,7 +7,9 @@ mavsdk::Camera::Mode get_mode(std::shared_ptr camera); void set_mode_async(std::shared_ptr camera, mavsdk::Camera::Mode mode); mavsdk::Camera::Result set_setting( - std::shared_ptr camera, const std::string& setting, const std::string& option); + std::shared_ptr camera, + const std::string& setting_id, + const std::string& option_id); mavsdk::Camera::Result get_setting( - std::shared_ptr camera, const std::string& setting, std::string& option); + std::shared_ptr camera, const std::string& setting_id, std::string& option_d); diff --git a/src/integration_tests/ftp.cpp b/src/integration_tests/ftp.cpp index ce6559feef..3f29f3c8b8 100644 --- a/src/integration_tests/ftp.cpp +++ b/src/integration_tests/ftp.cpp @@ -195,13 +195,13 @@ TEST(FtpTest, DownloadFile) reset_server(ftp); auto mavlink_passthrough = std::make_shared(system); - mavlink_passthrough->intercept_incoming_messages_async([this](mavlink_message_t& message) { + mavlink_passthrough->intercept_incoming_messages_async([](const mavlink_message_t& message) { if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { return true; } return (distribution(random_engine) > 0.01); }); - mavlink_passthrough->intercept_outgoing_messages_async([this](mavlink_message_t& message) { + mavlink_passthrough->intercept_outgoing_messages_async([](const mavlink_message_t& message) { if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { return true; } @@ -227,13 +227,13 @@ TEST(FtpTest, UploadFiles) reset_server(ftp); auto mavlink_passthrough = std::make_shared(system); - mavlink_passthrough->intercept_incoming_messages_async([this](mavlink_message_t& message) { + mavlink_passthrough->intercept_incoming_messages_async([](const mavlink_message_t& message) { if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { return true; } return (distribution(random_engine) > 0.01); }); - mavlink_passthrough->intercept_outgoing_messages_async([this](mavlink_message_t& message) { + mavlink_passthrough->intercept_outgoing_messages_async([](const mavlink_message_t& message) { if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { return true; } @@ -292,13 +292,13 @@ TEST(FtpTest, TestServer) auto system_cc = mavsdk_cc.systems().at(0); auto mavlink_passthrough_cc = std::make_shared(system_cc); - mavlink_passthrough_cc->intercept_incoming_messages_async([this](mavlink_message_t& message) { + mavlink_passthrough_cc->intercept_incoming_messages_async([](const mavlink_message_t& message) { if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { return true; } return (distribution(random_engine) > 0.1); }); - mavlink_passthrough_cc->intercept_outgoing_messages_async([this](mavlink_message_t& message) { + mavlink_passthrough_cc->intercept_outgoing_messages_async([](const mavlink_message_t& message) { if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) { return true; } diff --git a/src/integration_tests/gimbal.cpp b/src/integration_tests/gimbal.cpp index 083c0ec45e..9928b22734 100644 --- a/src/integration_tests/gimbal.cpp +++ b/src/integration_tests/gimbal.cpp @@ -13,7 +13,6 @@ using namespace mavsdk; -void send_new_gimbal_command(std::shared_ptr gimbal, int i); void gimbal_pattern(std::shared_ptr gimbal); void send_gimbal_roi_location( std::shared_ptr gimbal, double latitude_deg, double longitude_deg, float altitude_m); @@ -335,19 +334,6 @@ TEST(SitlTestGimbal, GimbalROIOffboard) std::this_thread::sleep_for(std::chrono::seconds(3)); } -void send_new_gimbal_command(std::shared_ptr gimbal, int i) -{ - float pitch_deg = 30.0f * cosf(i / 360.0f * 2 * M_PI_F); - float yaw_deg = 45.0f * sinf(i / 360.0f * 2 * M_PI_F); - - gimbal->set_pitch_and_yaw_async(pitch_deg, yaw_deg, &receive_gimbal_result); -} - -void send_gimbal_mode_command(std::shared_ptr gimbal, const Gimbal::GimbalMode gimbal_mode) -{ - gimbal->set_mode_async(gimbal_mode, &receive_gimbal_result); -} - void send_gimbal_roi_location( std::shared_ptr gimbal, double latitude_deg, double longitude_deg, float altitude_m) { diff --git a/src/integration_tests/log_files.cpp b/src/integration_tests/log_files.cpp index cc602c7752..f566e52ce8 100644 --- a/src/integration_tests/log_files.cpp +++ b/src/integration_tests/log_files.cpp @@ -26,9 +26,9 @@ TEST(HardwareTest, LogFiles) EXPECT_EQ(entry_result.first, LogFiles::Result::Success); - unsigned num_downloaded_files = 0; - if (entry_result.first == LogFiles::Result::Success) { + unsigned num_downloaded_files = 0; + for (auto& entry : entry_result.second) { float size_mib = entry.size_bytes / 1024.0f / 1024.0f; LogInfo() << "Entry " << entry.id << ": " diff --git a/src/integration_tests/mission_rtl.cpp b/src/integration_tests/mission_rtl.cpp index f589667a9c..1c05dfd742 100644 --- a/src/integration_tests/mission_rtl.cpp +++ b/src/integration_tests/mission_rtl.cpp @@ -16,7 +16,7 @@ using namespace std::placeholders; // for `_1` // TODO: add checks that verify the return altitude -void do_mission_with_rtl(float mission_altitude_m, float rtl_altitude_m); +void do_mission_with_rtl(float mission_altitude_m, float return_altitude_m); TEST_F(SitlTest, MissionWithRTLHigh) { @@ -118,7 +118,7 @@ void do_mission_with_rtl(float mission_altitude_m, float return_altitude_m) LogInfo() << "Armed."; // Before starting the mission, we want to be sure to subscribe to the mission progress. - mission->subscribe_mission_progress([&mission](Mission::MissionProgress progress) { + mission->subscribe_mission_progress([](Mission::MissionProgress progress) { LogInfo() << "Mission status update: " << progress.current << " / " << progress.total; }); diff --git a/src/integration_tests/mission_transfer_lossy.cpp b/src/integration_tests/mission_transfer_lossy.cpp index 8711eeb650..4239c8a2ef 100644 --- a/src/integration_tests/mission_transfer_lossy.cpp +++ b/src/integration_tests/mission_transfer_lossy.cpp @@ -54,10 +54,10 @@ TEST_F(SitlTest, MissionTransferLossy) void set_link_lossy(std::shared_ptr mavlink_passthrough) { mavlink_passthrough->intercept_outgoing_messages_async( - [](mavlink_message_t& message) { return should_keep_message(message); }); + [](const mavlink_message_t& message) { return should_keep_message(message); }); mavlink_passthrough->intercept_incoming_messages_async( - [](mavlink_message_t& message) { return should_keep_message(message); }); + [](const mavlink_message_t& message) { return should_keep_message(message); }); } bool should_keep_message(const mavlink_message_t& message) diff --git a/src/integration_tests/offboard_attitude.cpp b/src/integration_tests/offboard_attitude.cpp index fa449edbfb..98c2564529 100644 --- a/src/integration_tests/offboard_attitude.cpp +++ b/src/integration_tests/offboard_attitude.cpp @@ -10,11 +10,11 @@ using namespace mavsdk; static void arm_and_takeoff(std::shared_ptr action, std::shared_ptr telemetry); static void disarm_and_land(std::shared_ptr action, std::shared_ptr telemetry); -static void start_offboard(Offboard& offboard); -static void stop_offboard(Offboard& offboard); -static void flip_roll(Offboard& offboard, std::shared_ptr telemetry); -static void flip_pitch(Offboard& offboard, std::shared_ptr telemetry); -static void turn_yaw(Offboard& offboard); +static void start_offboard(const Offboard& offboard); +static void stop_offboard(const Offboard& offboard); +static void flip_roll(const Offboard& offboard, std::shared_ptr telemetry); +static void flip_pitch(const Offboard& offboard, std::shared_ptr telemetry); +static void turn_yaw(const Offboard& offboard); TEST(SitlTestDisabled, OffboardAttitudeRate) { @@ -80,7 +80,7 @@ void disarm_and_land(std::shared_ptr action, std::shared_ptr } } -void start_offboard(Offboard& offboard) +void start_offboard(const Offboard& offboard) { // Send it once before starting offboard, otherwise it will be rejected. // Also, turn yaw towards North. @@ -91,12 +91,12 @@ void start_offboard(Offboard& offboard) std::this_thread::sleep_for(std::chrono::seconds(1)); } -void stop_offboard(Offboard& offboard) +void stop_offboard(const Offboard& offboard) { EXPECT_EQ(offboard.stop(), Offboard::Result::Success); } -void flip_roll(Offboard& offboard, std::shared_ptr telemetry) +void flip_roll(const Offboard& offboard, std::shared_ptr telemetry) { while (telemetry->position().relative_altitude_m < 10.0f) { // Full speed up to avoid loosing too much altitude during the flip. @@ -121,7 +121,7 @@ void flip_roll(Offboard& offboard, std::shared_ptr telemetry) std::this_thread::sleep_for(std::chrono::seconds(2)); } -void flip_pitch(Offboard& offboard, std::shared_ptr telemetry) +void flip_pitch(const Offboard& offboard, std::shared_ptr telemetry) { while (telemetry->position().relative_altitude_m < 10.0f) { // Full speed up to avoid loosing too much altitude during the flip. @@ -148,7 +148,7 @@ void flip_pitch(Offboard& offboard, std::shared_ptr telemetry) std::this_thread::sleep_for(std::chrono::seconds(2)); } -void turn_yaw(Offboard& offboard) +void turn_yaw(const Offboard& offboard) { Offboard::AttitudeRate yaw{}; yaw.yaw_deg_s = 360.0f; diff --git a/src/integration_tests/offboard_position.cpp b/src/integration_tests/offboard_position.cpp index 75920a1ddc..fe9855d2b2 100644 --- a/src/integration_tests/offboard_position.cpp +++ b/src/integration_tests/offboard_position.cpp @@ -58,7 +58,8 @@ TEST_F(SitlTest, OffboardPositionNED) { const float radius = 10.0f; const float step = 0.01f; - for (float angle = 0.0f; angle <= 2.0f * M_PI_F; angle += step) { + float angle = 0.0f; + while (angle <= 2.0f * M_PI_F) { float x = radius * cosf(angle); float y = radius * sinf(angle); @@ -69,6 +70,8 @@ TEST_F(SitlTest, OffboardPositionNED) setpoint.yaw_deg = 90.0f; offboard->set_position_ned(setpoint); std::this_thread::sleep_for(std::chrono::milliseconds(50)); + + angle += step; } offboard->set_position_ned(up_and_yaw); } diff --git a/src/integration_tests/path_checker.h b/src/integration_tests/path_checker.h index 61a7964e69..6d90985d7d 100644 --- a/src/integration_tests/path_checker.h +++ b/src/integration_tests/path_checker.h @@ -10,7 +10,7 @@ class PathChecker { void set_max_altitude(float relative_altitude_m); void set_min_altitude(float relative_altitude_m); void set_next_reach_altitude(float relative_altitude_m); - void set_margin(float margin); + void set_margin(float margin_m); void check_current_alitude(float current_altitude); private: diff --git a/src/integration_tests/system_connection_async.cpp b/src/integration_tests/system_connection_async.cpp index 3a875733b5..df5ec787c8 100644 --- a/src/integration_tests/system_connection_async.cpp +++ b/src/integration_tests/system_connection_async.cpp @@ -20,7 +20,7 @@ TEST_F(SitlTest, SystemConnectionAsync) ASSERT_EQ(mavsdk.add_udp_connection(), ConnectionResult::Success); - mavsdk.subscribe_on_new_system([this, &mavsdk]() { + mavsdk.subscribe_on_new_system([&mavsdk]() { const auto system = mavsdk.systems().at(0); const auto sysid = system->get_system_id(); diff --git a/src/integration_tests/telemetry_async.cpp b/src/integration_tests/telemetry_async.cpp index 15d0a4f637..67d4af50c2 100644 --- a/src/integration_tests/telemetry_async.cpp +++ b/src/integration_tests/telemetry_async.cpp @@ -19,13 +19,13 @@ static void print_quaternion(Telemetry::Quaternion quaternion); static void print_euler_angle(Telemetry::EulerAngle euler_angle); static void print_angular_velocity_body(Telemetry::AngularVelocityBody angular_velocity_body); static void print_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics); -static void print_ground_truth(Telemetry::GroundTruth ground_truth); +static void print_ground_truth(const Telemetry::GroundTruth& ground_truth); #if CAMERA_AVAILABLE == 1 static void print_camera_quaternion(Telemetry::Quaternion quaternion); static void print_camera_euler_angle(Telemetry::EulerAngle euler_angle); #endif static void print_velocity_ned(Telemetry::VelocityNed velocity_ned); -static void print_imu_reading_ned(Telemetry::Imu imu_reading_ned); +static void print_imu(Telemetry::Imu imu); static void print_gps_info(Telemetry::GpsInfo gps_info); static void print_battery(Telemetry::Battery battery); static void print_rc_status(Telemetry::RcStatus rc_status); @@ -49,7 +49,7 @@ static bool _received_camera_quaternion = false; static bool _received_camera_euler_angle = false; #endif static bool _received_velocity = false; -static bool _received_imu_reading_ned = false; +static bool _received_imu = false; static bool _received_gps_info = false; static bool _received_battery = false; static bool _received_rc_status = false; @@ -134,7 +134,7 @@ TEST_F(SitlTest, TelemetryAsync) telemetry->subscribe_velocity_ned(std::bind(&print_velocity_ned, _1)); - telemetry->subscribe_imu(std::bind(&print_imu_reading_ned, _1)); + telemetry->subscribe_imu(std::bind(&print_imu, _1)); telemetry->subscribe_gps_info(std::bind(&print_gps_info, _1)); @@ -167,7 +167,7 @@ TEST_F(SitlTest, TelemetryAsync) EXPECT_TRUE(_received_camera_euler_angle); #endif EXPECT_TRUE(_received_velocity); - EXPECT_TRUE(_received_imu_reading_ned); + EXPECT_TRUE(_received_imu); EXPECT_TRUE(_received_gps_info); EXPECT_TRUE(_received_battery); // EXPECT_TRUE(_received_rc_status); // No RC is sent in SITL. @@ -246,7 +246,7 @@ void print_fixedwing_metrics(Telemetry::FixedwingMetrics fixedwing_metrics) _received_fixedwing_metrics = true; } -void print_ground_truth(Telemetry::GroundTruth ground_truth) +void print_ground_truth(const Telemetry::GroundTruth& ground_truth) { std::cout << ground_truth << '\n'; _received_ground_truth = true; @@ -278,11 +278,11 @@ void print_velocity_ned(Telemetry::VelocityNed velocity_ned) _received_velocity = true; } -void print_imu_reading_ned(Telemetry::Imu imu) +void print_imu(Telemetry::Imu imu) { std::cout << imu << '\n'; - _received_imu_reading_ned = true; + _received_imu = true; } void print_gps_info(Telemetry::GpsInfo gps_info) diff --git a/src/plugins/mission/mission_equality_operator_test.cpp b/src/plugins/mission/mission_equality_operator_test.cpp index e0fbadd439..51b201e044 100644 --- a/src/plugins/mission/mission_equality_operator_test.cpp +++ b/src/plugins/mission/mission_equality_operator_test.cpp @@ -46,7 +46,7 @@ TEST(MissionOperator, MissionItemEqualsOperatorIsValidForArbitraryItems) TEST(MissionOperator, MissionItemEqualsOperatorIsValidForDifferentItems) { Mission::MissionItem mission_item1; - Mission::MissionItem mission_item2; + Mission::MissionItem mission_item2{}; mission_item1.latitude_deg = 47.3982; mission_item1.longitude_deg = 8.54567; @@ -180,7 +180,7 @@ TEST(MissionOperator, MissionPlanOperatorIsValidForDifferentPlans) mission_plan1.mission_items = mission_items1; // Second MissionPlan - Mission::MissionPlan mission_plan2; + Mission::MissionPlan mission_plan2{}; ASSERT_FALSE(mission_plan1 == mission_plan2); } diff --git a/src/third_party/gtest b/src/third_party/gtest index 10b1902d89..e8b478a735 160000 --- a/src/third_party/gtest +++ b/src/third_party/gtest @@ -1 +1 @@ -Subproject commit 10b1902d893ea8cc43c69541d70868f91af3646b +Subproject commit e8b478a7356f21efbada1aae15b49b332cc54e3f