Browse Source

Merge pull request #7227 from mavlink/crashOnCameraDisconnect

Fix crash bug that could occur when reconnecting a camera.
QGC4.4
Gus Grubba 6 years ago committed by GitHub
parent
commit
98643b5f65
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 10
      src/Camera/QGCCameraManager.cc
  2. 2
      src/Camera/QGCCameraManager.h

10
src/Camera/QGCCameraManager.cc

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

2
src/Camera/QGCCameraManager.h

@ -76,7 +76,7 @@ protected:
class CameraStruct : public QObject { class CameraStruct : public QObject {
public: public:
CameraStruct(QObject* parent); CameraStruct(QObject* parent, uint8_t compID_);
QTime lastHeartbeat; QTime lastHeartbeat;
bool infoReceived = false; bool infoReceived = false;
bool gaveUp = false; bool gaveUp = false;

Loading…
Cancel
Save