CI: enable clang-tidy bugprone-incorrect-roundings (#26574)

switched to lroundf and included cmath in all



removed std namespace - quick tested

Signed-off-by: kuralme <kuralme@protonmail.com>
This commit is contained in:
Ege Kural
2026-02-24 17:16:33 -05:00
committed by GitHub
parent 4a0e257fc9
commit a5c67b90a9
16 changed files with 44 additions and 36 deletions
-1
View File
@@ -151,7 +151,6 @@ Checks: '*,
-readability-make-member-function-const,
-bugprone-assignment-in-if-condition,
-bugprone-implicit-widening-of-multiplication-result,
-bugprone-incorrect-roundings,
-bugprone-macro-parentheses,
-bugprone-multi-level-implicit-pointer-conversion,
-bugprone-signed-char-misuse,
@@ -40,6 +40,8 @@
#include "CollisionPrevention.hpp"
#include "ObstacleMath.hpp"
#include <px4_platform_common/events.h>
#include <math.h>
using namespace matrix;
@@ -329,7 +331,7 @@ CollisionPrevention::_enterData(int map_index, float sensor_range, float sensor_
//3. this sensor data is out of range, the last reading was as well and this is the sensor with longest range
//4. this sensor data is out of range, the last reading was valid and coming from the same sensor
uint16_t sensor_range_cm = static_cast<uint16_t>(100.0f * sensor_range + 0.5f); //convert to cm
uint16_t sensor_range_cm = static_cast<uint16_t>(lroundf(100.0f * sensor_range)); //convert to cm
if (sensor_reading < sensor_range) {
if ((_obstacle_map_body_frame.distances[map_index] < _data_maxranges[map_index]
@@ -406,13 +408,13 @@ CollisionPrevention::_addDistanceSensorData(distance_sensor_s &distance_sensor,
ObstacleMath::project_distance_on_horizontal_plane(distance_reading, sensor_yaw_body_rad, vehicle_attitude);
}
uint16_t sensor_range = static_cast<uint16_t>(100.0f * distance_sensor.max_distance + 0.5f); // convert to cm
uint16_t sensor_range = static_cast<uint16_t>(lroundf(100.0f * distance_sensor.max_distance)); // convert to cm
for (int bin = lower_bound; bin <= upper_bound; ++bin) {
int wrapped_bin = ObstacleMath::wrap_bin(bin, BIN_COUNT);
if (_enterData(wrapped_bin, distance_sensor.max_distance, distance_reading)) {
_obstacle_map_body_frame.distances[wrapped_bin] = static_cast<uint16_t>(100.0f * distance_reading + 0.5f);
_obstacle_map_body_frame.distances[wrapped_bin] = static_cast<uint16_t>(lroundf(100.0f * distance_reading));
_data_timestamps[wrapped_bin] = _obstacle_map_body_frame.timestamp;
_data_maxranges[wrapped_bin] = sensor_range;
_data_fov[wrapped_bin] = 1;
@@ -35,6 +35,7 @@
#include "FunctionProviderBase.hpp"
#include <math.h>
#include <uORB/topics/vehicle_command.h>
/**
@@ -58,7 +59,7 @@ public:
while (_topic.update(&vehicle_command)) {
if (vehicle_command.command == vehicle_command_s::VEHICLE_CMD_DO_SET_ACTUATOR) {
int index = (int)(vehicle_command.param7 + 0.5f);
int index = static_cast<int>(lroundf(vehicle_command.param7));
if (index == 0) {
if (PX4_ISFINITE(vehicle_command.param1)) { _data[0] = vehicle_command.param1; }
+2 -2
View File
@@ -237,7 +237,7 @@ sbus1_output(int sbus_fd, uint16_t *values, uint16_t num_values)
* currently ignoring single bit channels. */
for (unsigned i = 0; (i < num_values) && (i < 16); ++i) {
value = (uint16_t)(((values[i] - SBUS_SCALE_OFFSET) / SBUS_SCALE_FACTOR) + .5f);
value = static_cast<uint16_t>(lround((values[i] - SBUS_SCALE_OFFSET) / SBUS_SCALE_FACTOR));
/*protect from out of bounds values and limit to 11 bits*/
if (value > 0x07ff) {
@@ -643,7 +643,7 @@ sbus_decode(uint64_t frame_time, uint8_t *frame, uint16_t *values, uint16_t *num
/* convert 0-2048 values to 1000-2000 ppm encoding in a not too sloppy fashion */
values[channel] = (uint16_t)(value * SBUS_SCALE_FACTOR + .5f) + SBUS_SCALE_OFFSET;
values[channel] = static_cast<uint16_t>(lround(value * SBUS_SCALE_FACTOR) + SBUS_SCALE_OFFSET);
}
/* decode switch channels if data fields are wide enough */
+5 -4
View File
@@ -41,6 +41,7 @@
#include <stdbool.h>
#include <stdio.h>
#include <cmath>
#include "st24.h"
#include "common_rc.h"
@@ -180,13 +181,13 @@ int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *lost_count, uint16_t *chan
channels[chan_index] = ((uint16_t)d->channel[i] << 4);
channels[chan_index] |= ((uint16_t)(0xF0 & d->channel[i + 1]) >> 4);
/* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
channels[chan_index] = (uint16_t)lroundf(channels[chan_index] * ST24_SCALE_FACTOR) + ST24_SCALE_OFFSET;
chan_index++;
channels[chan_index] = ((uint16_t)d->channel[i + 2]);
channels[chan_index] |= (((uint16_t)(0x0F & d->channel[i + 1])) << 8);
/* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
channels[chan_index] = (uint16_t)lroundf(channels[chan_index] * ST24_SCALE_FACTOR) + ST24_SCALE_OFFSET;
chan_index++;
}
}
@@ -209,13 +210,13 @@ int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *lost_count, uint16_t *chan
channels[chan_index] = ((uint16_t)d->channel[i] << 4);
channels[chan_index] |= ((uint16_t)(0xF0 & d->channel[i + 1]) >> 4);
/* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
channels[chan_index] = static_cast<uint16_t>(lroundf(channels[chan_index] * ST24_SCALE_FACTOR) + ST24_SCALE_OFFSET);
chan_index++;
channels[chan_index] = ((uint16_t)d->channel[i + 2]);
channels[chan_index] |= (((uint16_t)(0x0F & d->channel[i + 1])) << 8);
/* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
channels[chan_index] = static_cast<uint16_t>(lroundf(channels[chan_index] * ST24_SCALE_FACTOR) + ST24_SCALE_OFFSET);
chan_index++;
}
}
+3 -3
View File
@@ -981,7 +981,7 @@ Commander::handle_command(const vehicle_command_s &cmd)
break;
case vehicle_command_s::VEHICLE_CMD_SET_NAV_STATE: { // Used from ROS
uint8_t desired_nav_state = (uint8_t)(cmd.param1 + 0.5f);
uint8_t desired_nav_state = static_cast<uint8_t>(lroundf(cmd.param1));
if (_user_mode_intention.change(desired_nav_state, getSourceFromCommand(cmd))) {
cmd_result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
@@ -1676,7 +1676,7 @@ unsigned Commander::handleCommandActuatorTest(const vehicle_command_s &cmd)
actuator_test_s actuator_test{};
actuator_test.timestamp = hrt_absolute_time();
actuator_test.function = (int)(cmd.param5 + 0.5);
actuator_test.function = static_cast<int>(lroundf(cmd.param5));
if (actuator_test.function < 1000) {
const int first_motor_function = 1; // from MAVLink ACTUATOR_OUTPUT_FUNCTION
@@ -1701,7 +1701,7 @@ unsigned Commander::handleCommandActuatorTest(const vehicle_command_s &cmd)
actuator_test.value = cmd.param1;
actuator_test.action = actuator_test_s::ACTION_DO_CONTROL;
int timeout_ms = (int)(cmd.param2 * 1000.f + 0.5f);
int timeout_ms = static_cast<int>(lroundf(cmd.param2 * 1000.f));
if (timeout_ms <= 0) {
actuator_test.action = actuator_test_s::ACTION_RELEASE_CONTROL;
@@ -33,6 +33,7 @@
#include "FailureInjector.hpp"
#include <cmath>
#include <parameters/param.h>
#include <uORB/topics/actuator_motors.h>
@@ -53,15 +54,15 @@ void FailureInjector::update()
vehicle_command_s vehicle_command;
while (_vehicle_command_sub.update(&vehicle_command)) {
const int failure_unit = static_cast<int>(vehicle_command.param1 + 0.5f);
const int failure_type = static_cast<int>(vehicle_command.param2 + 0.5f);
const int failure_unit = static_cast<int>(lroundf(vehicle_command.param1));
const int failure_type = static_cast<int>(lroundf(vehicle_command.param2));
if (vehicle_command.command != vehicle_command_s::VEHICLE_CMD_INJECT_FAILURE
|| failure_unit != vehicle_command_s::FAILURE_UNIT_SYSTEM_MOTOR) {
continue;
}
const int instance = static_cast<int>(vehicle_command.param3 + 0.5f);
const int instance = static_cast<int>(lroundf(vehicle_command.param3));
bool supported = false;
for (int i = 0; i < esc_status_s::CONNECTED_ESC_MAX; i++) {
@@ -33,6 +33,7 @@
#include "FlightModeManager.hpp"
#include <cmath>
#include <lib/mathlib/mathlib.h>
#include <lib/matrix/matrix/math.hpp>
@@ -324,7 +325,7 @@ void FlightModeManager::handleCommand()
if (_current_task.task) {
// check for other commands not related to task switching
if ((command.command == vehicle_command_s::VEHICLE_CMD_DO_CHANGE_SPEED)
&& (static_cast<uint8_t>(command.param1 + .5f) == vehicle_command_s::SPEED_TYPE_GROUNDSPEED)
&& (static_cast<uint8_t>(lroundf(command.param1)) == vehicle_command_s::SPEED_TYPE_GROUNDSPEED)
&& (command.param2 > 0.f)) {
_current_task.task->overrideCruiseSpeed(command.param2);
}
@@ -90,7 +90,7 @@ bool FlightTaskOrbit::applyCommandParameters(const vehicle_command_s &command, b
// commanded heading behaviour
if (PX4_ISFINITE(command.param3)) {
if (static_cast<uint8_t>(command.param3 + .5f) == vehicle_command_s::ORBIT_YAW_BEHAVIOUR_UNCHANGED) {
if (static_cast<uint8_t>(lround(command.param3)) == vehicle_command_s::ORBIT_YAW_BEHAVIOUR_UNCHANGED) {
if (!_currently_orbiting) { // only change the yaw behaviour if we are not actively orbiting
_yaw_behaviour = _param_mc_orbit_yaw_mod.get();
}
@@ -33,6 +33,7 @@
#include "FixedWingModeManager.hpp"
#include <cmath>
#include <px4_platform_common/events.h>
#include <uORB/topics/longitudinal_control_configuration.h>
@@ -139,7 +140,7 @@ FixedWingModeManager::vehicle_command_poll()
} else if (vehicle_command.command == vehicle_command_s::VEHICLE_CMD_DO_CHANGE_SPEED) {
if ((static_cast<uint8_t>(vehicle_command.param1 + .5f) == vehicle_command_s::SPEED_TYPE_AIRSPEED)) {
if ((static_cast<uint8_t>(lroundf(vehicle_command.param1)) == vehicle_command_s::SPEED_TYPE_AIRSPEED)) {
if (vehicle_command.param2 > FLT_EPSILON) { // param2 is an equivalent airspeed setpoint
if (_control_mode_current == FW_POSCTRL_MODE_AUTO) {
_pos_sp_triplet.current.cruising_speed = vehicle_command.param2;
+6 -6
View File
@@ -323,9 +323,9 @@ InputMavlinkCmdMount::_process_command(ControlData &control_data, const vehicle_
// Stabilization params are ignored. Use MNT_DO_STAB param instead.
const int params[] = {
(int)((float) vehicle_command.param5 + 0.5f),
(int)((float) vehicle_command.param6 + 0.5f),
(int)(vehicle_command.param7 + 0.5f)
static_cast<int>(lroundf(vehicle_command.param5)),
static_cast<int>(lroundf(vehicle_command.param6)),
static_cast<int>(lroundf(vehicle_command.param7))
};
for (int i = 0; i < 3; ++i) {
@@ -779,9 +779,9 @@ InputMavlinkGimbalV2::_process_command(ControlData &control_data, const vehicle_
// Stabilization params are ignored. Use MNT_DO_STAB param instead.
const int params[] = {
(int)((float) vehicle_command.param5 + 0.5f),
(int)((float) vehicle_command.param6 + 0.5f),
(int)(vehicle_command.param7 + 0.5f)
static_cast<int>(lroundf(vehicle_command.param5)),
static_cast<int>(lroundf(vehicle_command.param6)),
static_cast<int>(lroundf(vehicle_command.param7))
};
for (int i = 0; i < 3; ++i) {
+2 -1
View File
@@ -43,6 +43,7 @@
#include <string.h>
#include <stdlib.h>
#include <time.h>
#include <math.h>
#include <uORB/uORBMessageFields.hpp>
#include <uORB/Publication.hpp>
@@ -1185,7 +1186,7 @@ void Logger::handle_vehicle_command_update()
if (command.command == vehicle_command_s::VEHICLE_CMD_LOGGING_START) {
if ((int)(command.param1 + 0.5f) != 0) {
if (static_cast<int>(lroundf(command.param1)) != 0) {
ack_vehicle_command(&command, vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED);
} else if (can_start_mavlink_log()) {
+1 -1
View File
@@ -1375,7 +1375,7 @@ bool MissionBase::haveCachedCameraModeItems()
bool MissionBase::cameraWasTriggering()
{
return (_last_camera_trigger_item.nav_cmd == NAV_CMD_DO_TRIGGER_CONTROL
&& (int)(_last_camera_trigger_item.params[0] + 0.5f) == 1) ||
&& static_cast<int>(lround(_last_camera_trigger_item.params[0])) == 1) ||
(_last_camera_trigger_item.nav_cmd == NAV_CMD_IMAGE_START_CAPTURE) ||
(_last_camera_trigger_item.nav_cmd == NAV_CMD_DO_SET_CAM_TRIGG_DIST
&& _last_camera_trigger_item.params[0] > FLT_EPSILON);
@@ -32,6 +32,7 @@
****************************************************************************/
#include "BatterySimulator.hpp"
#include <cmath>
ModuleBase::Descriptor BatterySimulator::desc{task_spawn, custom_command, print_usage};
@@ -130,9 +131,9 @@ void BatterySimulator::updateCommands()
bool handled = false;
bool supported = false;
const int failure_unit = static_cast<int>(vehicle_command.param1 + 0.5f);
const int failure_type = static_cast<int>(vehicle_command.param2 + 0.5f);
const int instance = static_cast<int>(vehicle_command.param3 + 0.5f);
const int failure_unit = static_cast<int>(lroundf(vehicle_command.param1));
const int failure_type = static_cast<int>(lroundf(vehicle_command.param2));
const int instance = static_cast<int>(lroundf(vehicle_command.param3));
if (failure_unit == vehicle_command_s::FAILURE_UNIT_SYSTEM_BATTERY) {
@@ -1255,9 +1255,9 @@ void SimulatorMavlink::check_failure_injections()
bool handled = false;
bool supported = false;
const int failure_unit = static_cast<int>(vehicle_command.param1 + 0.5f);
const int failure_type = static_cast<int>(vehicle_command.param2 + 0.5f);
const int instance = static_cast<int>(vehicle_command.param3 + 0.5f);
const int failure_unit = static_cast<int>(std::lround(vehicle_command.param1));
const int failure_type = static_cast<int>(std::lround(vehicle_command.param2));
const int instance = static_cast<int>(std::lround(vehicle_command.param3));
if (failure_unit == vehicle_command_s::FAILURE_UNIT_SENSOR_GPS) {
handled = true;
@@ -149,7 +149,7 @@ void VtolAttitudeControl::vehicle_cmd_poll()
uint8_t result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
const int transition_command_param1 = int(vehicle_command.param1 + 0.5f);
const int transition_command_param1 = static_cast<int>(lround(vehicle_command.param1));
// deny transition from MC to FW in Takeoff, Land, RTL and Orbit
if (transition_command_param1 == vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW &&
@@ -162,7 +162,7 @@ void VtolAttitudeControl::vehicle_cmd_poll()
} else {
_transition_command = transition_command_param1;
_immediate_transition = (PX4_ISFINITE(vehicle_command.param2)) ? int(vehicle_command.param2 + 0.5f) : false;
_immediate_transition = (PX4_ISFINITE(vehicle_command.param2)) ? static_cast<int>(lround(vehicle_command.param2)) : false;
// reset fixed_wing_system_failure flag when a new transition to FW is triggered
if (_transition_command == vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW) {