From d5ddc9135d5447e27df291829ea0e8ec50905abf Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Tue, 17 Feb 2026 14:09:43 -0900 Subject: [PATCH] clang-tidy: fix issues (#26498) --- Makefile | 2 +- src/lib/mathlib/math/filter/LowPassFilter2p.hpp | 2 +- src/lib/rate_control/rate_control.cpp | 2 +- .../MecanumActControl/MecanumActControl.cpp | 2 +- src/modules/sensors/Integrator.hpp | 2 +- .../gz_plugins/buoyancy/BuoyancySystem.cpp | 2 +- .../SpacecraftThrusterModel.cpp | 15 ++++++++++----- 7 files changed, 16 insertions(+), 11 deletions(-) diff --git a/Makefile b/Makefile index df7c54f412..3cbe67acc9 100644 --- a/Makefile +++ b/Makefile @@ -505,7 +505,7 @@ px4_sitl_default-clang: # To add manual exclusions, append to CLANG_TIDY_EXCLUDE_EXTRA below. # Submodules are automatically excluded - no action needed when adding new ones. CLANG_TIDY_SUBMODULES := $(shell git config --file .gitmodules --get-regexp path | awk '{print $$2}' | tr '\n' '|' | sed 's/|$$//') -CLANG_TIDY_EXCLUDE_EXTRA := src/systemcmds/tests|src/examples|src/modules/gyro_fft/CMSIS_5|src/lib/drivers/smbus|src/drivers/gpio|src/modules/commander/failsafe/emscripten|failsafe_test\.dir +CLANG_TIDY_EXCLUDE_EXTRA := src/systemcmds/tests|src/examples|src/modules/gyro_fft/CMSIS_5|src/lib/drivers/smbus|src/drivers/gpio|src/modules/commander/failsafe/emscripten|failsafe_test\.dir|\.pb\.cc CLANG_TIDY_EXCLUDE := $(CLANG_TIDY_SUBMODULES)|$(CLANG_TIDY_EXCLUDE_EXTRA) clang-tidy: px4_sitl_default-clang diff --git a/src/lib/mathlib/math/filter/LowPassFilter2p.hpp b/src/lib/mathlib/math/filter/LowPassFilter2p.hpp index 159d2bcbfb..9999be13d4 100644 --- a/src/lib/mathlib/math/filter/LowPassFilter2p.hpp +++ b/src/lib/mathlib/math/filter/LowPassFilter2p.hpp @@ -100,7 +100,7 @@ public: // Direct Form II implementation T delay_element_0{sample - _delay_element_1 *_a1 - _delay_element_2 * _a2}; - const T output{delay_element_0 *_b0 + _delay_element_1 *_b1 + _delay_element_2 * _b2}; + T output{delay_element_0 *_b0 + _delay_element_1 *_b1 + _delay_element_2 * _b2}; _delay_element_2 = _delay_element_1; _delay_element_1 = delay_element_0; diff --git a/src/lib/rate_control/rate_control.cpp b/src/lib/rate_control/rate_control.cpp index 7d6367a886..ddfb796991 100644 --- a/src/lib/rate_control/rate_control.cpp +++ b/src/lib/rate_control/rate_control.cpp @@ -75,7 +75,7 @@ Vector3f RateControl::update(const Vector3f &rate, const Vector3f &rate_sp, cons Vector3f rate_error = rate_sp - rate; // PID control with feed forward - const Vector3f torque = _gain_p.emult(rate_error) + _rate_int - _gain_d.emult(angular_accel) + _gain_ff.emult(rate_sp); + Vector3f torque = _gain_p.emult(rate_error) + _rate_int - _gain_d.emult(angular_accel) + _gain_ff.emult(rate_sp); // update integral only if we are not landed if (!landed) { diff --git a/src/modules/rover_mecanum/MecanumActControl/MecanumActControl.cpp b/src/modules/rover_mecanum/MecanumActControl/MecanumActControl.cpp index 203aadc365..2f3280e853 100644 --- a/src/modules/rover_mecanum/MecanumActControl/MecanumActControl.cpp +++ b/src/modules/rover_mecanum/MecanumActControl/MecanumActControl.cpp @@ -111,7 +111,7 @@ Vector4f MecanumActControl::computeInverseKinematics(float throttle_body_x, floa const Matrix input(input_data); const float m_data[12] = {1.f, -1.f, -1.f, 1.f, 1.f, 1.f, 1.f, 1.f, -1.f, 1.f, -1.f, 1.f}; const Matrix m(m_data); - const Vector4f motor_commands = m * input; + Vector4f motor_commands = m * input; return motor_commands; } diff --git a/src/modules/sensors/Integrator.hpp b/src/modules/sensors/Integrator.hpp index 7895bd0c5b..74a54c7c3a 100644 --- a/src/modules/sensors/Integrator.hpp +++ b/src/modules/sensors/Integrator.hpp @@ -132,7 +132,7 @@ protected: // Use trapezoidal integration to calculate the delta integral _integrated_samples++; _integral_dt += dt; - const matrix::Vector3f delta_alpha{(val + _last_val) *dt * 0.5f}; + matrix::Vector3f delta_alpha{(val + _last_val) *dt * 0.5f}; _last_val = val; return delta_alpha; diff --git a/src/modules/simulation/gz_plugins/buoyancy/BuoyancySystem.cpp b/src/modules/simulation/gz_plugins/buoyancy/BuoyancySystem.cpp index d9fd3c200e..a16ff5eafb 100644 --- a/src/modules/simulation/gz_plugins/buoyancy/BuoyancySystem.cpp +++ b/src/modules/simulation/gz_plugins/buoyancy/BuoyancySystem.cpp @@ -277,7 +277,7 @@ void BuoyancyPrivate::CheckForNewEntities(const EntityComponentManager &_ecm) [&](const Entity & _entity, const components::Link *, const components::Inertial *) -> bool { - if (this->basicBuoyancy == true) return true; + if (this->basicBuoyancy == true) { return true; } // Skip if the entity already has a volume and center of volume if (_ecm.EntityHasComponentType(_entity, components::CenterOfVolume().TypeId()) && diff --git a/src/modules/simulation/gz_plugins/spacecraft_thruster/SpacecraftThrusterModel.cpp b/src/modules/simulation/gz_plugins/spacecraft_thruster/SpacecraftThrusterModel.cpp index 846d794de4..f4f9994b6f 100644 --- a/src/modules/simulation/gz_plugins/spacecraft_thruster/SpacecraftThrusterModel.cpp +++ b/src/modules/simulation/gz_plugins/spacecraft_thruster/SpacecraftThrusterModel.cpp @@ -334,16 +334,18 @@ void SpacecraftThrusterModelPrivate::UpdateForcesAndMoments( // d: cycle period double targetDutyCycle = normalizedInput * (1.0 / this->dutyCycleFrequency); - if (this->actuatorNumber == 0) + if (this->actuatorNumber == 0) { gzdbg << this->actuatorNumber << ": target duty cycle: " << targetDutyCycle << std::endl; + } // Calculate cycle start time if (this->samplingTime >= 1.0 / this->dutyCycleFrequency) { - if (this->actuatorNumber == 0) + if (this->actuatorNumber == 0) { gzdbg << this->actuatorNumber << ": Cycle completed. Resetting cycle start time." << std::endl; + } this->cycleStartTime = this->simTime; } @@ -351,22 +353,24 @@ void SpacecraftThrusterModelPrivate::UpdateForcesAndMoments( // Calculate sampling time instant within the cycle this->samplingTime = this->simTime - this->cycleStartTime; - if (this->actuatorNumber == 0) + if (this->actuatorNumber == 0) { gzdbg << this->actuatorNumber << ": PWM Period: " << 1.0 / this->dutyCycleFrequency << " Cycle Start time: " << this->cycleStartTime << " Sampling time: " << this->samplingTime << std::endl; + } // Apply force if the sampling time is less than the target ON duty cycle double force = this->samplingTime <= targetDutyCycle ? this->maxThrust : 0.0; if (targetDutyCycle < 1e-9) { force = 0.0; } - if (this->actuatorNumber == 0) + if (this->actuatorNumber == 0) { gzdbg << this->actuatorNumber << ": Force: " << force << " Sampling time: " << this->samplingTime << " Tgt duty cycle: " << targetDutyCycle << std::endl; + } // Apply force to the link Link link(this->linkEntity); @@ -374,10 +378,11 @@ void SpacecraftThrusterModelPrivate::UpdateForcesAndMoments( link.AddWorldForce(_ecm, worldPose->Rot().RotateVector(math::Vector3d(0, 0, force))); - if (this->actuatorNumber == 0) + if (this->actuatorNumber == 0) { gzdbg << this->actuatorNumber << ": Input Value: " << msg->velocity(this->actuatorNumber) << " Calc. Force: " << force << std::endl; + } } GZ_ADD_PLUGIN(SpacecraftThrusterModel,