From 207456fd35bd650a0a4cd739e8f9dd12349a7d6a Mon Sep 17 00:00:00 2001 From: Ege Kural Date: Mon, 23 Feb 2026 23:21:20 -0500 Subject: [PATCH] CI: enable clang-tidy cppcoreguidelines-virtual-class-destructor (#26559) * CI: enable clang-tidy cppcoreguidelines-virtual-class-destructor Signed-off-by: kuralme * format fix Signed-off-by: kuralme --------- Signed-off-by: kuralme --- .clang-tidy | 1 - .../px4_work_queue/ScheduledWorkItem.hpp | 3 ++- .../px4_work_queue/WorkItem.hpp | 3 ++- platforms/common/uORB/uORBManager.hpp | 3 ++- src/drivers/camera_trigger/camera_trigger.cpp | 2 +- src/modules/commander/ModeManagement.hpp | 4 ++-- src/modules/commander/UserModeIntention.hpp | 17 +++++++++++++++++ .../simulator_mavlink/SimulatorMavlink.hpp | 7 +++---- 8 files changed, 29 insertions(+), 11 deletions(-) diff --git a/.clang-tidy b/.clang-tidy index 10dc90d5fc..cc6c3dcf2c 100644 --- a/.clang-tidy +++ b/.clang-tidy @@ -147,7 +147,6 @@ Checks: '*, -readability-avoid-nested-conditional-operator, -cppcoreguidelines-prefer-member-initializer, -cppcoreguidelines-explicit-virtual-functions, - -cppcoreguidelines-virtual-class-destructor, -readability-convert-member-functions-to-static, -readability-make-member-function-const, -bugprone-assignment-in-if-condition, diff --git a/platforms/common/include/px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp b/platforms/common/include/px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp index 20f5ebf29b..c4c84debe2 100644 --- a/platforms/common/include/px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp +++ b/platforms/common/include/px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp @@ -46,6 +46,8 @@ public: bool Scheduled() { return !hrt_called(&_call); } + virtual ~ScheduledWorkItem(); + /** * Schedule next run with a delay in microseconds. * @@ -76,7 +78,6 @@ public: protected: ScheduledWorkItem(const char *name, const wq_config_t &config) : WorkItem(name, config) {} - virtual ~ScheduledWorkItem() override; virtual void print_run_status() override; diff --git a/platforms/common/include/px4_platform_common/px4_work_queue/WorkItem.hpp b/platforms/common/include/px4_platform_common/px4_work_queue/WorkItem.hpp index 5c1f82061d..a2eddbef58 100644 --- a/platforms/common/include/px4_platform_common/px4_work_queue/WorkItem.hpp +++ b/platforms/common/include/px4_platform_common/px4_work_queue/WorkItem.hpp @@ -83,13 +83,14 @@ public: const char *ItemName() const { return _item_name; } + virtual ~WorkItem(); + protected: explicit WorkItem(const char *name, const wq_config_t &config); explicit WorkItem(const char *name, const WorkItem &work_item); - virtual ~WorkItem(); /** * Remove work item from the runnable queue, if it's there diff --git a/platforms/common/uORB/uORBManager.hpp b/platforms/common/uORB/uORBManager.hpp index d5202b9236..9b4ed5f089 100644 --- a/platforms/common/uORB/uORBManager.hpp +++ b/platforms/common/uORB/uORBManager.hpp @@ -448,6 +448,8 @@ public: static uint8_t orb_get_instance(const void *node_handle); + virtual ~Manager(); + #if defined(CONFIG_BUILD_FLAT) /* These are optimized by inlining in NuttX Flat build */ static unsigned updates_available(const void *node_handle, unsigned last_generation) { return is_advertised(node_handle) ? static_cast(node_handle)->updates_available(last_generation) : 0; } @@ -504,7 +506,6 @@ private: // data members private: //class methods Manager(); - virtual ~Manager(); #ifdef CONFIG_ORB_COMMUNICATOR /** diff --git a/src/drivers/camera_trigger/camera_trigger.cpp b/src/drivers/camera_trigger/camera_trigger.cpp index 33d89f3c01..2a1fbfc443 100644 --- a/src/drivers/camera_trigger/camera_trigger.cpp +++ b/src/drivers/camera_trigger/camera_trigger.cpp @@ -90,7 +90,7 @@ typedef enum : int32_t { #define commandParamToInt(n) static_cast(n >= 0 ? n + 0.5f : n - 0.5f) -class CameraTrigger : public px4::ScheduledWorkItem +class CameraTrigger final : public px4::ScheduledWorkItem { public: /** diff --git a/src/modules/commander/ModeManagement.hpp b/src/modules/commander/ModeManagement.hpp index e65b340fa1..e55e5c2f3d 100644 --- a/src/modules/commander/ModeManagement.hpp +++ b/src/modules/commander/ModeManagement.hpp @@ -130,7 +130,7 @@ class ModeManagement : public ModeChangeHandler { public: ModeManagement(ExternalChecks &external_checks); - ~ModeManagement() = default; + virtual ~ModeManagement() = default; struct UpdateRequest { bool change_user_intended_nav_state{false}; @@ -202,7 +202,7 @@ class ModeManagement : public ModeChangeHandler { public: ModeManagement() = default; - ~ModeManagement() = default; + virtual ~ModeManagement() = default; struct UpdateRequest { bool change_user_intended_nav_state{false}; diff --git a/src/modules/commander/UserModeIntention.hpp b/src/modules/commander/UserModeIntention.hpp index e37bf467b1..fd563e5d49 100644 --- a/src/modules/commander/UserModeIntention.hpp +++ b/src/modules/commander/UserModeIntention.hpp @@ -44,6 +44,17 @@ enum class ModeChangeSource { class ModeChangeHandler { public: + ModeChangeHandler() = default; + virtual ~ModeChangeHandler() = default; + + /** + * Explicitly disable copying/moving + */ + ModeChangeHandler(const ModeChangeHandler &) = delete; + ModeChangeHandler &operator=(const ModeChangeHandler &) = delete; + ModeChangeHandler(ModeChangeHandler &&) = delete; + ModeChangeHandler &operator=(ModeChangeHandler &&) = delete; + virtual void onUserIntendedNavStateChange(ModeChangeSource source, uint8_t user_intended_nav_state) = 0; /** @@ -64,6 +75,12 @@ public: const HealthAndArmingChecks &health_and_arming_checks, ModeChangeHandler *handler); ~UserModeIntention() = default; + /** + * Explicitly disable copying/moving + */ + UserModeIntention(const UserModeIntention &) = delete; + UserModeIntention &operator=(const UserModeIntention &) = delete; + /** * Change the user intended mode * @param user_intended_nav_state new mode diff --git a/src/modules/simulation/simulator_mavlink/SimulatorMavlink.hpp b/src/modules/simulation/simulator_mavlink/SimulatorMavlink.hpp index bf8c07bbf4..5c1e9481e8 100644 --- a/src/modules/simulation/simulator_mavlink/SimulatorMavlink.hpp +++ b/src/modules/simulation/simulator_mavlink/SimulatorMavlink.hpp @@ -134,10 +134,7 @@ public: bool has_initialized() { return _has_initialized.load(); } #endif -private: - SimulatorMavlink(); - - ~SimulatorMavlink() + virtual ~SimulatorMavlink() { // free perf counters perf_free(_perf_sim_delay); @@ -156,6 +153,8 @@ private: _instance = nullptr; } +private: + SimulatorMavlink(); void check_failure_injections();