diff --git a/src/Camera/QGCCameraManager.cc b/src/Camera/QGCCameraManager.cc index bcf3cce4be8bd63b55f584c217c83fa2dc3ba6d2..e61c62f952c9821bfed3d3d9ab9c92b1ed06b608 100644 --- a/src/Camera/QGCCameraManager.cc +++ b/src/Camera/QGCCameraManager.cc @@ -12,8 +12,9 @@ QGC_LOGGING_CATEGORY(CameraManagerLog, "CameraManagerLog") //----------------------------------------------------------------------------- -QGCCameraManager::CameraStruct::CameraStruct(QObject* parent) +QGCCameraManager::CameraStruct::CameraStruct(QObject* parent, uint8_t compID_) : QObject(parent) + , compID(compID_) { } @@ -112,7 +113,7 @@ QGCCameraManager::_handleHeartbeat(const mavlink_message_t &message) QString sCompID = QString::number(message.compid); if(!_cameraInfoRequest.contains(sCompID)) { qCDebug(CameraManagerLog) << "Hearbeat from " << message.compid; - CameraStruct* pInfo = new CameraStruct(this); + CameraStruct* pInfo = new CameraStruct(this, message.compid); pInfo->lastHeartbeat.start(); _cameraInfoRequest[sCompID] = pInfo; //-- Request camera info @@ -226,19 +227,22 @@ QGCCameraManager::_cameraTimeout() //-- Has the camera stopped talking to us? if(pInfo->lastHeartbeat.elapsed() > 5000) { //-- Camera is gone. Remove it. + bool autoStream = false; QGCCameraControl* pCamera = _findCamera(pInfo->compID); - qWarning() << "Camera" << pCamera->modelName() << "stopped transmitting. Removing from list."; - int idx = _cameraLabels.indexOf(pCamera->modelName()); - if(idx >= 0) { - _cameraLabels.removeAt(idx); - } - idx = _cameras.indexOf(pCamera); - if(idx >= 0) { - _cameras.removeAt(idx); + if(pCamera) { + qWarning() << "Camera" << pCamera->modelName() << "stopped transmitting. Removing from list."; + int idx = _cameraLabels.indexOf(pCamera->modelName()); + if(idx >= 0) { + _cameraLabels.removeAt(idx); + } + idx = _cameras.indexOf(pCamera); + if(idx >= 0) { + _cameras.removeAt(idx); + } + autoStream = pCamera->autoStream(); + pCamera->deleteLater(); + delete pInfo; } - bool autoStream = pCamera->autoStream(); - pCamera->deleteLater(); - delete pInfo; _cameraInfoRequest.remove(sCompID); emit cameraLabelsChanged(); //-- If we have another camera, switch current camera. diff --git a/src/Camera/QGCCameraManager.h b/src/Camera/QGCCameraManager.h index 8d52976d7a2359360401b2b1f0a0d48fce7c05ae..9dce028116f9d17b13c2d0a0284b2bc378c23b4c 100644 --- a/src/Camera/QGCCameraManager.h +++ b/src/Camera/QGCCameraManager.h @@ -76,7 +76,7 @@ protected: class CameraStruct : public QObject { public: - CameraStruct(QObject* parent); + CameraStruct(QObject* parent, uint8_t compID_); QTime lastHeartbeat; bool infoReceived = false; bool gaveUp = false;