From 1703a30c7ea4b423c6bb40be60c9b17605987bd7 Mon Sep 17 00:00:00 2001 From: Gus Grubba Date: Wed, 26 Jul 2017 14:15:20 -0400 Subject: [PATCH] c++ ownership and memory guards --- src/Camera/QGCCameraControl.cc | 25 +++++++++++++++++++++---- src/Camera/QGCCameraIO.cc | 10 +++++++--- src/Camera/QGCCameraManager.cc | 2 ++ src/FactSystem/Fact.cc | 2 +- src/uas/UAS.cc | 2 +- src/uas/UASInterface.h | 2 ++ 6 files changed, 34 insertions(+), 9 deletions(-) diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc index c74e72c67..198b7f0f9 100644 --- a/src/Camera/QGCCameraControl.cc +++ b/src/Camera/QGCCameraControl.cc @@ -118,6 +118,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh , _cameraMode(CAM_MODE_UNDEFINED) , _video_status(VIDEO_CAPTURE_STATUS_UNDEFINED) { + QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); memcpy(&_info, info, sizeof(mavlink_camera_information_t)); connect(this, &QGCCameraControl::dataReady, this, &QGCCameraControl::_dataReady); _vendor = QString((const char*)(void*)&info->vendor_name[0]); @@ -533,6 +534,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList) } //-- Build metadata FactMetaData* metaData = new FactMetaData(factType, factName, this); + QQmlEngine::setObjectOwnership(metaData, QQmlEngine::CppOwnership); metaData->setShortDescription(description); metaData->setLongDescription(description); //-- Options (enums) @@ -560,6 +562,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList) if(exclusions.size()) { qCDebug(CameraControlLogVerbose) << "New exclusions:" << factName << optValue << exclusions; QGCCameraOptionExclusion* pExc = new QGCCameraOptionExclusion(this, factName, optValue, exclusions); + QQmlEngine::setObjectOwnership(pExc, QQmlEngine::CppOwnership); _valueExclusions.append(pExc); } //-- Check for range rules @@ -589,9 +592,11 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList) } else { _nameToFactMetaDataMap[factName] = metaData; Fact* pFact = new Fact(_compID, factName, factType, this); + QQmlEngine::setObjectOwnership(pFact, QQmlEngine::CppOwnership); pFact->setMetaData(metaData); pFact->_containerSetRawValue(metaData->rawDefaultValue()); QGCCameraParamIO* pIO = new QGCCameraParamIO(this, pFact, _vehicle); + QQmlEngine::setObjectOwnership(pIO, QQmlEngine::CppOwnership); _paramIO[factName] = pIO; _addFact(pFact, factName); } @@ -695,8 +700,12 @@ void QGCCameraControl::_requestAllParameters() { //-- Reset receive list - foreach(QString pramName, _paramIO.keys()) { - _paramIO[pramName]->setParamRequest(); + foreach(QString paramName, _paramIO.keys()) { + if(_paramIO[paramName]) { + _paramIO[paramName]->setParamRequest(); + } else { + qCritical() << "QGCParamIO is NULL" << paramName; + } } MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); mavlink_message_t msg; @@ -729,7 +738,11 @@ QGCCameraControl::handleParamAck(const mavlink_param_ext_ack_t& ack) qCWarning(CameraControlLog) << "Received PARAM_EXT_ACK for unknown param:" << paramName; return; } - _paramIO[paramName]->handleParamAck(ack); + if(_paramIO[paramName]) { + _paramIO[paramName]->handleParamAck(ack); + } else { + qCritical() << "QGCParamIO is NULL" << paramName; + } } //----------------------------------------------------------------------------- @@ -741,7 +754,11 @@ QGCCameraControl::handleParamValue(const mavlink_param_ext_value_t& value) qCWarning(CameraControlLog) << "Received PARAM_EXT_VALUE for unknown param:" << paramName; return; } - _paramIO[paramName]->handleParamValue(value); + if(_paramIO[paramName]) { + _paramIO[paramName]->handleParamValue(value); + } else { + qCritical() << "QGCParamIO is NULL" << paramName; + } } //----------------------------------------------------------------------------- diff --git a/src/Camera/QGCCameraIO.cc b/src/Camera/QGCCameraIO.cc index 82aef4cff..3b3ba8ab9 100644 --- a/src/Camera/QGCCameraIO.cc +++ b/src/Camera/QGCCameraIO.cc @@ -21,6 +21,7 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl , _requestRetries(0) , _done(false) { + QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); _paramWriteTimer.setSingleShot(true); _paramWriteTimer.setInterval(1000); _paramRequestTimer.setSingleShot(true); @@ -94,10 +95,10 @@ void QGCCameraParamIO::_sendParameter() { //-- TODO: We should use something other than mavlink_param_union_t for PARAM_EXT_SET - mavlink_param_ext_set_t p; + mavlink_param_ext_set_t p; + memset(&p, 0, sizeof(mavlink_param_ext_set_t)); mavlink_param_union_t union_value; mavlink_message_t msg; - memset(&p, 0, sizeof(mavlink_param_ext_set_t)); FactMetaData::ValueType_t factType = _fact->type(); p.param_type = _mavParamType; switch (factType) { @@ -247,6 +248,9 @@ QGCCameraParamIO::_paramRequestTimeout() } else { //-- Request it again qCDebug(CameraIOLog) << "Param request retry:" << _fact->name(); + char param_id[MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN + 1]; + memset(param_id, 0, sizeof(param_id)); + strncpy(param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN); mavlink_message_t msg; mavlink_msg_param_ext_request_read_pack_chan( _pMavlink->getSystemId(), @@ -255,7 +259,7 @@ QGCCameraParamIO::_paramRequestTimeout() &msg, _vehicle->id(), _control->compID(), - _fact->name().toStdString().c_str(), + param_id, -1); _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); _paramRequestTimer.start(); diff --git a/src/Camera/QGCCameraManager.cc b/src/Camera/QGCCameraManager.cc index 4dd272a5e..e75852d62 100644 --- a/src/Camera/QGCCameraManager.cc +++ b/src/Camera/QGCCameraManager.cc @@ -16,6 +16,7 @@ QGCCameraManager::QGCCameraManager(Vehicle *vehicle) , _vehicleReadyState(false) , _currentTask(0) { + QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); qCDebug(CameraManagerLog) << "QGCCameraManager Created"; connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &QGCCameraManager::_vehicleReady); connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &QGCCameraManager::_mavlinkMessageReceived); @@ -121,6 +122,7 @@ QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message) qCDebug(CameraManagerLog) << "_handleCameraInfo:" << (const char*)(void*)&info.model_name[0] << (const char*)(void*)&info.vendor_name[0]; QGCCameraControl* pCamera = _vehicle->firmwarePlugin()->createCameraControl(&info, _vehicle, message.compid, this); if(pCamera) { + QQmlEngine::setObjectOwnership(pCamera, QQmlEngine::CppOwnership); _cameras.append(pCamera); emit camerasChanged(); } diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index db007e8e4..ff1cf10d7 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -31,7 +31,7 @@ Fact::Fact(QObject* parent) FactMetaData* metaData = new FactMetaData(_type, this); setMetaData(metaData); - // Better sage than sorry on object ownership + // Better safe than sorry on object ownership QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); } diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 93acba906..bdcbe1f6b 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -139,9 +139,9 @@ UAS::UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * fi #ifndef __mobile__ connect(_vehicle, &Vehicle::mavlinkMessageReceived, &fileManager, &FileManager::receiveMessage); + color = UASInterface::getNextColor(); #endif - color = UASInterface::getNextColor(); } /** diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 0bed211c8..af0257e7f 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -61,6 +61,7 @@ public: * @return The next color in the color map. The map holds 20 colors and starts from the beginning * if the colors are exceeded. */ +#if !defined(__mobile__) static QColor getNextColor() { /* Create color map */ static QList colors = QList() @@ -91,6 +92,7 @@ public: nextColor++; return colors[nextColor];//return the next color } +#endif virtual QMap getComponents() = 0; -- 2.22.0