mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
CI: enable clang-tidy cppcoreguidelines-virtual-class-destructor (#26559)
* CI: enable clang-tidy cppcoreguidelines-virtual-class-destructor Signed-off-by: kuralme <kuralme@protonmail.com> * format fix Signed-off-by: kuralme <kuralme@protonmail.com> --------- Signed-off-by: kuralme <kuralme@protonmail.com>
This commit is contained in:
parent
a4f9786c3d
commit
207456fd35
@ -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,
|
||||
|
||||
@ -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;
|
||||
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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<const DeviceNode *>(node_handle)->updates_available(last_generation) : 0; }
|
||||
@ -504,7 +506,6 @@ private: // data members
|
||||
|
||||
private: //class methods
|
||||
Manager();
|
||||
virtual ~Manager();
|
||||
|
||||
#ifdef CONFIG_ORB_COMMUNICATOR
|
||||
/**
|
||||
|
||||
@ -90,7 +90,7 @@ typedef enum : int32_t {
|
||||
|
||||
#define commandParamToInt(n) static_cast<int>(n >= 0 ? n + 0.5f : n - 0.5f)
|
||||
|
||||
class CameraTrigger : public px4::ScheduledWorkItem
|
||||
class CameraTrigger final : public px4::ScheduledWorkItem
|
||||
{
|
||||
public:
|
||||
/**
|
||||
|
||||
@ -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};
|
||||
|
||||
@ -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
|
||||
|
||||
@ -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();
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user