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

Merge pull request #7674 from muramura/QGC_Change_NULL_or_0_to_nullptr

Global: change null or 0 to nullptr
parents f3b1e7bd f9a7d849
......@@ -41,7 +41,7 @@ AirspaceFlightInfo*
AirspaceFlightModel::get(int index)
{
if (index < 0 || index >= _flightEntries.count()) {
return NULL;
return nullptr;
}
return _flightEntries[index];
}
......
......@@ -104,9 +104,9 @@ QGCLogEntry::sizeStr() const
//----------------------------------------------------------------------------------------
LogDownloadController::LogDownloadController(void)
: _uas(NULL)
, _downloadData(NULL)
, _vehicle(NULL)
: _uas(nullptr)
, _downloadData(nullptr)
, _vehicle(nullptr)
, _requestingLogEntries(false)
, _downloadingLogs(false)
, _retries(0)
......@@ -137,7 +137,7 @@ LogDownloadController::_setActiveVehicle(Vehicle* vehicle)
_logEntriesModel.clear();
disconnect(_uas, &UASInterface::logEntry, this, &LogDownloadController::_logEntry);
disconnect(_uas, &UASInterface::logData, this, &LogDownloadController::_logData);
_uas = NULL;
_uas = nullptr;
}
_vehicle = vehicle;
if(_vehicle) {
......@@ -566,7 +566,7 @@ LogDownloadController::_getNextSelected()
}
}
}
return NULL;
return nullptr;
}
//----------------------------------------------------------------------------------------
......@@ -575,7 +575,7 @@ LogDownloadController::_prepareLogDownload()
{
if(_downloadData) {
delete _downloadData;
_downloadData = NULL;
_downloadData = nullptr;
}
QGCLogEntry* entry = _getNextSelected();
if(!entry) {
......@@ -634,7 +634,7 @@ LogDownloadController::_prepareLogDownload()
}
_downloadData->entry->setStatus(tr("Error"));
delete _downloadData;
_downloadData = NULL;
_downloadData = nullptr;
}
return result;
}
......@@ -709,7 +709,7 @@ QGCLogEntry*
QGCLogModel::get(int index)
{
if (index < 0 || index >= _logEntries.count()) {
return NULL;
return nullptr;
}
return _logEntries[index];
}
......
......@@ -18,7 +18,7 @@ class APMAirframeComponent : public VehicleComponent
Q_OBJECT
public:
APMAirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
APMAirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList(void) const override;
......
......@@ -38,19 +38,19 @@
APMAutoPilotPlugin::APMAutoPilotPlugin(Vehicle* vehicle, QObject* parent)
: AutoPilotPlugin (vehicle, parent)
, _incorrectParameterVersion(false)
, _airframeComponent (NULL)
, _cameraComponent (NULL)
, _lightsComponent (NULL)
, _subFrameComponent (NULL)
, _flightModesComponent (NULL)
, _powerComponent (NULL)
, _motorComponent (NULL)
, _radioComponent (NULL)
, _safetyComponent (NULL)
, _sensorsComponent (NULL)
, _tuningComponent (NULL)
, _esp8266Component (NULL)
, _heliComponent (NULL)
, _airframeComponent (nullptr)
, _cameraComponent (nullptr)
, _lightsComponent (nullptr)
, _subFrameComponent (nullptr)
, _flightModesComponent (nullptr)
, _powerComponent (nullptr)
, _motorComponent (nullptr)
, _radioComponent (nullptr)
, _safetyComponent (nullptr)
, _sensorsComponent (nullptr)
, _tuningComponent (nullptr)
, _esp8266Component (nullptr)
, _heliComponent (nullptr)
{
#if !defined(NO_SERIAL_LINK) && !defined(__android__)
connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &APMAutoPilotPlugin::_checkForBadCubeBlack);
......
......@@ -18,7 +18,7 @@ class APMCameraComponent : public VehicleComponent
Q_OBJECT
public:
APMCameraComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
APMCameraComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList(void) const final;
......
......@@ -73,9 +73,9 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate(void)
for (size_t cur_mag=0; cur_mag<max_mags; cur_mag++) {
// Initialize to no memory allocated
worker_data.x[cur_mag] = NULL;
worker_data.y[cur_mag] = NULL;
worker_data.z[cur_mag] = NULL;
worker_data.x[cur_mag] = nullptr;
worker_data.y[cur_mag] = nullptr;
worker_data.z[cur_mag] = nullptr;
worker_data.calibration_counter_total[cur_mag] = 0;
}
......@@ -86,7 +86,7 @@ CalWorkerThread::calibrate_return CalWorkerThread::calibrate(void)
worker_data.x[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount));
worker_data.y[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount));
worker_data.z[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount));
if (worker_data.x[cur_mag] == NULL || worker_data.y[cur_mag] == NULL || worker_data.z[cur_mag] == NULL) {
if (worker_data.x[cur_mag] == nullptr || worker_data.y[cur_mag] == nullptr || worker_data.z[cur_mag] == nullptr) {
_emitVehicleTextMessage(QStringLiteral("[cal] ERROR: out of memory"));
result = calibrate_return_error;
}
......@@ -576,8 +576,8 @@ int CalWorkerThread::sphere_fit_least_squares(const float x[], const float y[],
}
APMCompassCal::APMCompassCal(void)
: _vehicle(NULL)
, _calWorkerThread(NULL)
: _vehicle(nullptr)
, _calWorkerThread(nullptr)
{
}
......
......@@ -26,7 +26,7 @@ class CalWorkerThread : public QThread
Q_OBJECT
public:
CalWorkerThread(Vehicle* vehicle, QObject* parent = NULL);
CalWorkerThread(Vehicle* vehicle, QObject* parent = nullptr);
// Cancel currently in progress calibration
void cancel(void) { _cancel = true; }
......
......@@ -18,7 +18,7 @@ class APMFlightModesComponent : public VehicleComponent
Q_OBJECT
public:
APMFlightModesComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
APMFlightModesComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList(void) const final;
......
......@@ -16,7 +16,7 @@ class APMHeliComponent : public VehicleComponent
Q_OBJECT
public:
APMHeliComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
APMHeliComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList(void) const override;
......
......@@ -18,7 +18,7 @@ class APMLightsComponent : public VehicleComponent
Q_OBJECT
public:
APMLightsComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
APMLightsComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList(void) const final;
......
......@@ -18,7 +18,7 @@ class APMMotorComponent : public MotorComponent
Q_OBJECT
public:
APMMotorComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
APMMotorComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
QUrl setupSource(void) const final;
......
......@@ -18,7 +18,7 @@ class APMPowerComponent : public VehicleComponent
Q_OBJECT
public:
APMPowerComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
APMPowerComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Overrides from VehicleComponent
QStringList setupCompleteChangedTriggerList(void) const override { return QStringList(); }
......
......@@ -19,7 +19,7 @@ class APMRadioComponent : public VehicleComponent
Q_OBJECT
public:
APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList(void) const final;
......
......@@ -18,7 +18,7 @@ class APMSafetyComponent : public VehicleComponent
Q_OBJECT
public:
APMSafetyComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
APMSafetyComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList(void) const override;
......
......@@ -18,7 +18,7 @@ class APMSensorsComponent : public VehicleComponent
Q_OBJECT
public:
APMSensorsComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
APMSensorsComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
bool compassSetupNeeded(void) const;
bool accelSetupNeeded(void) const;
......
......@@ -24,11 +24,11 @@ QGC_LOGGING_CATEGORY(APMSensorsComponentControllerVerboseLog, "APMSensorsCompone
const char* APMSensorsComponentController::_compassCalFitnessParam = "COMPASS_CAL_FIT";
APMSensorsComponentController::APMSensorsComponentController(void)
: _sensorsComponent(NULL)
, _statusLog(NULL)
, _progressBar(NULL)
, _nextButton(NULL)
, _cancelButton(NULL)
: _sensorsComponent(nullptr)
, _statusLog(nullptr)
, _progressBar(nullptr)
, _nextButton(nullptr)
, _cancelButton(nullptr)
, _showOrientationCalArea(false)
, _calTypeInProgress(CalTypeNone)
, _orientationCalDownSideDone(false)
......
......@@ -18,7 +18,7 @@ class APMSubFrameComponent : public VehicleComponent
Q_OBJECT
public:
APMSubFrameComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
APMSubFrameComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList(void) const final;
......
......@@ -59,7 +59,7 @@ signals:
protected:
/// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin
AutoPilotPlugin(QObject* parent = NULL) : QObject(parent) { }
AutoPilotPlugin(QObject* parent = nullptr) : QObject(parent) { }
Vehicle* _vehicle;
FirmwarePlugin* _firmwarePlugin;
......
......@@ -17,7 +17,7 @@ class ESP8266Component : public VehicleComponent
{
Q_OBJECT
public:
ESP8266Component (Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
ESP8266Component (Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList() const;
......
......@@ -19,7 +19,7 @@ class MotorComponent : public VehicleComponent
Q_OBJECT
public:
MotorComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
MotorComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList(void) const final;
......
......@@ -17,7 +17,7 @@ class SyslinkComponent : public VehicleComponent
{
Q_OBJECT
public:
SyslinkComponent (Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
SyslinkComponent (Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList() const;
......
......@@ -23,7 +23,7 @@ class GenericAutoPilotPlugin : public AutoPilotPlugin
Q_OBJECT
public:
GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent = NULL);
GenericAutoPilotPlugin(Vehicle* vehicle, QObject* parent = nullptr);
// Overrides from AutoPilotPlugin
const QVariantList& vehicleComponents(void) final;
......
......@@ -22,7 +22,7 @@ class AirframeComponent : public VehicleComponent
Q_OBJECT
public:
AirframeComponent(Vehicle* vehicles, AutoPilotPlugin* autopilot, QObject* parent = NULL);
AirframeComponent(Vehicle* vehicles, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
virtual QStringList setupCompleteChangedTriggerList(void) const;
......
......@@ -71,7 +71,7 @@ class Airframe : public QObject
Q_OBJECT
public:
Airframe(const QString& name, int autostartId, QObject* parent = NULL);
Airframe(const QString& name, int autostartId, QObject* parent = nullptr);
~Airframe();
Q_PROPERTY(QString text MEMBER _name CONSTANT)
......@@ -87,7 +87,7 @@ class AirframeType : public QObject
Q_OBJECT
public:
AirframeType(const QString& name, const QString& imageResource, QObject* parent = NULL);
AirframeType(const QString& name, const QString& imageResource, QObject* parent = nullptr);
~AirframeType();
Q_PROPERTY(QString name MEMBER _name CONSTANT)
......
......@@ -23,7 +23,7 @@ class CameraComponent : public VehicleComponent
Q_OBJECT
public:
CameraComponent (Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
CameraComponent (Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList (void) const;
......
......@@ -22,7 +22,7 @@ class FlightModesComponent : public VehicleComponent
Q_OBJECT
public:
FlightModesComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
FlightModesComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
virtual QStringList setupCompleteChangedTriggerList(void) const;
......
......@@ -34,7 +34,7 @@ class PX4AirframeLoader : QObject
public:
/// @param uas Uas which this set of facts is associated with
PX4AirframeLoader(AutoPilotPlugin* autpilot,UASInterface* uas, QObject* parent = NULL);
PX4AirframeLoader(AutoPilotPlugin* autpilot,UASInterface* uas, QObject* parent = nullptr);
static void loadAirframeMetaData(void);
......
......@@ -30,16 +30,16 @@
PX4AutoPilotPlugin::PX4AutoPilotPlugin(Vehicle* vehicle, QObject* parent)
: AutoPilotPlugin(vehicle, parent)
, _incorrectParameterVersion(false)
, _airframeComponent(NULL)
, _radioComponent(NULL)
, _esp8266Component(NULL)
, _flightModesComponent(NULL)
, _sensorsComponent(NULL)
, _safetyComponent(NULL)
, _powerComponent(NULL)
, _motorComponent(NULL)
, _tuningComponent(NULL)
, _syslinkComponent(NULL)
, _airframeComponent(nullptr)
, _radioComponent(nullptr)
, _esp8266Component(nullptr)
, _flightModesComponent(nullptr)
, _sensorsComponent(nullptr)
, _safetyComponent(nullptr)
, _powerComponent(nullptr)
, _motorComponent(nullptr)
, _tuningComponent(nullptr)
, _syslinkComponent(nullptr)
{
if (!vehicle) {
qWarning() << "Internal error";
......
......@@ -18,7 +18,7 @@ class PX4RadioComponent : public VehicleComponent
Q_OBJECT
public:
PX4RadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
PX4RadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
virtual QStringList setupCompleteChangedTriggerList(void) const;
......
......@@ -18,7 +18,7 @@ class PX4TuningComponent : public VehicleComponent
Q_OBJECT
public:
PX4TuningComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
PX4TuningComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList(void) const final;
......
......@@ -22,7 +22,7 @@ class PowerComponent : public VehicleComponent
Q_OBJECT
public:
PowerComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
PowerComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Overrides from VehicleComponent
QStringList setupCompleteChangedTriggerList(void) const override;
......
......@@ -23,7 +23,7 @@ class SafetyComponent : public VehicleComponent
Q_OBJECT
public:
SafetyComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
SafetyComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList(void) const override;
......
......@@ -22,7 +22,7 @@ class SensorsComponent : public VehicleComponent
Q_OBJECT
public:
SensorsComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = NULL);
SensorsComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent = nullptr);
// Virtuals from VehicleComponent
QStringList setupCompleteChangedTriggerList(void) const override;
......
......@@ -19,15 +19,15 @@
QGC_LOGGING_CATEGORY(SensorsComponentControllerLog, "SensorsComponentControllerLog")
SensorsComponentController::SensorsComponentController(void)
: _statusLog (NULL)
, _progressBar (NULL)
, _compassButton (NULL)
, _gyroButton (NULL)
, _accelButton (NULL)
, _airspeedButton (NULL)
, _levelButton (NULL)
, _cancelButton (NULL)
, _setOrientationsButton (NULL)
: _statusLog (nullptr)
, _progressBar (nullptr)
, _compassButton (nullptr)
, _gyroButton (nullptr)
, _accelButton (nullptr)
, _airspeedButton (nullptr)
, _levelButton (nullptr)
, _cancelButton (nullptr)
, _setOrientationsButton (nullptr)
, _showOrientationCalArea (false)
, _gyroCalInProgress (false)
, _magCalInProgress (false)
......
......@@ -53,19 +53,19 @@ void FactGroup::_setupTimer()
Fact* FactGroup::getFact(const QString& name)
{
Fact* fact = NULL;
Fact* fact = nullptr;
if (name.contains(".")) {
QStringList parts = name.split(".");
if (parts.count() != 2) {
qWarning() << "Only single level of hierarchy supported";
return NULL;
return nullptr;
}
FactGroup * factGroup = getFactGroup(parts[0]);
if (!factGroup) {
qWarning() << "Unknown FactGroup" << parts[0];
return NULL;
return nullptr;
}
return factGroup->getFact(parts[1]);
......@@ -83,7 +83,7 @@ Fact* FactGroup::getFact(const QString& name)
FactGroup* FactGroup::getFactGroup(const QString& name)
{
FactGroup* factGroup = NULL;
FactGroup* factGroup = nullptr;
if (_nameToFactGroupMap.contains(name)) {
factGroup = _nameToFactGroupMap[name];
......
......@@ -26,8 +26,8 @@ class FactGroup : public QObject
Q_OBJECT
public:
FactGroup(int updateRateMsecs, const QString& metaDataFile, QObject* parent = NULL);
FactGroup(int updateRateMsecs, QObject* parent = NULL);
FactGroup(int updateRateMsecs, const QString& metaDataFile, QObject* parent = nullptr);
FactGroup(int updateRateMsecs, QObject* parent = nullptr);
Q_PROPERTY(QStringList factNames READ factNames CONSTANT)
Q_PROPERTY(QStringList factGroupNames READ factGroupNames CONSTANT)
......
......@@ -933,7 +933,7 @@ const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsDist
return pAppSettingsTranslation;
}
}
return NULL;
return nullptr;
}
const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsAreaUnitsTranslation(const QString& rawUnits)
......@@ -953,7 +953,7 @@ const FactMetaData::AppSettingsTranslation_s* FactMetaData::_findAppSettingsArea
}
}
return NULL;
return nullptr;
}
QVariant FactMetaData::metersToAppSettingsDistanceUnits(const QVariant& meters)
......
......@@ -48,7 +48,7 @@ void FactSystemTestBase::_parameter_default_component_id_test(void)
{
QVERIFY(_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "RC_MAP_THROTTLE"));
Fact* fact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "RC_MAP_THROTTLE");
QVERIFY(fact != NULL);
QVERIFY(fact != nullptr);
QVariant factValue = fact->rawValue();
QCOMPARE(factValue.isValid(), true);
......@@ -59,7 +59,7 @@ void FactSystemTestBase::_parameter_specific_component_id_test(void)
{
QVERIFY(_vehicle->parameterManager()->parameterExists(MAV_COMP_ID_AUTOPILOT1, "RC_MAP_THROTTLE"));
Fact* fact = _vehicle->parameterManager()->getParameter(MAV_COMP_ID_AUTOPILOT1, "RC_MAP_THROTTLE");
QVERIFY(fact != NULL);
QVERIFY(fact != nullptr);
QVariant factValue = fact->rawValue();
QCOMPARE(factValue.isValid(), true);
QCOMPARE(factValue.toInt(), 3);
......
......@@ -19,7 +19,7 @@ class FactValueSliderListModel : public QAbstractListModel
Q_OBJECT
public:
FactValueSliderListModel(Fact& fact, QObject* parent = NULL);
FactValueSliderListModel(Fact& fact, QObject* parent = nullptr);
~FactValueSliderListModel();
/// The initial value of the Fact at the meta data specified decimal place precision
......
......@@ -35,7 +35,7 @@ const char* ParameterManager::_jsonParamValueKey = "value";
ParameterManager::ParameterManager(Vehicle* vehicle)
: QObject (vehicle)
, _vehicle (vehicle)
, _mavlink (NULL)
, _mavlink (nullptr)
, _loadProgress (0.0)
, _parametersReady (false)
, _missingParameters (false)
......@@ -45,7 +45,7 @@ ParameterManager::ParameterManager(Vehicle* vehicle)
, _metaDataAddedToFacts (false)
, _logReplay (vehicle->priorityLink() && vehicle->priorityLink()->isLogReplay())
, _parameterSetMajorVersion (-1)
, _parameterMetaData (NULL)
, _parameterMetaData (nullptr)
, _prevWaitingReadParamIndexCount (0)
, _prevWaitingReadParamNameCount (0)
, _prevWaitingWriteParamNameCount (0)
......@@ -330,7 +330,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
_dataMutex.unlock();
Fact* fact = NULL;
Fact* fact = nullptr;
if (_mapParameterName2Variant[componentId].contains(parameterName)) {
fact = _mapParameterName2Variant[componentId][parameterName].value<Fact*>();
}
......@@ -1052,7 +1052,7 @@ void ParameterManager::_clearMetaData(void)
{
if (_parameterMetaData) {
_parameterMetaData->deleteLater();
_parameterMetaData = NULL;
_parameterMetaData = nullptr;
}
}
......@@ -1288,7 +1288,7 @@ void ParameterManager::cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPI
// Find the cache hit closest to this new file
int cacheMajorVersion, cacheMinorVersion;
QString cacheHit = ParameterManager::parameterMetaDataFile(NULL, firmwareType, newMajorVersion, cacheMajorVersion, cacheMinorVersion);
QString cacheHit = ParameterManager::parameterMetaDataFile(nullptr, firmwareType, newMajorVersion, cacheMajorVersion, cacheMinorVersion);
qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion;
bool cacheNewFile = false;
......
......@@ -148,7 +148,7 @@ class APMFirmwarePluginInstanceData : public QObject
Q_OBJECT
public:
APMFirmwarePluginInstanceData(QObject* parent = NULL);
APMFirmwarePluginInstanceData(QObject* parent = nullptr);
bool textSeverityAdjustmentNeeded;
};
......
......@@ -16,10 +16,10 @@
APMFirmwarePluginFactory APMFirmwarePluginFactory;
APMFirmwarePluginFactory::APMFirmwarePluginFactory(void)
: _arduCopterPluginInstance(NULL)
, _arduPlanePluginInstance(NULL)
, _arduRoverPluginInstance(NULL)
, _arduSubPluginInstance(NULL)
: _arduCopterPluginInstance(nullptr)
, _arduPlanePluginInstance(nullptr)
, _arduRoverPluginInstance(nullptr)
, _arduSubPluginInstance(nullptr)
{
}
......@@ -74,5 +74,5 @@ FirmwarePlugin* APMFirmwarePluginFactory::firmwarePluginForAutopilot(MAV_AUTOPIL
}
}
return NULL;
return nullptr;
}
......@@ -157,7 +157,7 @@ void APMParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData
bool badMetaData = true;
QStack<int> xmlState;
APMFactMetaDataRaw* rawMetaData = NULL;
APMFactMetaDataRaw* rawMetaData = nullptr;
xmlState.push(XmlStateNone);
......@@ -285,7 +285,7 @@ void APMParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData
// Done loading this parameter
// Reset for next parameter
qCDebug(APMParameterMetaDataVerboseLog) << "done loading parameter";
rawMetaData = NULL;
rawMetaData = nullptr;
badMetaData = false;
xmlState.pop();
} else if (elementName == "parameters") {
......@@ -422,7 +422,7 @@ bool APMParameterMetaData::parseParameterAttributes(QXmlStreamReader& xml, APMFa
void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
{
const QString mavTypeString = mavTypeToString(vehicleType);
APMFactMetaDataRaw* rawMetaData = NULL;
APMFactMetaDataRaw* rawMetaData = nullptr;
// check if we have metadata for fact, use generic otherwise
if (_vehicleTypeToParametersMap[mavTypeString].contains(fact->name())) {
......
......@@ -33,7 +33,7 @@ class APMSubmarineFactGroup : public FactGroup
Q_OBJECT
public:
APMSubmarineFactGroup(QObject* parent = NULL);
APMSubmarineFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* camTilt READ camTilt CONSTANT)
Q_PROPERTY(Fact* tetherTurns READ tetherTurns CONSTANT)
......
......@@ -26,7 +26,7 @@ public:
bool landscape,
bool fixedOrientation,
double minTriggerInterval,
QObject* parent = NULL);
QObject* parent = nullptr);
Q_PROPERTY(QString name READ name CONSTANT) ///< Camera name
Q_PROPERTY(double sensorWidth READ sensorWidth CONSTANT) ///< Sensor size in millimeters
......
......@@ -89,5 +89,5 @@ FirmwarePluginFactory* FirmwarePluginManager::_findPluginFactory(MAV_AUTOPILOT f
}
}
return NULL;
return nullptr;
}
......@@ -84,8 +84,8 @@ void GPSManager::disconnectGPS(void)
if (_rtcmMavlink) {
delete(_rtcmMavlink);
}
_gpsProvider = NULL;
_rtcmMavlink = NULL;
_gpsProvider = nullptr;
_rtcmMavlink = nullptr;
}
......
......@@ -19,7 +19,7 @@ class CameraCalc : public CameraSpec
Q_OBJECT
public:
CameraCalc(Vehicle* vehicle, const QString& settingsGroup, QObject* parent = NULL);
CameraCalc(Vehicle* vehicle, const QString& settingsGroup, QObject* parent = nullptr);
Q_PROPERTY(QString customCameraName READ customCameraName CONSTANT) ///< Camera name for custom camera setting
Q_PROPERTY(QString manualCameraName READ manualCameraName CONSTANT) ///< Camera name for manual camera setting
......
......@@ -11,7 +11,7 @@
#include "QGCApplication.h"
CameraCalcTest::CameraCalcTest(void)
: _offlineVehicle(NULL)
: _offlineVehicle(nullptr)
{
}
......
......@@ -147,7 +147,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
}
if (_cameraActionFact.rawValue().toInt() != CameraActionNone) {
MissionItem* item = NULL;
MissionItem* item = nullptr;
switch (_cameraActionFact.rawValue().toInt()) {
case TakePhotosIntervalTime:
......
......@@ -21,7 +21,7 @@ class CameraSection : public Section
Q_OBJECT
public:
CameraSection(Vehicle* vehicle, QObject* parent = NULL);
CameraSection(Vehicle* vehicle, QObject* parent = nullptr);
// These enum values must match the json meta data
......
......@@ -13,16 +13,16 @@
#include "MissionCommandUIInfo.h"
CameraSectionTest::CameraSectionTest(void)
: _spyCamera (NULL)
, _spySection (NULL)
, _cameraSection (NULL)
, _validGimbalItem (NULL)
, _validDistanceItem (NULL)
, _validTimeItem (NULL)
, _validStartVideoItem (NULL)
, _validCameraPhotoModeItem (NULL)
, _validCameraVideoModeItem (NULL)
, _validCameraSurveyPhotoModeItem (NULL)
: _spyCamera (nullptr)
, _spySection (nullptr)
, _cameraSection (nullptr)
, _validGimbalItem (nullptr)
, _validDistanceItem (nullptr)
, _validTimeItem (nullptr)
, _validStartVideoItem (nullptr)
, _validCameraPhotoModeItem (nullptr)
, _validCameraVideoModeItem (nullptr)
, _validCameraSurveyPhotoModeItem (nullptr)
{
}
......@@ -143,7 +143,7 @@ void CameraSectionTest::cleanup(void)
void CameraSectionTest::_createSpy(CameraSection* cameraSection, MultiSignalSpy** cameraSpy)
{
*cameraSpy = NULL;
*cameraSpy = nullptr;
MultiSignalSpy* spy = new MultiSignalSpy();
QCOMPARE(spy->init(cameraSection, rgCameraSignals, cCameraSignals), true);
*cameraSpy = spy;
......@@ -618,7 +618,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
// Gimbal command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validGimbalItem->missionItem(), NULL);
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validGimbalItem->missionItem(), nullptr);
invalidSimpleItem.missionItem().setParam2(10); // roll is not supported
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
......@@ -708,7 +708,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
*/
// Mode command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validCameraPhotoModeItem->missionItem(), NULL);
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validCameraPhotoModeItem->missionItem(), nullptr);
invalidSimpleItem.missionItem().setParam3(1); // Param3 should be NaN
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
......@@ -747,7 +747,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
// Image start command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validTimeItem->missionItem(), NULL);
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validTimeItem->missionItem(), nullptr);
invalidSimpleItem.missionItem().setParam3(10); // must be 0 for unlimited
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
......@@ -788,7 +788,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
// Trigger distance command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validDistanceItem->missionItem(), NULL);
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validDistanceItem->missionItem(), nullptr);
invalidSimpleItem.missionItem().setParam1(-1); // must be >= 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
......@@ -873,7 +873,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
// Start Video command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validStartVideoItem->missionItem(), NULL);
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validStartVideoItem->missionItem(), nullptr);
invalidSimpleItem.missionItem().setParam1(10); // Reserved (must be 0)
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
......@@ -909,7 +909,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
// Trigger distance command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validStopVideoItem->missionItem(), NULL);
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validStopVideoItem->missionItem(), nullptr);
invalidSimpleItem.missionItem().setParam1(10); // must be 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
......@@ -949,8 +949,8 @@ void CameraSectionTest::_testScanForStopPhotoSection(void)
// Out of order commands
SimpleMissionItem validStopDistanceItem(_offlineVehicle, false /* flyView */, NULL);
SimpleMissionItem validStopTimeItem(_offlineVehicle, false /* flyView */, NULL);
SimpleMissionItem validStopDistanceItem(_offlineVehicle, false /* flyView */, nullptr);
SimpleMissionItem validStopTimeItem(_offlineVehicle, false /* flyView */, nullptr);
validStopDistanceItem.missionItem() = _validStopDistanceItem->missionItem();
validStopTimeItem.missionItem() = _validStopTimeItem->missionItem();
visualItems.append(&validStopTimeItem);
......@@ -990,7 +990,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
// Take Photo command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validTimeItem->missionItem(), NULL);
SimpleMissionItem invalidSimpleItem(_offlineVehicle, false /* flyView */, _validTimeItem->missionItem(), nullptr);
invalidSimpleItem.missionItem().setParam3(10); // must be 1 for single photo
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
......
......@@ -16,7 +16,7 @@ class CameraSpec : public QObject
Q_OBJECT
public:
CameraSpec(const QString& settingsGroup, QObject* parent = NULL);
CameraSpec(const QString& settingsGroup, QObject* parent = nullptr);
const CameraSpec& operator=(const CameraSpec& other);
......
......@@ -335,7 +335,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
if (_loadedMissionItemsParent) {
_loadedMissionItems.clear();
_loadedMissionItemsParent->deleteLater();
_loadedMissionItemsParent = NULL;
_loadedMissionItemsParent = nullptr;
}
_transects.clear();
......
......@@ -11,7 +11,7 @@
#include "QGCApplication.h"
CorridorScanComplexItemTest::CorridorScanComplexItemTest(void)
: _offlineVehicle(NULL)
: _offlineVehicle(nullptr)
{
_linePoints << QGeoCoordinate(47.633550640000003, -122.08982199)
<< QGeoCoordinate(47.634129020000003, -122.08887249)
......
......@@ -30,7 +30,7 @@ class MissionCommandList : public QObject
public:
/// @param jsonFilename Json file which contains commands
/// @param baseCommandList true: bottomost level of mission command hierarchy (partial not allowed), false: mid-level of command hierarchy
MissionCommandList(const QString& jsonFilename, bool baseCommandList, QObject* parent = NULL);
MissionCommandList(const QString& jsonFilename, bool baseCommandList, QObject* parent = nullptr);
/// Returns list of categories in this list
QStringList& categories(void) { return _categories; }
......
......@@ -59,7 +59,7 @@ void MissionCommandTreeTest::_checkFullInfoMap(const MissionCommandUIInfo* uiInf
// Verifies that values match settings for base tree
void MissionCommandTreeTest::_checkBaseValues(const MissionCommandUIInfo* uiInfo, int command)
{
QVERIFY(uiInfo != NULL);
QVERIFY(uiInfo != nullptr);
_checkFullInfoMap(uiInfo);
QCOMPARE(uiInfo->command(), (MAV_CMD)command);
QCOMPARE(uiInfo->rawName(), _rawName(command));
......@@ -116,7 +116,7 @@ void MissionCommandTreeTest::_checkOverrideValues(const MissionCommandUIInfo* ui
bool showUI;
QString overrideString = QString("override fw %1").arg(command);
QVERIFY(uiInfo != NULL);
QVERIFY(uiInfo != nullptr);
_checkFullInfoMap(uiInfo);
QCOMPARE(uiInfo->command(), (MAV_CMD)command);
QCOMPARE(uiInfo->rawName(), _rawName(command));
......@@ -143,11 +143,11 @@ void MissionCommandTreeTest::testJsonLoad(void)
// Test loading from the bad command list
MissionCommandList* commandList = _commandTree->_staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_GENERIC];
QVERIFY(commandList != NULL);
QVERIFY(commandList != nullptr);
// Command 1 should have all values defaulted, no params
MissionCommandUIInfo* uiInfo = commandList->getUIInfo((MAV_CMD)1);
QVERIFY(uiInfo != NULL);
QVERIFY(uiInfo != nullptr);
_checkFullInfoMap(uiInfo);
QCOMPARE(uiInfo->command(), (MAV_CMD)1);
QCOMPARE(uiInfo->rawName(), _rawName(1));
......@@ -158,13 +158,13 @@ void MissionCommandTreeTest::testJsonLoad(void)
QCOMPARE(uiInfo->isStandaloneCoordinate(), false);
QCOMPARE(uiInfo->specifiesCoordinate(), false);
for (int i=1; i<=7; i++) {
QVERIFY(uiInfo->getParamInfo(i, showUI) == NULL);
QVERIFY(uiInfo->getParamInfo(i, showUI) == nullptr);
QCOMPARE(showUI, false);
}
// Command 2 should all values defaulted for param 1
uiInfo = commandList->getUIInfo((MAV_CMD)2);
QVERIFY(uiInfo != NULL);
QVERIFY(uiInfo != nullptr);
const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(1, showUI);
QVERIFY(paramInfo);
QCOMPARE(showUI, true);
......@@ -176,7 +176,7 @@ void MissionCommandTreeTest::testJsonLoad(void)
QCOMPARE(paramInfo->param(), 1);
QVERIFY(paramInfo->units().isEmpty());
for (int i=2; i<=7; i++) {
QVERIFY(uiInfo->getParamInfo(i, showUI) == NULL);
QVERIFY(uiInfo->getParamInfo(i, showUI) == nullptr);
QCOMPARE(showUI, false);
}
......@@ -214,7 +214,7 @@ void MissionCommandTreeTest::testAllTrees(void)
}
qDebug() << firmwareType << vehicleType;
Vehicle* vehicle = new Vehicle(firmwareType, vehicleType, qgcApp()->toolbox()->firmwarePluginManager());
QVERIFY(qgcApp()->toolbox()->missionCommandTree()->getUIInfo(vehicle, MAV_CMD_NAV_WAYPOINT) != NULL);
QVERIFY(qgcApp()->toolbox()->missionCommandTree()->getUIInfo(vehicle, MAV_CMD_NAV_WAYPOINT) != nullptr);
delete vehicle;
}
}
......
......@@ -42,9 +42,9 @@ class MissionCmdParamInfo : public QObject {
Q_OBJECT
public:
MissionCmdParamInfo(QObject* parent = NULL);
MissionCmdParamInfo(QObject* parent = nullptr);
MissionCmdParamInfo(const MissionCmdParamInfo& other, QObject* parent = NULL);
MissionCmdParamInfo(const MissionCmdParamInfo& other, QObject* parent = nullptr);
const MissionCmdParamInfo& operator=(const MissionCmdParamInfo& other);
Q_PROPERTY(int decimalPlaces READ decimalPlaces CONSTANT)
......@@ -105,9 +105,9 @@ class MissionCommandUIInfo : public QObject {
Q_OBJECT
public:
MissionCommandUIInfo(QObject* parent = NULL);
MissionCommandUIInfo(QObject* parent = nullptr);
MissionCommandUIInfo(const MissionCommandUIInfo& other, QObject* parent = NULL);
MissionCommandUIInfo(const MissionCommandUIInfo& other, QObject* parent = nullptr);
const MissionCommandUIInfo& operator=(const MissionCommandUIInfo& other);
Q_PROPERTY(QString category READ category CONSTANT)
......
......@@ -1663,7 +1663,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem)
void MissionController::_deinitVisualItem(VisualMissionItem* visualItem)
{
// Disconnect all signals
disconnect(visualItem, 0, 0, 0);
disconnect(visualItem, nullptr, nullptr, nullptr);
}
void MissionController::_itemCommandChanged(void)
......@@ -1677,8 +1677,8 @@ void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
if (_managerVehicle) {
_missionManager->disconnect(this);
_managerVehicle->disconnect(this);
_managerVehicle = NULL;
_missionManager = NULL;
_managerVehicle = nullptr;
_missionManager = nullptr;
}
_managerVehicle = managerVehicle;
......@@ -2056,7 +2056,7 @@ VisualMissionItem* MissionController::currentPlanViewItem(void) const
void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
{
if(_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) {
_currentPlanViewItem = NULL;
_currentPlanViewItem = nullptr;
_currentPlanViewIndex = -1;
for (int i = 0; i < _visualItems->count(); i++) {
VisualMissionItem* pVI = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
......
......@@ -40,7 +40,7 @@ class MissionController : public PlanElementController
Q_OBJECT
public:
MissionController(PlanMasterController* masterController, QObject* parent = NULL);
MissionController(PlanMasterController* masterController, QObject* parent = nullptr);
~MissionController();
typedef struct _MissionFlightStatus_t {
......
......@@ -21,7 +21,7 @@ MissionControllerManagerTest::MissionControllerManagerTest(void)
void MissionControllerManagerTest::cleanup(void)
{
delete _multiSpyMissionManager;
_multiSpyMissionManager = NULL;
_multiSpyMissionManager = nullptr;
UnitTest::cleanup();
}
......
......@@ -18,9 +18,9 @@
#include "AppSettings.h"
MissionControllerTest::MissionControllerTest(void)
: _multiSpyMissionController(NULL)
, _multiSpyMissionItem(NULL)
, _missionController(NULL)
: _multiSpyMissionController(nullptr)
, _multiSpyMissionItem(nullptr)
, _missionController(nullptr)
{
}
......@@ -28,13 +28,13 @@ MissionControllerTest::MissionControllerTest(void)
void MissionControllerTest::cleanup(void)
{
delete _masterController;
_masterController = NULL;
_masterController = nullptr;
delete _multiSpyMissionController;
_multiSpyMissionController = NULL;
_multiSpyMissionController = nullptr;
delete _multiSpyMissionItem;
_multiSpyMissionItem = NULL;
_multiSpyMissionItem = nullptr;
MissionControllerManagerTest::cleanup();
}
......
......@@ -38,7 +38,7 @@ class MissionItem : public QObject
Q_OBJECT
public:
MissionItem(QObject* parent = NULL);
MissionItem(QObject* parent = nullptr);
MissionItem(int sequenceNumber,
MAV_CMD command,
......@@ -52,9 +52,9 @@ public:
double param7,
bool autoContinue,
bool isCurrentItem,
QObject* parent = NULL);
QObject* parent = nullptr);
MissionItem(const MissionItem& other, QObject* parent = NULL);
MissionItem(const MissionItem& other, QObject* parent = nullptr);
~MissionItem();
......
......@@ -28,7 +28,7 @@ const size_t MissionItemTest::_cTestCases = sizeof(_rgTestCases)/sizeof(_rgTestC
#endif
MissionItemTest::MissionItemTest(void)
: _offlineVehicle(NULL)
: _offlineVehicle(nullptr)
{
}
......@@ -282,7 +282,7 @@ void MissionItemTest::_testSimpleLoadFromStream(void)
{
// We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values.
SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, NULL);
SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, nullptr);
QString testString("10\t0\t3\t80\t10\t20\t30\t40\t-10\t-20\t-30\t1\r\n");
QTextStream testStream(&testString, QIODevice::ReadOnly);
......@@ -452,7 +452,7 @@ void MissionItemTest::_testSimpleLoadFromJson(void)
// We specifically test SimpleMissionItem loading as well since it has additional
// signalling which can affect values.
SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, NULL);
SimpleMissionItem simpleMissionItem(_offlineVehicle, false /* flyView */, nullptr);
QString errorString;
QJsonArray coordinateArray;
QJsonObject jsonObject;
......
......@@ -35,7 +35,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
QList<MissionItem*> missionItems;
// Editor has a home position item on the front, so we do the same
MissionItem* homeItem = new MissionItem(NULL /* Vehicle */, this);
MissionItem* homeItem = new MissionItem(nullptr /* Vehicle */, this);
homeItem->setCommand(MAV_CMD_NAV_WAYPOINT);
homeItem->setParam5(47.3769);
homeItem->setParam6(8.549444);
......
......@@ -40,7 +40,7 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject
_editorQml = "qrc:/qml/MissionSettingsEditor.qml";
if (_metaDataMap.isEmpty()) {
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/MissionSettings.FactMetaData.json"), NULL /* metaDataParent */);
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/MissionSettings.FactMetaData.json"), nullptr /* metaDataParent */);
}
_plannedHomePositionAltitudeFact.setMetaData (_metaDataMap[_plannedHomePositionAltitudeName]);
......@@ -163,7 +163,7 @@ void MissionSettingsItem::appendMissionItems(QList<MissionItem*>& items, QObject
bool MissionSettingsItem::addMissionEndAction(QList<MissionItem*>& items, int seqNum, QObject* missionItemParent)
{
MissionItem* item = NULL;
MissionItem* item = nullptr;
// IMPORTANT NOTE: If anything changes here you must also change MissionSettingsItem::scanForMissionSettings
......
......@@ -13,7 +13,7 @@
#include "SettingsManager.h"
MissionSettingsTest::MissionSettingsTest(void)
: _settingsItem(NULL)
: _settingsItem(nullptr)
{
}
......
......@@ -24,7 +24,7 @@ class PlanElementController : public QObject
Q_OBJECT
public:
PlanElementController(PlanMasterController* masterController, QObject* parent = NULL);
PlanElementController(PlanMasterController* masterController, QObject* parent = nullptr);
~PlanElementController();
Q_PROPERTY(bool supported READ supported NOTIFY supportedChanged) ///< true: Element is supported by Vehicle
......
......@@ -24,8 +24,8 @@ QGC_LOGGING_CATEGORY(PlanManagerLog, "PlanManagerLog")
PlanManager::PlanManager(Vehicle* vehicle, MAV_MISSION_TYPE planType)
: _vehicle (vehicle)
, _planType (planType)
, _dedicatedLink (NULL)
, _ackTimeoutTimer (NULL)
, _dedicatedLink (nullptr)
, _ackTimeoutTimer (nullptr)
, _expectedAck (AckNone)
, _transactionInProgress (TransactionNone)
, _resumeMission (false)
......
......@@ -26,7 +26,7 @@ class PlanMasterController : public QObject
Q_OBJECT
public:
PlanMasterController(QObject* parent = NULL);
PlanMasterController(QObject* parent = nullptr);
~PlanMasterController();
Q_PROPERTY(MissionController* missionController READ missionController CONSTANT)
......
......@@ -17,7 +17,7 @@
#include "AppSettings.h"
PlanMasterControllerTest::PlanMasterControllerTest(void)
: _masterController(NULL)
: _masterController(nullptr)
{
}
......@@ -33,7 +33,7 @@ void PlanMasterControllerTest::init(void)
void PlanMasterControllerTest::cleanup(void)
{
delete _masterController;
_masterController = NULL;
_masterController = nullptr;
UnitTest::cleanup();
}
......
......@@ -17,9 +17,9 @@ class QGCFenceCircle : public QGCMapCircle
Q_OBJECT
public:
QGCFenceCircle(QObject* parent = NULL);
QGCFenceCircle(const QGeoCoordinate& center, double radius, bool inclusion, QObject* parent = NULL);
QGCFenceCircle(const QGCFenceCircle& other, QObject* parent = NULL);
QGCFenceCircle(QObject* parent = nullptr);
QGCFenceCircle(const QGeoCoordinate& center, double radius, bool inclusion, QObject* parent = nullptr);
QGCFenceCircle(const QGCFenceCircle& other, QObject* parent = nullptr);
const QGCFenceCircle& operator=(const QGCFenceCircle& other);
......
......@@ -17,8 +17,8 @@ class QGCFencePolygon : public QGCMapPolygon
Q_OBJECT
public:
QGCFencePolygon(bool inclusion, QObject* parent = NULL);
QGCFencePolygon(const QGCFencePolygon& other, QObject* parent = NULL);
QGCFencePolygon(bool inclusion, QObject* parent = nullptr);
QGCFencePolygon(const QGCFencePolygon& other, QObject* parent = nullptr);
const QGCFencePolygon& operator=(const QGCFencePolygon& other);
......
......@@ -20,8 +20,8 @@ class QGCMapPolyline : public QObject
Q_OBJECT
public:
QGCMapPolyline(QObject* parent = NULL);
QGCMapPolyline(const QGCMapPolyline& other, QObject* parent = NULL);
QGCMapPolyline(QObject* parent = nullptr);
QGCMapPolyline(const QGCMapPolyline& other, QObject* parent = nullptr);
const QGCMapPolyline& operator=(const QGCMapPolyline& other);
......
......@@ -64,7 +64,7 @@ RallyPoint::~RallyPoint()
void RallyPoint::_factSetup(void)
{
if (_metaDataMap.isEmpty()) {
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/RallyPoint.FactMetaData.json"), NULL /* metaDataParent */);
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/RallyPoint.FactMetaData.json"), nullptr /* metaDataParent */);
}
_longitudeFact.setMetaData(_metaDataMap[_longitudeFactName]);
......
......@@ -22,8 +22,8 @@ class RallyPoint : public QObject
Q_OBJECT
public:
RallyPoint(const QGeoCoordinate& coordinate, QObject* parent = NULL);
RallyPoint(const RallyPoint& other, QObject* parent = NULL);
RallyPoint(const QGeoCoordinate& coordinate, QObject* parent = nullptr);
RallyPoint(const RallyPoint& other, QObject* parent = nullptr);
~RallyPoint();
......
......@@ -37,7 +37,7 @@ RallyPointController::RallyPointController(PlanMasterController* masterControlle
: PlanElementController(masterController, parent)
, _rallyPointManager(_managerVehicle->rallyPointManager())
, _dirty(false)
, _currentRallyPoint(NULL)
, _currentRallyPoint(nullptr)
, _itemsRequested(false)
{
connect(&_points, &QmlObjectListModel::countChanged, this, &RallyPointController::_updateContainsItems);
......@@ -55,8 +55,8 @@ void RallyPointController::managerVehicleChanged(Vehicle* managerVehicle)
if (_managerVehicle) {
_rallyPointManager->disconnect(this);
_managerVehicle->disconnect(this);
_managerVehicle = NULL;
_rallyPointManager = NULL;
_managerVehicle = nullptr;
_rallyPointManager = nullptr;
}
_managerVehicle = managerVehicle;
......@@ -138,7 +138,7 @@ void RallyPointController::removeAll(void)
{
_points.clearAndDeleteContents();
setDirty(true);
setCurrentRallyPoint(NULL);
setCurrentRallyPoint(nullptr);
}
void RallyPointController::removeAllFromVehicle(void)
......@@ -268,7 +268,7 @@ void RallyPointController::removePoint(QObject* rallyPoint)
newIndex = qMax(newIndex, 0);
setCurrentRallyPoint(_points[newIndex]);
} else {
setCurrentRallyPoint(NULL);
setCurrentRallyPoint(nullptr);
}
}
......@@ -282,7 +282,7 @@ void RallyPointController::setCurrentRallyPoint(QObject* rallyPoint)
void RallyPointController::_setFirstPointCurrent(void)
{
setCurrentRallyPoint(_points.count() ? _points[0] : NULL);
setCurrentRallyPoint(_points.count() ? _points[0] : nullptr);
}
bool RallyPointController::containsItems(void) const
......
......@@ -26,7 +26,7 @@ class RallyPointController : public PlanElementController
Q_OBJECT
public:
RallyPointController(PlanMasterController* masterController, QObject* parent = NULL);
RallyPointController(PlanMasterController* masterController, QObject* parent = nullptr);
~RallyPointController();
Q_PROPERTY(QmlObjectListModel* points READ points CONSTANT)
......
......@@ -21,7 +21,7 @@ class Section : public QObject
Q_OBJECT
public:
Section(Vehicle* vehicle, QObject* parent = NULL)
Section(Vehicle* vehicle, QObject* parent = nullptr)
: QObject(parent)
, _vehicle(vehicle)
{
......
......@@ -11,7 +11,7 @@
#include "SurveyComplexItem.h"
SectionTest::SectionTest(void)
: _simpleItem(NULL)
: _simpleItem(nullptr)
{
}
......@@ -48,7 +48,7 @@ void SectionTest::cleanup(void)
void SectionTest::_createSpy(Section* section, MultiSignalSpy** sectionSpy)
{
*sectionSpy = NULL;
*sectionSpy = nullptr;
MultiSignalSpy* spy = new MultiSignalSpy();
QCOMPARE(spy->init(section, rgSectionSignals, cSectionSignals), true);
*sectionSpy = spy;
......
......@@ -24,7 +24,7 @@ SpeedSection::SpeedSection(Vehicle* vehicle, QObject* parent)
, _flightSpeedFact (0, _flightSpeedName, FactMetaData::valueTypeDouble)
{
if (_metaDataMap.isEmpty()) {
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/SpeedSection.FactMetaData.json"), NULL /* metaDataParent */);
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/SpeedSection.FactMetaData.json"), nullptr /* metaDataParent */);
}
double flightSpeed = 0;
......
......@@ -18,7 +18,7 @@ class SpeedSection : public Section
Q_OBJECT
public:
SpeedSection(Vehicle* vehicle, QObject* parent = NULL);
SpeedSection(Vehicle* vehicle, QObject* parent = nullptr);
Q_PROPERTY(bool specifyFlightSpeed READ specifyFlightSpeed WRITE setSpecifyFlightSpeed NOTIFY specifyFlightSpeedChanged)
Q_PROPERTY(Fact* flightSpeed READ flightSpeed CONSTANT)
......
......@@ -10,9 +10,9 @@
#include "SpeedSectionTest.h"
SpeedSectionTest::SpeedSectionTest(void)
: _spySpeed(NULL)
, _spySection(NULL)
, _speedSection(NULL)
: _spySpeed(nullptr)
, _spySection(nullptr)
, _speedSection(nullptr)
{
}
......@@ -39,7 +39,7 @@ void SpeedSectionTest::cleanup(void)
void SpeedSectionTest::_createSpy(SpeedSection* speedSection, MultiSignalSpy** speedSpy)
{
*speedSpy = NULL;
*speedSpy = nullptr;
MultiSignalSpy* spy = new MultiSignalSpy();
QCOMPARE(spy->init(speedSection, rgSpeedSignals, cSpeedSignals), true);
*speedSpy = spy;
......@@ -193,7 +193,7 @@ void SpeedSectionTest::_testScanForSection(void)
double flightSpeed = 10.123456;
MissionItem validSpeedItem(0, MAV_CMD_DO_CHANGE_SPEED, MAV_FRAME_MISSION, _offlineVehicle->multiRotor() ? 1 : 0, flightSpeed, -1, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleItem(_offlineVehicle, false /* flyView */, validSpeedItem, NULL);
SimpleMissionItem simpleItem(_offlineVehicle, false /* flyView */, validSpeedItem, nullptr);
MissionItem& simpleMissionItem = simpleItem.missionItem();
visualItems.append(&simpleItem);
scanIndex = 0;
......@@ -264,7 +264,7 @@ void SpeedSectionTest::_testScanForSection(void)
// Valid item in wrong position
MissionItem waypointMissionItem(0, MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT, 0, 0, 0, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleWaypointItem(_offlineVehicle, false /* flyView */, waypointMissionItem, NULL);
SimpleMissionItem simpleWaypointItem(_offlineVehicle, false /* flyView */, waypointMissionItem, nullptr);
simpleMissionItem = validSpeedItem;
visualItems.append(&simpleWaypointItem);
visualItems.append(&simpleMissionItem);
......
......@@ -11,7 +11,7 @@
#include "QGCApplication.h"
SurveyComplexItemTest::SurveyComplexItemTest(void)
: _offlineVehicle(NULL)
: _offlineVehicle(nullptr)
{
_polyPoints << QGeoCoordinate(47.633550640000003, -122.08982199) << QGeoCoordinate(47.634129020000003, -122.08887249) <<
QGeoCoordinate(47.633619320000001, -122.08811074) << QGeoCoordinate(47.633189139999999, -122.08900124);
......
......@@ -11,7 +11,7 @@
#include "QGCApplication.h"
TransectStyleComplexItemTest::TransectStyleComplexItemTest(void)
: _offlineVehicle(NULL)
: _offlineVehicle(nullptr)
{
_polygonVertices << QGeoCoordinate(47.633550640000003, -122.08982199)
<< QGeoCoordinate(47.634129020000003, -122.08887249)
......
......@@ -83,7 +83,7 @@ class TransectStyleItem : public TransectStyleComplexItem
Q_OBJECT
public:
TransectStyleItem(Vehicle* vehicle, QObject* parent = NULL);
TransectStyleItem(Vehicle* vehicle, QObject* parent = nullptr);
// Overrides from ComplexMissionItem
QString mapVisualQML (void) const final { return QString(); }
......
......@@ -12,7 +12,7 @@
#include "QGCApplication.h"
VisualMissionItemTest::VisualMissionItemTest(void)
: _offlineVehicle(NULL)
: _offlineVehicle(nullptr)
{
}
......@@ -60,7 +60,7 @@ void VisualMissionItemTest::cleanup(void)
void VisualMissionItemTest::_createSpy(SimpleMissionItem* simpleItem, MultiSignalSpy** visualSpy)
{
*visualSpy = NULL;
*visualSpy = nullptr;
MultiSignalSpy* spy = new MultiSignalSpy();
QCOMPARE(spy->init(simpleItem, rgVisualItemSignals, cVisualItemSignals), true);
*visualSpy = spy;
......
......@@ -15,10 +15,10 @@ QGCPositionManager::QGCPositionManager(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool (app, toolbox)
, _updateInterval (0)
, _gcsHeading (NAN)
, _currentSource (NULL)
, _defaultSource (NULL)
, _nmeaSource (NULL)
, _simulatedSource (NULL)
, _currentSource (nullptr)
, _defaultSource (nullptr)
, _nmeaSource (nullptr)
, _simulatedSource (nullptr)
{
}
......
......@@ -16,7 +16,7 @@
SimulatedPosition::simulated_motion_s SimulatedPosition::_simulated_motion[5] = {{0,250},{0,0},{0, -250},{-250, 0},{0,0}};
SimulatedPosition::SimulatedPosition()
: QGeoPositionInfoSource(NULL),
: QGeoPositionInfoSource(nullptr),
lat_int(47.3977420*1e7),
lon_int(8.5455941*1e7),
_step_cnt(0),
......
......@@ -23,7 +23,7 @@ class QGCComboBox : public QComboBox {
Q_OBJECT
public:
QGCComboBox(QWidget* parent = NULL);
QGCComboBox(QWidget* parent = nullptr);
/// @brief Sets the current index on the combo. Signals activated, as well as currentIndexChanged.
void simulateUserSetCurrentIndex(int index);
......
......@@ -18,7 +18,7 @@ class QGCFileDownload : public QNetworkAccessManager
Q_OBJECT
public:
QGCFileDownload(QObject* parent = NULL);
QGCFileDownload(QObject* parent = nullptr);
/// Download the specified remote file.
/// @param remoteFile File to download. Can be http address or file system path.
......
......@@ -25,7 +25,7 @@ QGC_LOGGING_CATEGORY(GeotaggingLog, "GeotaggingLog")
QGC_LOGGING_CATEGORY(RTKGPSLog, "RTKGPSLog")
QGC_LOGGING_CATEGORY(GuidedActionsControllerLog, "GuidedActionsControllerLog")
QGCLoggingCategoryRegister* _instance = NULL;
QGCLoggingCategoryRegister* _instance = nullptr;
const char* QGCLoggingCategoryRegister::_filterRulesSettingsGroup = "LoggingFilters";
QGCLoggingCategoryRegister* QGCLoggingCategoryRegister::instance(void)
......
......@@ -47,7 +47,7 @@ class QGCMapPalette : public QObject
Q_PROPERTY(QColor thumbJoystick READ thumbJoystick NOTIFY paletteChanged)
public:
QGCMapPalette(QObject* parent = NULL);
QGCMapPalette(QObject* parent = nullptr);
/// Text color
QColor text(void) const { return _text[_lightColors ? 0 : 1]; }
......
......@@ -18,7 +18,7 @@ class QGCQGeoCoordinate : public QObject
Q_OBJECT
public:
QGCQGeoCoordinate(const QGeoCoordinate& coord, QObject* parent = NULL);
QGCQGeoCoordinate(const QGeoCoordinate& coord, QObject* parent = nullptr);
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
......
......@@ -28,7 +28,7 @@ public:
// QStandardPaths::TempLocation directory.
// @param template Template for file name following QTemporaryFile rules. Template should NOT include
// directory path, only file name.
QGCTemporaryFile(const QString& fileTemplate, QObject* parent = NULL);
QGCTemporaryFile(const QString& fileTemplate, QObject* parent = nullptr);
/// @brief Opens the file in ReadWrite mode.
/// @returns false - open failed
......
......@@ -19,8 +19,8 @@ class CoordinateVector : public QObject
Q_OBJECT
public:
CoordinateVector(QObject* parent = NULL);
CoordinateVector(const QGeoCoordinate& coordinate1, const QGeoCoordinate& coordinate2, QObject* parent = NULL);
CoordinateVector(QObject* parent = nullptr);
CoordinateVector(const QGeoCoordinate& coordinate1, const QGeoCoordinate& coordinate2, QObject* parent = nullptr);
Q_PROPERTY(QGeoCoordinate coordinate1 MEMBER _coordinate1 NOTIFY coordinate1Changed)
Q_PROPERTY(QGeoCoordinate coordinate2 MEMBER _coordinate2 NOTIFY coordinate2Changed)
......
......@@ -29,7 +29,7 @@ EditPositionDialogController::EditPositionDialogController(void)
, _northingFact (0, _northingFactName, FactMetaData::valueTypeDouble)
{
if (_metaDataMap.isEmpty()) {
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/EditPositionDialog.FactMetaData.json"), NULL /* QObject parent */);
_metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/EditPositionDialog.FactMetaData.json"), nullptr /* QObject parent */);
}
_latitudeFact.setMetaData (_metaDataMap[_latitudeFactName]);
......
......@@ -48,11 +48,11 @@ QGCCachedTileSet::QGCCachedTileSet(const QString& name)
, _downloading(false)
, _id(0)
, _type(UrlFactory::Invalid)
, _networkManager(NULL)
, _networkManager(nullptr)
, _errorCount(0)
, _noMoreTiles(false)
, _batchRequested(false)
, _manager(NULL)
, _manager(nullptr)
, _selected(false)
{
......
......@@ -42,7 +42,7 @@ UrlFactory::UrlFactory()
: _timeout(5 * 1000)
#ifndef QGC_NO_GOOGLE_MAPS
, _googleVersionRetrieved(false)
, _googleReply(NULL)
, _googleReply(nullptr)
#endif
{
QStringList langs = QLocale::system().uiLanguages();
......@@ -512,7 +512,7 @@ UrlFactory::_networkReplyError(QNetworkReply::NetworkError error)
if(_googleReply)
{
_googleReply->deleteLater();
_googleReply = NULL;
_googleReply = nullptr;
}
}
#endif
......@@ -521,7 +521,7 @@ UrlFactory::_networkReplyError(QNetworkReply::NetworkError error)
void
UrlFactory::_replyDestroyed()
{
_googleReply = NULL;
_googleReply = nullptr;
}
#endif
......@@ -563,7 +563,7 @@ UrlFactory::_googleVersionCompleted()
_versionGoogleTerrain = QString("t@%1,r@%2").arg(gc[1]).arg(gc[2]);
}
_googleReply->deleteLater();
_googleReply = NULL;
_googleReply = nullptr;
}
#endif
......
......@@ -675,7 +675,7 @@ QGCCacheWorker::_importSets(QGCMapTask* mtask)
//-- Close and delete old database
if(_db) {
delete _db;
_db = NULL;
_db = nullptr;
QSqlDatabase::removeDatabase(kSession);
}
QFile file(_databasePath);
......@@ -989,7 +989,7 @@ QGCCacheWorker::_init()
_failed = true;
}
delete _db;
_db = NULL;
_db = nullptr;
QSqlDatabase::removeDatabase(kSession);
} else {
qCritical() << "Could not find suitable cache directory.";
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
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