Commit 5776de49 authored by Gus Grubba's avatar Gus Grubba

Handle mode change through (known) parameter (if it exists)

Keep track of recording time if camera doesn't provide it.
Make sure camera info is received (if camera ACKs the request)
Keep track of camera's heartbeat. Remove camera if not heard from after a while.
Update MAVLink
parent f5d6ff4d
Subproject commit 90d9b285e01fe8bfa3b4e8868ca71c5537d43302
Subproject commit c847642263deefa584691eebade8b29a25264442
This diff is collapsed.
......@@ -147,6 +147,7 @@ public:
Q_PROPERTY(Fact* shutter READ shutter NOTIFY parametersReady)
Q_PROPERTY(Fact* aperture READ aperture NOTIFY parametersReady)
Q_PROPERTY(Fact* wb READ wb NOTIFY parametersReady)
Q_PROPERTY(Fact* mode READ mode NOTIFY parametersReady)
Q_PROPERTY(QStringList activeSettings READ activeSettings NOTIFY activeSettingsChanged)
Q_PROPERTY(VideoStatus videoStatus READ videoStatus NOTIFY videoStatusChanged)
......@@ -159,6 +160,8 @@ public:
Q_PROPERTY(bool autoStream READ autoStream NOTIFY autoStreamChanged)
Q_PROPERTY(QmlObjectListModel* streams READ streams NOTIFY streamsChanged)
Q_PROPERTY(QGCVideoStreamInfo* currentStreamInstance READ currentStreamInstance NOTIFY currentStreamChanged)
Q_PROPERTY(quint32 recordTime READ recordTime NOTIFY recordTimeChanged)
Q_PROPERTY(QString recordTimeStr READ recordTimeStr NOTIFY recordTimeChanged)
Q_INVOKABLE virtual void setVideoMode ();
Q_INVOKABLE virtual void setPhotoMode ();
......@@ -213,6 +216,8 @@ public:
virtual int currentStream () { return _currentStream; }
virtual void setCurrentStream (int stream);
virtual bool autoStream ();
virtual quint32 recordTime () { return _recordTime; }
virtual QString recordTimeStr ();
virtual Fact* exposureMode ();
virtual Fact* ev ();
......@@ -220,6 +225,7 @@ public:
virtual Fact* shutter ();
virtual Fact* aperture ();
virtual Fact* wb ();
virtual Fact* mode ();
virtual void setZoomLevel (qreal level);
virtual void setFocusLevel (qreal level);
......@@ -261,6 +267,7 @@ signals:
void streamsChanged ();
void currentStreamChanged ();
void autoStreamChanged ();
void recordTimeChanged ();
protected:
virtual void _setVideoStatus (VideoStatus status);
......@@ -283,6 +290,8 @@ protected slots:
virtual void _paramDone ();
virtual void _streamTimeout ();
virtual void _streamStatusTimeout ();
virtual void _recTimerHandler ();
virtual void _checkForVideoStreams ();
private:
bool _handleLocalization (QByteArray& bytes);
......@@ -336,6 +345,9 @@ protected:
int _storageInfoRetries = 0;
int _captureInfoRetries = 0;
bool _resetting = false;
QTimer _recTimer;
QTime _recTime;
uint32_t _recordTime = 0;
//-- Parameters that require a full update
QMap<QString, QStringList> _requestUpdates;
QStringList _updatesToRequest;
......
......@@ -11,6 +11,12 @@
QGC_LOGGING_CATEGORY(CameraManagerLog, "CameraManagerLog")
//-----------------------------------------------------------------------------
QGCCameraManager::CameraStruct::CameraStruct(QObject* parent)
: QObject(parent)
{
}
//-----------------------------------------------------------------------------
QGCCameraManager::QGCCameraManager(Vehicle *vehicle)
: _vehicle(vehicle)
......@@ -19,8 +25,11 @@ QGCCameraManager::QGCCameraManager(Vehicle *vehicle)
qCDebug(CameraManagerLog) << "QGCCameraManager Created";
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &QGCCameraManager::_vehicleReady);
connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &QGCCameraManager::_mavlinkMessageReceived);
connect(&_cameraTimer, &QTimer::timeout, this, &QGCCameraManager::_cameraTimeout);
_cameraTimer.setSingleShot(false);
_lastZoomChange.start();
_lastCameraChange.start();
_cameraTimer.start(500);
}
//-----------------------------------------------------------------------------
......@@ -97,12 +106,36 @@ QGCCameraManager::_handleHeartbeat(const mavlink_message_t &message)
{
mavlink_heartbeat_t heartbeat;
mavlink_msg_heartbeat_decode(&message, &heartbeat);
//-- If this heartbeat is from a different node within the vehicle
//-- If this heartbeat is from a different component within the vehicle
if(_vehicleReadyState && _vehicle->id() == message.sysid && _vehicle->defaultComponentId() != message.compid) {
if(!_cameraInfoRequested.contains(message.compid)) {
_cameraInfoRequested[message.compid] = true;
//-- First time hearing from this one?
if(!_cameraInfoRequest.contains(message.compid)) {
CameraStruct* pInfo = new CameraStruct(this);
pInfo->lastHeartbeat.start();
_cameraInfoRequest[message.compid] = pInfo;
//-- Request camera info
_requestCameraInfo(message.compid);
} else {
//-- Check if we have indeed received the camera info
if(_cameraInfoRequest[message.compid]->infoReceived) {
//-- We have it. Just update the heartbeat timeout
_cameraInfoRequest[message.compid]->lastHeartbeat.start();
} else {
//-- Try again. Maybe.
if(_cameraInfoRequest[message.compid]->lastHeartbeat.elapsed() > 2000) {
if(_cameraInfoRequest[message.compid]->tryCount > 3) {
if(!_cameraInfoRequest[message.compid]->gaveUp) {
_cameraInfoRequest[message.compid]->gaveUp = true;
qWarning() << "Giving up requesting camera info from" << _vehicle->id() << message.compid;
}
} else {
_cameraInfoRequest[message.compid]->tryCount++;
//-- Request camera info. Again. It could be something other than a camera, in which
// case, we won't ever receive it.
_requestCameraInfo(message.compid);
}
}
}
}
}
}
......@@ -155,9 +188,9 @@ void
QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
{
//-- Have we requested it?
if(_cameraInfoRequested.contains(message.compid) && _cameraInfoRequested[message.compid]) {
if(_cameraInfoRequest.contains(message.compid) && !_cameraInfoRequest[message.compid]->infoReceived) {
//-- Flag it as done
_cameraInfoRequested[message.compid] = false;
_cameraInfoRequest[message.compid]->infoReceived = true;
mavlink_camera_information_t info;
mavlink_msg_camera_information_decode(&message, &info);
qCDebug(CameraManagerLog) << "_handleCameraInfo:" << reinterpret_cast<const char*>(info.model_name) << reinterpret_cast<const char*>(info.vendor_name) << "Comp ID:" << message.compid;
......@@ -172,6 +205,51 @@ QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_cameraTimeout()
{
//-- Iterate cameras
for(int i = 0; i < _cameraInfoRequest.count(); i++) {
if(_cameraInfoRequest[i]) {
//-- Have we received a camera info message?
if(_cameraInfoRequest[i]->infoReceived) {
//-- Has the camera stopped talking to us?
if(_cameraInfoRequest[i]->lastHeartbeat.elapsed() > 5000) {
//-- Camera is gone. Remove it.
QGCCameraControl* pCamera = _findCamera(i);
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);
}
bool autoStream = pCamera->autoStream();
pCamera->deleteLater();
delete _cameraInfoRequest[i];
_cameraInfoRequest.remove(i);
emit cameraLabelsChanged();
//-- If we have another camera, switch current camera.
if(_cameras.count()) {
setCurrentCamera(0);
} else {
//-- We're out of cameras
emit camerasChanged();
if(autoStream) {
emit streamChanged();
}
}
//-- Exit loop.
return;
}
}
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleCaptureStatus(const mavlink_message_t &message)
......
......@@ -27,10 +27,10 @@ public:
QGCCameraManager(Vehicle* vehicle);
virtual ~QGCCameraManager();
Q_PROPERTY(QmlObjectListModel* cameras READ cameras NOTIFY camerasChanged)
Q_PROPERTY(QStringList cameraLabels READ cameraLabels NOTIFY cameraLabelsChanged)
Q_PROPERTY(int currentCamera READ currentCamera WRITE setCurrentCamera NOTIFY currentCameraChanged)
Q_PROPERTY(QmlObjectListModel* cameras READ cameras NOTIFY camerasChanged)
Q_PROPERTY(QStringList cameraLabels READ cameraLabels NOTIFY cameraLabelsChanged)
Q_PROPERTY(QGCCameraControl* currentCameraInstance READ currentCameraInstance NOTIFY currentCameraChanged)
Q_PROPERTY(int currentCamera READ currentCamera WRITE setCurrentCamera NOTIFY currentCameraChanged)
//-- Return a list of cameras provided by this vehicle
virtual QmlObjectListModel* cameras () { return &_cameras; }
......@@ -57,6 +57,7 @@ protected slots:
virtual void _stepZoom (int direction);
virtual void _stepCamera (int direction);
virtual void _stepStream (int direction);
virtual void _cameraTimeout ();
protected:
virtual QGCCameraControl* _findCamera (int id);
......@@ -72,14 +73,25 @@ protected:
virtual void _handleVideoStreamStatus(const mavlink_message_t& message);
protected:
class CameraStruct : public QObject {
public:
CameraStruct(QObject* parent);
QTime lastHeartbeat;
bool infoReceived = false;
bool gaveUp = false;
int tryCount = 0;
};
Vehicle* _vehicle = nullptr;
Joystick* _activeJoystick = nullptr;
bool _vehicleReadyState = false;
int _currentTask = 0;
QmlObjectListModel _cameras;
QStringList _cameraLabels;
QMap<int, bool> _cameraInfoRequested;
int _currentCamera = 0;
QTime _lastZoomChange;
QTime _lastCameraChange;
QTimer _cameraTimer;
QMap<int, CameraStruct*> _cameraInfoRequest;
};
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