From d317113dc8b6d41c8304440c8846e69dc511cd4a Mon Sep 17 00:00:00 2001 From: Ege Kural Date: Fri, 27 Feb 2026 04:04:45 -0500 Subject: [PATCH] CI: enable clang-tidy bugprone-assignment-in-if-condition (#26580) * docs: auto-sync metadata [skip ci] Co-Authored-By: PX4 BuildBot CI: enable clang-tidy bugprone-assignment-in-if-condition Signed-off-by: kuralme initialize and immediate assignments made one line Signed-off-by: kuralme * two more initialization fix Signed-off-by: kuralme --------- Signed-off-by: kuralme Co-authored-by: PX4BuildBot --- .clang-tidy | 1 - .../uORB/uORB_tests/uORBTest_UnitTest.cpp | 8 ++++---- platforms/posix/src/px4/common/SerialImpl.cpp | 16 +++++++++++----- .../posix/src/px4/common/px4_daemon/pxh.cpp | 8 ++++---- .../posix/src/px4/common/px4_daemon/server.cpp | 4 ++-- .../src/px4/common/px4_daemon/server_io.cpp | 18 +++++++++--------- src/drivers/osd/msp_osd/MspV1.cpp | 12 +++++++++--- src/lib/led/led.cpp | 4 +++- src/modules/gimbal/input_mavlink.cpp | 12 +++++++++--- .../simulator_mavlink/SimulatorMavlink.cpp | 8 ++++++-- .../uxrce_dds_client/uxrce_dds_client.cpp | 12 +++++++++--- 11 files changed, 66 insertions(+), 37 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index 6713228d7b..fa3fe3f1fb 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -149,7 +149,6 @@ Checks: '*, -cppcoreguidelines-explicit-virtual-functions, -readability-convert-member-functions-to-static, -readability-make-member-function-const, - -bugprone-assignment-in-if-condition, -bugprone-implicit-widening-of-multiplication-result, -bugprone-macro-parentheses, -bugprone-multi-level-implicit-pointer-conversion, diff --git a/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp b/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp index 035d2f9ac5..d96fc0e983 100644 --- a/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp +++ b/platforms/common/uORB/uORB_tests/uORBTest_UnitTest.cpp @@ -941,10 +941,10 @@ int uORBTest::UnitTest::pub_test_queue_entry(int argc, char *argv[]) int uORBTest::UnitTest::pub_test_queue_main() { orb_test_medium_s t{}; - orb_advert_t ptopic{nullptr}; + orb_advert_t ptopic = orb_advertise(ORB_ID(orb_test_medium_queue_poll), &t); const int queue_size = orb_get_queue_size(ORB_ID(orb_test_medium_queue_poll)); - if ((ptopic = orb_advertise(ORB_ID(orb_test_medium_queue_poll), &t)) == nullptr) { + if (ptopic == nullptr) { _thread_should_exit = true; return test_fail("advertise failed: %d", errno); } @@ -981,9 +981,9 @@ int uORBTest::UnitTest::test_queue_poll_notify() test_note("Testing orb queuing (poll & notify)"); orb_test_medium_s t{}; - int sfd = -1; + int sfd = orb_subscribe(ORB_ID(orb_test_medium_queue_poll)); - if ((sfd = orb_subscribe(ORB_ID(orb_test_medium_queue_poll))) < 0) { + if (sfd < 0) { return test_fail("subscribe failed: %d", errno); } diff --git a/platforms/posix/src/px4/common/SerialImpl.cpp b/platforms/posix/src/px4/common/SerialImpl.cpp index 4859832829..a2e11c4100 100644 --- a/platforms/posix/src/px4/common/SerialImpl.cpp +++ b/platforms/posix/src/px4/common/SerialImpl.cpp @@ -128,10 +128,10 @@ bool SerialImpl::configure() struct termios uart_config; - int termios_state; + int termios_state = tcgetattr(_serial_fd, &uart_config); /* fill the struct for the new configuration */ - if ((termios_state = tcgetattr(_serial_fd, &uart_config)) < 0) { + if (termios_state < 0) { PX4_ERR("ERR: %d (tcgetattr)", termios_state); return false; } @@ -199,17 +199,23 @@ bool SerialImpl::configure() } /* set baud rate */ - if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) { + termios_state = cfsetispeed(&uart_config, speed); + + if (termios_state < 0) { PX4_ERR("ERR: %d (cfsetispeed)", termios_state); return false; } - if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) { + termios_state = cfsetospeed(&uart_config, speed); + + if (termios_state < 0) { PX4_ERR("ERR: %d (cfsetospeed)", termios_state); return false; } - if ((termios_state = tcsetattr(_serial_fd, TCSANOW, &uart_config)) < 0) { + termios_state = tcsetattr(_serial_fd, TCSANOW, &uart_config); + + if (termios_state < 0) { PX4_ERR("ERR: %d (tcsetattr)", termios_state); return false; } diff --git a/platforms/posix/src/px4/common/px4_daemon/pxh.cpp b/platforms/posix/src/px4/common/px4_daemon/pxh.cpp index 262f1ae2c0..609356484f 100644 --- a/platforms/posix/src/px4/common/px4_daemon/pxh.cpp +++ b/platforms/posix/src/px4/common/px4_daemon/pxh.cpp @@ -209,9 +209,9 @@ void Pxh::run_remote_pxh(int remote_in_fd, int remote_out_fd) if (fds[0].revents & POLLIN) { uint8_t buffer[512]; - size_t len; + size_t len = read(pipe_stderr, buffer, sizeof(buffer)); - if ((len = read(pipe_stderr, buffer, sizeof(buffer))) <= 0) { + if (len <= 0) { break; //EOF or ERROR } @@ -233,9 +233,9 @@ void Pxh::run_remote_pxh(int remote_in_fd, int remote_out_fd) if (fds[1].revents & POLLIN) { uint8_t buffer[512]; - size_t len; + size_t len = read(pipe_stdout, buffer, sizeof(buffer)); - if ((len = read(pipe_stdout, buffer, sizeof(buffer))) <= 0) { + if (len <= 0) { break; //EOF or ERROR } diff --git a/platforms/posix/src/px4/common/px4_daemon/server.cpp b/platforms/posix/src/px4/common/px4_daemon/server.cpp index c26b364457..95b8116be4 100644 --- a/platforms/posix/src/px4/common/px4_daemon/server.cpp +++ b/platforms/posix/src/px4/common/px4_daemon/server.cpp @@ -269,9 +269,9 @@ void cmd.pop_back(); // We register thread specific data. This is used for PX4_INFO (etc.) log calls. - CmdThreadSpecificData *thread_data_ptr; + CmdThreadSpecificData *thread_data_ptr = static_cast(pthread_getspecific(_instance->_key)); - if ((thread_data_ptr = (CmdThreadSpecificData *)pthread_getspecific(_instance->_key)) == nullptr) { + if (thread_data_ptr == nullptr) { thread_data_ptr = new CmdThreadSpecificData; thread_data_ptr->thread_stdout = out; thread_data_ptr->is_atty = isatty; diff --git a/platforms/posix/src/px4/common/px4_daemon/server_io.cpp b/platforms/posix/src/px4/common/px4_daemon/server_io.cpp index d06aa1922f..7deb93b4b1 100644 --- a/platforms/posix/src/px4/common/px4_daemon/server_io.cpp +++ b/platforms/posix/src/px4/common/px4_daemon/server_io.cpp @@ -60,20 +60,20 @@ using namespace px4_daemon; FILE *get_stdout(bool *isatty_) { - Server::CmdThreadSpecificData *thread_data_ptr; - - // If we are not in a thread that has been started by a client, we don't - // have any thread specific data set and we won't have a pipe to write - // stdout to. - if (!Server::is_running() || - (thread_data_ptr = (Server::CmdThreadSpecificData *)pthread_getspecific( - Server::get_pthread_key())) == nullptr) { + // If the server is not running, we are not in a thread that has been started + if (!Server::is_running()) { if (isatty_) { *isatty_ = isatty(1); } return stdout; } - if (thread_data_ptr->thread_stdout == nullptr) { + Server::CmdThreadSpecificData *thread_data_ptr = static_cast(pthread_getspecific( + Server::get_pthread_key())); + + // If we are not in a thread that has been started by a client, we don't + // have any thread specific data set and we won't have a pipe to write + // stdout to. + if (thread_data_ptr == nullptr || thread_data_ptr->thread_stdout == nullptr) { if (isatty_) { *isatty_ = isatty(1); } return stdout; diff --git a/src/drivers/osd/msp_osd/MspV1.cpp b/src/drivers/osd/msp_osd/MspV1.cpp index 1b5371302f..24165ce9e6 100644 --- a/src/drivers/osd/msp_osd/MspV1.cpp +++ b/src/drivers/osd/msp_osd/MspV1.cpp @@ -170,7 +170,9 @@ int MspV1::Receive(uint8_t *payload, uint8_t *message_id) } while (bytes_available > 4) { - if ((ret = read(_fd, header, 1)) != 1) { + ret = read(_fd, header, 1); + + if (ret != 1) { return ret; } @@ -186,7 +188,9 @@ int MspV1::Receive(uint8_t *payload, uint8_t *message_id) return -EWOULDBLOCK; } - if ((ret = read(_fd, &header[1], 4)) != 4) { + ret = read(_fd, &header[1], 4); + + if (ret != 4) { return ret; } @@ -198,7 +202,9 @@ int MspV1::Receive(uint8_t *payload, uint8_t *message_id) payload_size = header[3]; *message_id = header[4]; - if ((ret = read(_fd, payload, payload_size + MSP_CRC_SIZE)) != payload_size + MSP_CRC_SIZE) { + ret = read(_fd, payload, payload_size + MSP_CRC_SIZE); + + if (ret != payload_size + MSP_CRC_SIZE) { if (ret != -EWOULDBLOCK) { has_header = false; } diff --git a/src/lib/led/led.cpp b/src/lib/led/led.cpp index 6a96d49960..062c20cd5a 100644 --- a/src/lib/led/led.cpp +++ b/src/lib/led/led.cpp @@ -161,7 +161,9 @@ int LedController::update(LedControlData &control_data) if (current_blink_duration > 0) { ++num_blinking_leds; - if ((_states[i].current_blinking_time += blink_delta_t) > current_blink_duration) { + _states[i].current_blinking_time += blink_delta_t; + + if (_states[i].current_blinking_time > current_blink_duration) { _states[i].current_blinking_time -= current_blink_duration; if (cur_data.blink_times_left == 246) { diff --git a/src/modules/gimbal/input_mavlink.cpp b/src/modules/gimbal/input_mavlink.cpp index 1203d25935..7091a7bc89 100644 --- a/src/modules/gimbal/input_mavlink.cpp +++ b/src/modules/gimbal/input_mavlink.cpp @@ -182,7 +182,9 @@ InputMavlinkCmdMount::~InputMavlinkCmdMount() int InputMavlinkCmdMount::initialize() { - if ((_vehicle_command_sub = orb_subscribe(ORB_ID(vehicle_command))) < 0) { + _vehicle_command_sub = orb_subscribe(ORB_ID(vehicle_command)); + + if (_vehicle_command_sub < 0) { return -errno; } @@ -438,11 +440,15 @@ int InputMavlinkGimbalV2::initialize() return -errno; } - if ((_vehicle_command_sub = orb_subscribe(ORB_ID(vehicle_command))) < 0) { + _vehicle_command_sub = orb_subscribe(ORB_ID(vehicle_command)); + + if (_vehicle_command_sub < 0) { return -errno; } - if ((_gimbal_manager_set_manual_control_sub = orb_subscribe(ORB_ID(gimbal_manager_set_manual_control))) < 0) { + _gimbal_manager_set_manual_control_sub = orb_subscribe(ORB_ID(gimbal_manager_set_manual_control)); + + if (_gimbal_manager_set_manual_control_sub < 0) { return -errno; } diff --git a/src/modules/simulation/simulator_mavlink/SimulatorMavlink.cpp b/src/modules/simulation/simulator_mavlink/SimulatorMavlink.cpp index dec6a60b7e..c579a9ba4b 100644 --- a/src/modules/simulation/simulator_mavlink/SimulatorMavlink.cpp +++ b/src/modules/simulation/simulator_mavlink/SimulatorMavlink.cpp @@ -1120,7 +1120,9 @@ void SimulatorMavlink::run() if (_ip == InternetProtocol::UDP) { - if ((_fd = socket(AF_INET, SOCK_DGRAM, 0)) < 0) { + _fd = socket(AF_INET, SOCK_DGRAM, 0); + + if (_fd < 0) { PX4_ERR("Creating UDP socket failed: %s", strerror(errno)); return; } @@ -1153,7 +1155,9 @@ void SimulatorMavlink::run() PX4_INFO("Waiting for simulator to accept connection on TCP port %u", _port); while (true) { - if ((_fd = socket(AF_INET, SOCK_STREAM, 0)) < 0) { + _fd = socket(AF_INET, SOCK_STREAM, 0); + + if (_fd < 0) { PX4_ERR("Creating TCP socket failed: %s", strerror(errno)); return; } diff --git a/src/modules/uxrce_dds_client/uxrce_dds_client.cpp b/src/modules/uxrce_dds_client/uxrce_dds_client.cpp index 084765a8ec..b773bc0e5e 100644 --- a/src/modules/uxrce_dds_client/uxrce_dds_client.cpp +++ b/src/modules/uxrce_dds_client/uxrce_dds_client.cpp @@ -851,17 +851,23 @@ bool UxrceddsClient::setBaudrate(int fd, unsigned baud) } /* set baud rate */ - if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) { + termios_state = cfsetispeed(&uart_config, speed); + + if (termios_state < 0) { PX4_ERR("ERR: %d (cfsetispeed)", termios_state); return false; } - if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) { + termios_state = cfsetospeed(&uart_config, speed); + + if (termios_state < 0) { PX4_ERR("ERR: %d (cfsetospeed)", termios_state); return false; } - if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) { + termios_state = tcsetattr(fd, TCSANOW, &uart_config); + + if (termios_state < 0) { PX4_ERR("ERR: %d (tcsetattr)", termios_state); return false; }