Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Some static analysis #1335

Merged
merged 6 commits into from
Mar 2, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
40 changes: 40 additions & 0 deletions src/cmake/static_analyzers.cmake
Original file line number Diff line number Diff line change
@@ -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()
4 changes: 2 additions & 2 deletions src/core/call_every_handler.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -30,7 +30,7 @@ class CallEveryHandler {
struct Entry {
std::function<void()> callback{nullptr};
dl_time_t last_time{};
double interval_s{0.0f};
double interval_s{0.0};
};

std::unordered_map<void*, std::shared_ptr<Entry>> _entries{};
Expand Down
18 changes: 9 additions & 9 deletions src/core/call_every_handler_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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));
Expand All @@ -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();
Expand All @@ -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));
Expand All @@ -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();
Expand All @@ -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();
Expand All @@ -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();
Expand Down Expand Up @@ -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();
Expand Down
2 changes: 1 addition & 1 deletion src/core/cli_arg.h
Original file line number Diff line number Diff line change
Expand Up @@ -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; }

Expand Down
6 changes: 3 additions & 3 deletions src/core/locked_queue.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@ namespace mavsdk {

template<class T> class LockedQueue {
public:
LockedQueue(){};
~LockedQueue(){};
LockedQueue() = default;
~LockedQueue() = default;

void push_back(std::shared_ptr<T> item_ptr)
{
Expand All @@ -34,7 +34,7 @@ template<class T> 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();
}
Expand Down
2 changes: 1 addition & 1 deletion src/core/mavlink_channels.h
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
6 changes: 3 additions & 3 deletions src/core/mavlink_mission_transfer_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
})));
Expand Down Expand Up @@ -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);
})))
Expand Down Expand Up @@ -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);
})));
Expand Down
2 changes: 1 addition & 1 deletion src/core/timeout_handler.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion src/integration_tests/camera_settings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
8 changes: 4 additions & 4 deletions src/integration_tests/camera_status.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<bool> _received_status{false};

Expand All @@ -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) {
Expand Down
3 changes: 1 addition & 2 deletions src/integration_tests/camera_test_helpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,8 +35,7 @@ void set_mode_async(std::shared_ptr<Camera> camera, Camera::Mode mode)

auto prom = std::make_shared<std::promise<void>>();
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();
});
Expand Down
6 changes: 4 additions & 2 deletions src/integration_tests/camera_test_helpers.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,9 @@ mavsdk::Camera::Mode get_mode(std::shared_ptr<mavsdk::Camera> camera);
void set_mode_async(std::shared_ptr<mavsdk::Camera> camera, mavsdk::Camera::Mode mode);

mavsdk::Camera::Result set_setting(
std::shared_ptr<mavsdk::Camera> camera, const std::string& setting, const std::string& option);
std::shared_ptr<mavsdk::Camera> camera,
const std::string& setting_id,
const std::string& option_id);

mavsdk::Camera::Result get_setting(
std::shared_ptr<mavsdk::Camera> camera, const std::string& setting, std::string& option);
std::shared_ptr<mavsdk::Camera> camera, const std::string& setting_id, std::string& option_d);
12 changes: 6 additions & 6 deletions src/integration_tests/ftp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,13 +195,13 @@ TEST(FtpTest, DownloadFile)
reset_server(ftp);

auto mavlink_passthrough = std::make_shared<MavlinkPassthrough>(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;
}
Expand All @@ -227,13 +227,13 @@ TEST(FtpTest, UploadFiles)
reset_server(ftp);

auto mavlink_passthrough = std::make_shared<MavlinkPassthrough>(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;
}
Expand Down Expand Up @@ -292,13 +292,13 @@ TEST(FtpTest, TestServer)
auto system_cc = mavsdk_cc.systems().at(0);

auto mavlink_passthrough_cc = std::make_shared<MavlinkPassthrough>(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;
}
Expand Down
14 changes: 0 additions & 14 deletions src/integration_tests/gimbal.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,6 @@

using namespace mavsdk;

void send_new_gimbal_command(std::shared_ptr<Gimbal> gimbal, int i);
void gimbal_pattern(std::shared_ptr<Gimbal> gimbal);
void send_gimbal_roi_location(
std::shared_ptr<Gimbal> gimbal, double latitude_deg, double longitude_deg, float altitude_m);
Expand Down Expand Up @@ -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> 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> gimbal, const Gimbal::GimbalMode gimbal_mode)
{
gimbal->set_mode_async(gimbal_mode, &receive_gimbal_result);
}

void send_gimbal_roi_location(
std::shared_ptr<Gimbal> gimbal, double latitude_deg, double longitude_deg, float altitude_m)
{
Expand Down
4 changes: 2 additions & 2 deletions src/integration_tests/log_files.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 << ": "
Expand Down
4 changes: 2 additions & 2 deletions src/integration_tests/mission_rtl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand Down Expand Up @@ -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;
});

Expand Down
4 changes: 2 additions & 2 deletions src/integration_tests/mission_transfer_lossy.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,10 +54,10 @@ TEST_F(SitlTest, MissionTransferLossy)
void set_link_lossy(std::shared_ptr<MavlinkPassthrough> 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)
Expand Down
Loading