From a7f330075a3ba7f22691859adfcf96c8fcc0e997 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Sun, 27 Oct 2019 19:33:10 -0400 Subject: [PATCH] clang-tidy: enable hicpp-braces-around-statements and fix --- .clang-tidy | 1 - platforms/common/work_queue/queue.c | 2 +- src/modules/logger/logger.cpp | 2 +- src/modules/mavlink/mavlink_ftp.cpp | 2 +- src/modules/mavlink/mavlink_parameters.cpp | 2 +- 5 files changed, 4 insertions(+), 5 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index de59db208f..1f20700a50 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -48,7 +48,6 @@ Checks: '*, -google-readability-todo, -google-runtime-int, -google-runtime-references, - -hicpp-braces-around-statements, -hicpp-deprecated-headers, -hicpp-explicit-conversions, -hicpp-function-size, diff --git a/platforms/common/work_queue/queue.c b/platforms/common/work_queue/queue.c index 1b0d73c990..339e517a12 100644 --- a/platforms/common/work_queue/queue.c +++ b/platforms/common/work_queue/queue.c @@ -55,7 +55,7 @@ void sq_rem(sq_entry_t *node, sq_queue_t *queue) for (prev = (sq_entry_t *)queue->head; prev && prev->flink != node; - prev = prev->flink); + prev = prev->flink) {} if (prev) { sq_remafter(prev, queue); diff --git a/src/modules/logger/logger.cpp b/src/modules/logger/logger.cpp index 9a3e3e0d62..0f49e32f3d 100644 --- a/src/modules/logger/logger.cpp +++ b/src/modules/logger/logger.cpp @@ -1152,7 +1152,7 @@ void Logger::run() * And on linux this is quite accurate as well, but under NuttX it is not accurate, * because usleep() has only a granularity of CONFIG_MSEC_PER_TICK (=1ms). */ - while (px4_sem_wait(&timer_callback_data.semaphore) != 0); + while (px4_sem_wait(&timer_callback_data.semaphore) != 0) {} } } diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index e3a43dbf47..ca421871be 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -364,7 +364,7 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden) // move to the requested offset int requested_offset = payload->offset; - while (requested_offset-- > 0 && readdir(dp)); + while (requested_offset-- > 0 && readdir(dp)) {} for (;;) { errno = 0; diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index 2fa2961f2a..7aec610f9d 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -289,7 +289,7 @@ MavlinkParametersManager::send(const hrt_abstime t) int i = 0; // Send while burst is not exceeded, we still have buffer space and still something to send - while ((i++ < max_num_to_send) && (_mavlink->get_free_tx_buf() >= get_size()) && send_params()); + while ((i++ < max_num_to_send) && (_mavlink->get_free_tx_buf() >= get_size()) && send_params()) {} } bool