Unverified Commit c304d6f4 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8278 from patrickelectric/null_ptr_check

Remove unnecessary pointer check before delete 
parents 1d5c87d7 0535ac25
...@@ -48,21 +48,16 @@ AirspaceManager::AirspaceManager(QGCApplication* app, QGCToolbox* toolbox) ...@@ -48,21 +48,16 @@ AirspaceManager::AirspaceManager(QGCApplication* app, QGCToolbox* toolbox)
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
AirspaceManager::~AirspaceManager() AirspaceManager::~AirspaceManager()
{ {
if(_advisories) { delete _advisories;
delete _advisories; _advisories = nullptr;
} delete _weatherProvider;
if(_weatherProvider) { _weatherProvider = nullptr;
delete _weatherProvider; delete _ruleSetsProvider;
} _ruleSetsProvider = nullptr;
if(_ruleSetsProvider) { delete _airspaces;
delete _ruleSetsProvider; _airspaces = nullptr;
} delete _flightPlan;
if(_airspaces) { _flightPlan = nullptr;
delete _airspaces;
}
if(_flightPlan) {
delete _flightPlan;
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
......
...@@ -527,10 +527,9 @@ void LogDownloadController::downloadToDirectory(const QString& dir) ...@@ -527,10 +527,9 @@ void LogDownloadController::downloadToDirectory(const QString& dir)
//-- Stop listing just in case //-- Stop listing just in case
_receivedAllEntries(); _receivedAllEntries();
//-- Reset downloads, again just in case //-- Reset downloads, again just in case
if(_downloadData) { delete _downloadData;
delete _downloadData; _downloadData = nullptr;
_downloadData = 0;
}
_downloadPath = dir; _downloadPath = dir;
if(!_downloadPath.isEmpty()) { if(!_downloadPath.isEmpty()) {
if(!_downloadPath.endsWith(QDir::separator())) if(!_downloadPath.endsWith(QDir::separator()))
...@@ -573,10 +572,9 @@ LogDownloadController::_getNextSelected() ...@@ -573,10 +572,9 @@ LogDownloadController::_getNextSelected()
bool bool
LogDownloadController::_prepareLogDownload() LogDownloadController::_prepareLogDownload()
{ {
if(_downloadData) { delete _downloadData;
delete _downloadData; _downloadData = nullptr;
_downloadData = nullptr;
}
QGCLogEntry* entry = _getNextSelected(); QGCLogEntry* entry = _getNextSelected();
if(!entry) { if(!entry) {
return false; return false;
......
...@@ -189,9 +189,8 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh ...@@ -189,9 +189,8 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QGCCameraControl::~QGCCameraControl() QGCCameraControl::~QGCCameraControl()
{ {
if(_netManager) { delete _netManager;
delete _netManager; _netManager = nullptr;
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -217,10 +216,9 @@ QGCCameraControl::_initWhenReady() ...@@ -217,10 +216,9 @@ QGCCameraControl::_initWhenReady()
QTimer::singleShot(2500, this, &QGCCameraControl::_requestStorageInfo); QTimer::singleShot(2500, this, &QGCCameraControl::_requestStorageInfo);
_captureStatusTimer.start(2750); _captureStatusTimer.start(2750);
emit infoChanged(); emit infoChanged();
if(_netManager) {
delete _netManager; delete _netManager;
_netManager = nullptr; _netManager = nullptr;
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
......
...@@ -39,12 +39,10 @@ VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox) ...@@ -39,12 +39,10 @@ VideoManager::VideoManager(QGCApplication* app, QGCToolbox* toolbox)
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
VideoManager::~VideoManager() VideoManager::~VideoManager()
{ {
if(_videoReceiver) { delete _videoReceiver;
delete _videoReceiver; _videoReceiver = nullptr;
} delete _thermalVideoReceiver;
if(_thermalVideoReceiver) { _thermalVideoReceiver = nullptr;
delete _thermalVideoReceiver;
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
......
...@@ -60,10 +60,8 @@ getQGCMapEngine() ...@@ -60,10 +60,8 @@ getQGCMapEngine()
void void
destroyMapEngine() destroyMapEngine()
{ {
if(kMapEngine) { delete kMapEngine;
delete kMapEngine; kMapEngine = nullptr;
kMapEngine = nullptr;
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -105,8 +103,8 @@ QGCMapEngine::~QGCMapEngine() ...@@ -105,8 +103,8 @@ QGCMapEngine::~QGCMapEngine()
{ {
_worker.quit(); _worker.quit();
_worker.wait(); _worker.wait();
if(_urlFactory) delete _urlFactory;
delete _urlFactory; _urlFactory = nullptr;
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
...@@ -373,8 +371,8 @@ int ...@@ -373,8 +371,8 @@ int
QGCMapEngine::concurrentDownloads(QString type) QGCMapEngine::concurrentDownloads(QString type)
{ {
Q_UNUSED(type); Q_UNUSED(type);
// TODO : We may want different values depending on // TODO : We may want different values depending on
// the provider here, let it like this as all provider are set to 12 // the provider here, let it like this as all provider are set to 12
// at the moment // at the moment
return 12; return 12;
} }
...@@ -408,4 +406,3 @@ QGCMapEngine::_internetStatus(bool active) ...@@ -408,4 +406,3 @@ QGCMapEngine::_internetStatus(bool active)
} }
// Resolution math: https://wiki.openstreetmap.org/wiki/Slippy_map_tilenames#Resolution_and_Scale // Resolution math: https://wiki.openstreetmap.org/wiki/Slippy_map_tilenames#Resolution_and_Scale
...@@ -243,8 +243,8 @@ public: ...@@ -243,8 +243,8 @@ public:
~QGCSaveTileTask() ~QGCSaveTileTask()
{ {
if(_tile) delete _tile;
delete _tile; _tile = nullptr;
} }
QGCCacheTile* tile() { return _tile; } QGCCacheTile* tile() { return _tile; }
......
...@@ -61,9 +61,8 @@ QGCCachedTileSet::QGCCachedTileSet(const QString& name) ...@@ -61,9 +61,8 @@ QGCCachedTileSet::QGCCachedTileSet(const QString& name)
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
QGCCachedTileSet::~QGCCachedTileSet() QGCCachedTileSet::~QGCCachedTileSet()
{ {
if(_networkManager) { delete _networkManager;
delete _networkManager; _networkManager = nullptr;
}
} }
//----------------------------------------------------------------------------- //-----------------------------------------------------------------------------
......
...@@ -688,9 +688,8 @@ MAVLinkLogManager::_sendLog(const QString& logFile) ...@@ -688,9 +688,8 @@ MAVLinkLogManager::_sendLog(const QString& logFile)
} }
QFile* file = new QFile(logFile); QFile* file = new QFile(logFile);
if(!file || !file->open(QIODevice::ReadOnly)) { if(!file || !file->open(QIODevice::ReadOnly)) {
if(file) { delete file;
delete file; file = nullptr;
}
qCWarning(MAVLinkLogManagerLog) << "Could not open log file:" << logFile; qCWarning(MAVLinkLogManagerLog) << "Could not open log file:" << logFile;
return false; return false;
} }
...@@ -929,10 +928,7 @@ MAVLinkLogManager::_discardLog() ...@@ -929,10 +928,7 @@ MAVLinkLogManager::_discardLog()
bool bool
MAVLinkLogManager::_createNewLog() MAVLinkLogManager::_createNewLog()
{ {
if(_logProcessor) { delete _logProcessor;
delete _logProcessor;
_logProcessor = nullptr;
}
_logProcessor = new MAVLinkLogProcessor; _logProcessor = new MAVLinkLogProcessor;
if(_logProcessor->create(this, _logPath, static_cast<uint8_t>(_vehicle->id()))) { if(_logProcessor->create(this, _logPath, static_cast<uint8_t>(_vehicle->id()))) {
_insertNewLog(_logProcessor->record()); _insertNewLog(_logProcessor->record());
......
...@@ -140,10 +140,9 @@ void ...@@ -140,10 +140,9 @@ void
VideoReceiver::_tcp_timeout() VideoReceiver::_tcp_timeout()
{ {
//-- If socket is live, we got no connection nor a socket error //-- If socket is live, we got no connection nor a socket error
if(_socket) { delete _socket;
delete _socket; _socket = nullptr;
_socket = nullptr;
}
if(_videoSettings->streamEnabled()->rawValue().toBool()) { if(_videoSettings->streamEnabled()->rawValue().toBool()) {
//-- RTSP will try to connect to the server. If it cannot connect, //-- RTSP will try to connect to the server. If it cannot connect,
// it will simply give up and never try again. Instead, we keep // it will simply give up and never try again. Instead, we keep
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment