QGCCameraManager.cc 15.2 KB
Newer Older
1 2 3 4 5 6 7 8 9
/*!
 * @file
 *   @brief Camera Controller
 *   @author Gus Grubba <mavlink@grubba.com>
 *
 */

#include "QGCApplication.h"
#include "QGCCameraManager.h"
10
#include "JoystickManager.h"
11 12 13

QGC_LOGGING_CATEGORY(CameraManagerLog, "CameraManagerLog")

14 15 16 17 18 19
//-----------------------------------------------------------------------------
QGCCameraManager::CameraStruct::CameraStruct(QObject* parent)
    : QObject(parent)
{
}

20 21 22 23
//-----------------------------------------------------------------------------
QGCCameraManager::QGCCameraManager(Vehicle *vehicle)
    : _vehicle(vehicle)
{
24
    QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
25 26 27
    qCDebug(CameraManagerLog) << "QGCCameraManager Created";
    connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &QGCCameraManager::_vehicleReady);
    connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &QGCCameraManager::_mavlinkMessageReceived);
28 29
    connect(&_cameraTimer, &QTimer::timeout, this, &QGCCameraManager::_cameraTimeout);
    _cameraTimer.setSingleShot(false);
30 31
    _lastZoomChange.start();
    _lastCameraChange.start();
32
    _cameraTimer.start(500);
33 34 35 36 37 38 39
}

//-----------------------------------------------------------------------------
QGCCameraManager::~QGCCameraManager()
{
}

Gus Grubba's avatar
Gus Grubba committed
40 41 42 43 44 45 46
//-----------------------------------------------------------------------------
void
QGCCameraManager::setCurrentCamera(int sel)
{
    if(sel != _currentCamera && sel >= 0 && sel < _cameras.count()) {
        _currentCamera = sel;
        emit currentCameraChanged();
47
        emit streamChanged();
Gus Grubba's avatar
Gus Grubba committed
48 49 50
    }
}

51 52 53 54 55 56 57 58
//-----------------------------------------------------------------------------
void
QGCCameraManager::_vehicleReady(bool ready)
{
    qCDebug(CameraManagerLog) << "_vehicleReady(" << ready << ")";
    if(ready) {
        if(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle() == _vehicle) {
            _vehicleReadyState = true;
59 60 61
            JoystickManager *pJoyMgr = qgcApp()->toolbox()->joystickManager();
            _activeJoystickChanged(pJoyMgr->activeJoystick());
            connect(pJoyMgr, &JoystickManager::activeJoystickChanged, this, &QGCCameraManager::_activeJoystickChanged);
62 63 64 65 66 67 68 69
        }
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraManager::_mavlinkMessageReceived(const mavlink_message_t& message)
{
Gus Grubba's avatar
Gus Grubba committed
70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92
    if(message.sysid == _vehicle->id()) {
        switch (message.msgid) {
            case MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS:
                _handleCaptureStatus(message);
                break;
            case MAVLINK_MSG_ID_STORAGE_INFORMATION:
                _handleStorageInfo(message);
                break;
            case MAVLINK_MSG_ID_HEARTBEAT:
                _handleHeartbeat(message);
                break;
            case MAVLINK_MSG_ID_CAMERA_INFORMATION:
                _handleCameraInfo(message);
                break;
            case MAVLINK_MSG_ID_CAMERA_SETTINGS:
                _handleCameraSettings(message);
                break;
            case MAVLINK_MSG_ID_PARAM_EXT_ACK:
                _handleParamAck(message);
                break;
            case MAVLINK_MSG_ID_PARAM_EXT_VALUE:
                _handleParamValue(message);
                break;
93 94 95 96 97 98
            case MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION:
                _handleVideoStreamInfo(message);
                break;
            case MAVLINK_MSG_ID_VIDEO_STREAM_STATUS:
                _handleVideoStreamStatus(message);
                break;
Gus Grubba's avatar
Gus Grubba committed
99
        }
100 101 102 103 104 105 106 107 108
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleHeartbeat(const mavlink_message_t &message)
{
    mavlink_heartbeat_t heartbeat;
    mavlink_msg_heartbeat_decode(&message, &heartbeat);
109
    //-- If this heartbeat is from a different component within the vehicle
110
    if(_vehicleReadyState && _vehicle->id() == message.sysid && _vehicle->defaultComponentId() != message.compid) {
111 112 113 114 115
        //-- First time hearing from this one?
        if(!_cameraInfoRequest.contains(message.compid)) {
            CameraStruct* pInfo = new CameraStruct(this);
            pInfo->lastHeartbeat.start();
            _cameraInfoRequest[message.compid] = pInfo;
116 117
            //-- Request camera info
            _requestCameraInfo(message.compid);
118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138
        } 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);
                    }
                }
            }
139 140 141 142
        }
    }
}

143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165
//-----------------------------------------------------------------------------
QGCCameraControl*
QGCCameraManager::currentCameraInstance()
{
    if(_currentCamera < _cameras.count() && _cameras.count()) {
        QGCCameraControl* pCamera = qobject_cast<QGCCameraControl*>(_cameras[_currentCamera]);
        return pCamera;
    }
    return nullptr;
}

//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
QGCCameraManager::currentStreamInstance()
{
    QGCCameraControl* pCamera = currentCameraInstance();
    if(pCamera) {
        QGCVideoStreamInfo* pInfo = pCamera->currentStreamInstance();
        return pInfo;
    }
    return nullptr;
}

166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181
//-----------------------------------------------------------------------------
QGCCameraControl*
QGCCameraManager::_findCamera(int id)
{
    for(int i = 0; i < _cameras.count(); i++) {
        if(_cameras[i]) {
            QGCCameraControl* pCamera = qobject_cast<QGCCameraControl*>(_cameras[i]);
            if(pCamera) {
                if(pCamera->compID() == id) {
                    return pCamera;
                }
            } else {
                qCritical() << "Null QGCCameraControl instance";
            }
        }
    }
Gus Grubba's avatar
Gus Grubba committed
182
    qWarning() << "Camera component id not found:" << id;
183
    return nullptr;
184 185 186 187 188 189
}

//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
{
190
    //-- Have we requested it?
191
    if(_cameraInfoRequest.contains(message.compid) && !_cameraInfoRequest[message.compid]->infoReceived) {
192
        //-- Flag it as done
193
        _cameraInfoRequest[message.compid]->infoReceived = true;
194 195
        mavlink_camera_information_t info;
        mavlink_msg_camera_information_decode(&message, &info);
196
        qCDebug(CameraManagerLog) << "_handleCameraInfo:" << reinterpret_cast<const char*>(info.model_name) << reinterpret_cast<const char*>(info.vendor_name) << "Comp ID:" << message.compid;
197 198 199 200
        QGCCameraControl* pCamera = _vehicle->firmwarePlugin()->createCameraControl(&info, _vehicle, message.compid, this);
        if(pCamera) {
            QQmlEngine::setObjectOwnership(pCamera, QQmlEngine::CppOwnership);
            _cameras.append(pCamera);
Gus Grubba's avatar
Gus Grubba committed
201
            _cameraLabels << pCamera->modelName();
202
            emit camerasChanged();
Gus Grubba's avatar
Gus Grubba committed
203
            emit cameraLabelsChanged();
204
        }
205 206 207
    }
}

208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252
//-----------------------------------------------------------------------------
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;
                }
            }
        }
    }
}

Gus Grubba's avatar
Gus Grubba committed
253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276
//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleCaptureStatus(const mavlink_message_t &message)
{
    QGCCameraControl* pCamera = _findCamera(message.compid);
    if(pCamera) {
        mavlink_camera_capture_status_t cap;
        mavlink_msg_camera_capture_status_decode(&message, &cap);
        pCamera->handleCaptureStatus(cap);
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleStorageInfo(const mavlink_message_t& message)
{
    QGCCameraControl* pCamera = _findCamera(message.compid);
    if(pCamera) {
        mavlink_storage_information_t st;
        mavlink_msg_storage_information_decode(&message, &st);
        pCamera->handleStorageInfo(st);
    }
}

277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312
//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleCameraSettings(const mavlink_message_t& message)
{
    QGCCameraControl* pCamera = _findCamera(message.compid);
    if(pCamera) {
        mavlink_camera_settings_t settings;
        mavlink_msg_camera_settings_decode(&message, &settings);
        pCamera->handleSettings(settings);
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleParamAck(const mavlink_message_t& message)
{
    QGCCameraControl* pCamera = _findCamera(message.compid);
    if(pCamera) {
        mavlink_param_ext_ack_t ack;
        mavlink_msg_param_ext_ack_decode(&message, &ack);
        pCamera->handleParamAck(ack);
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleParamValue(const mavlink_message_t& message)
{
    QGCCameraControl* pCamera = _findCamera(message.compid);
    if(pCamera) {
        mavlink_param_ext_value_t value;
        mavlink_msg_param_ext_value_decode(&message, &value);
        pCamera->handleParamValue(value);
    }
}

313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336
//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleVideoStreamInfo(const mavlink_message_t& message)
{
    QGCCameraControl* pCamera = _findCamera(message.compid);
    if(pCamera) {
        mavlink_video_stream_information_t streamInfo;
        mavlink_msg_video_stream_information_decode(&message, &streamInfo);
        pCamera->handleVideoInfo(&streamInfo);
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraManager::_handleVideoStreamStatus(const mavlink_message_t& message)
{
    QGCCameraControl* pCamera = _findCamera(message.compid);
    if(pCamera) {
        mavlink_video_stream_status_t streamStatus;
        mavlink_msg_video_stream_status_decode(&message, &streamStatus);
        pCamera->handleVideoStatus(&streamStatus);
    }
}

337 338 339 340 341 342 343 344 345 346 347 348 349
//-----------------------------------------------------------------------------
void
QGCCameraManager::_requestCameraInfo(int compID)
{
    qCDebug(CameraManagerLog) << "_requestCameraInfo(" << compID << ")";
    if(_vehicle) {
        _vehicle->sendMavCommand(
            compID,                                 // target component
            MAV_CMD_REQUEST_CAMERA_INFORMATION,     // command id
            false,                                  // showError
            1);                                     // Do Request
    }
}
350 351 352 353 354 355 356 357 358

//----------------------------------------------------------------------------------------
void
QGCCameraManager::_activeJoystickChanged(Joystick* joystick)
{
    qCDebug(CameraManagerLog) << "Joystick changed";
    if(_activeJoystick) {
        disconnect(_activeJoystick, &Joystick::stepZoom,   this, &QGCCameraManager::_stepZoom);
        disconnect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera);
359
        disconnect(_activeJoystick, &Joystick::stepStream, this, &QGCCameraManager::_stepStream);
360 361 362 363 364
    }
    _activeJoystick = joystick;
    if(_activeJoystick) {
        connect(_activeJoystick, &Joystick::stepZoom,   this, &QGCCameraManager::_stepZoom);
        connect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera);
365
        connect(_activeJoystick, &Joystick::stepStream, this, &QGCCameraManager::_stepStream);
366 367 368 369 370 371 372 373 374 375
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraManager::_stepZoom(int direction)
{
    if(_lastZoomChange.elapsed() > 250) {
        _lastZoomChange.start();
        qCDebug(CameraManagerLog) << "Step Camera Zoom" << direction;
376 377 378
        QGCCameraControl* pCamera = currentCameraInstance();
        if(pCamera) {
            pCamera->stepZoom(direction);
379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396
        }
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraManager::_stepCamera(int direction)
{
    if(_lastCameraChange.elapsed() > 1000) {
        _lastCameraChange.start();
        qCDebug(CameraManagerLog) << "Step Camera" << direction;
        int c = _currentCamera + direction;
        if(c < 0) c = _cameras.count() - 1;
        if(c >= _cameras.count()) c = 0;
        setCurrentCamera(c);
    }
}

397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413
//-----------------------------------------------------------------------------
void
QGCCameraManager::_stepStream(int direction)
{
    if(_lastCameraChange.elapsed() > 1000) {
        _lastCameraChange.start();
        QGCCameraControl* pCamera = currentCameraInstance();
        if(pCamera) {
            qCDebug(CameraManagerLog) << "Step Camera Stream" << direction;
            int c = pCamera->currentStream() + direction;
            if(c < 0) c = pCamera->streams()->count() - 1;
            if(c >= pCamera->streams()->count()) c = 0;
            pCamera->setCurrentStream(c);
        }
    }
}

414