forked from Archive/PX4-Autopilot
clang-tidy: enable readability-delete-null-pointer and fix
This commit is contained in:
parent
4192414576
commit
744f06cc8f
|
@ -87,7 +87,6 @@ Checks: '*,
|
|||
-readability-avoid-const-params-in-decls,
|
||||
-readability-braces-around-statements,
|
||||
-readability-container-size-empty,
|
||||
-readability-delete-null-pointer,
|
||||
-readability-else-after-return,
|
||||
-readability-function-size,
|
||||
-readability-implicit-bool-cast,
|
||||
|
|
|
@ -53,9 +53,7 @@ RingBuffer::RingBuffer(unsigned num_items, size_t item_size) :
|
|||
|
||||
RingBuffer::~RingBuffer()
|
||||
{
|
||||
if (_buf != nullptr) {
|
||||
delete[] _buf;
|
||||
}
|
||||
delete[] _buf;
|
||||
}
|
||||
|
||||
unsigned
|
||||
|
|
|
@ -182,9 +182,7 @@ AirspeedModule::~AirspeedModule()
|
|||
|
||||
perf_free(_perf_elapsed);
|
||||
|
||||
if (_airspeed_validator != nullptr) {
|
||||
delete[] _airspeed_validator;
|
||||
}
|
||||
delete[] _airspeed_validator;
|
||||
}
|
||||
|
||||
int
|
||||
|
|
|
@ -81,13 +81,8 @@ SendEvent::SendEvent() : ModuleParams(nullptr)
|
|||
|
||||
SendEvent::~SendEvent()
|
||||
{
|
||||
if (_status_display != nullptr) {
|
||||
delete _status_display;
|
||||
}
|
||||
|
||||
if (_rc_loss_alarm != nullptr) {
|
||||
delete _rc_loss_alarm;
|
||||
}
|
||||
delete _status_display;
|
||||
delete _rc_loss_alarm;
|
||||
}
|
||||
|
||||
int SendEvent::start()
|
||||
|
|
|
@ -57,13 +57,8 @@ MavlinkFTP::MavlinkFTP(Mavlink *mavlink) :
|
|||
|
||||
MavlinkFTP::~MavlinkFTP()
|
||||
{
|
||||
if (_work_buffer1) {
|
||||
delete[] _work_buffer1;
|
||||
}
|
||||
|
||||
if (_work_buffer2) {
|
||||
delete[] _work_buffer2;
|
||||
}
|
||||
delete[] _work_buffer1;
|
||||
delete[] _work_buffer2;
|
||||
}
|
||||
|
||||
unsigned
|
||||
|
|
|
@ -297,9 +297,7 @@ MulticopterPositionControl::MulticopterPositionControl() :
|
|||
|
||||
MulticopterPositionControl::~MulticopterPositionControl()
|
||||
{
|
||||
if (_wv_controller != nullptr) {
|
||||
delete _wv_controller;
|
||||
}
|
||||
delete _wv_controller;
|
||||
|
||||
perf_free(_cycle_perf);
|
||||
}
|
||||
|
|
|
@ -66,9 +66,7 @@ uORB::DeviceNode::DeviceNode(const struct orb_metadata *meta, const uint8_t inst
|
|||
|
||||
uORB::DeviceNode::~DeviceNode()
|
||||
{
|
||||
if (_data != nullptr) {
|
||||
delete[] _data;
|
||||
}
|
||||
delete[] _data;
|
||||
|
||||
CDev::unregister_driver_and_memory();
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue