QGCCameraIO.cc 10.8 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21
/*!
 * @file
 *   @brief Camera Controller
 *   @author Gus Grubba <mavlink@grubba.com>
 *
 */

#include "QGCCameraControl.h"
#include "QGCCameraIO.h"

QGC_LOGGING_CATEGORY(CameraIOLog, "CameraIOLog")
QGC_LOGGING_CATEGORY(CameraIOLogVerbose, "CameraIOLogVerbose")

//-----------------------------------------------------------------------------
QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicle *vehicle)
    : QObject(control)
    , _control(control)
    , _fact(fact)
    , _vehicle(vehicle)
    , _sentRetries(0)
    , _requestRetries(0)
22
    , _done(false)
23
    , _updateOnSet(false)
24
    , _forceUIUpdate(false)
25
{
26
    QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
27
    _paramWriteTimer.setSingleShot(true);
28
    _paramWriteTimer.setInterval(3000);
29
    _paramRequestTimer.setSingleShot(true);
30
    _paramRequestTimer.setInterval(3500);
31 32 33
    connect(&_paramWriteTimer,   &QTimer::timeout, this, &QGCCameraParamIO::_paramWriteTimeout);
    connect(&_paramRequestTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramRequestTimeout);
    connect(_fact, &Fact::rawValueChanged, this, &QGCCameraParamIO::_factChanged);
Gus Grubba's avatar
Gus Grubba committed
34
    connect(_fact, &Fact::_containerRawValueChanged, this, &QGCCameraParamIO::_containerRawValueChanged);
35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63
    _pMavlink = qgcApp()->toolbox()->mavlinkProtocol();
    //-- TODO: Even though we don't use anything larger than 32-bit, this should
    //   probably be updated.
    switch (_fact->type()) {
        case FactMetaData::valueTypeUint8:
            _mavParamType = MAV_PARAM_TYPE_UINT8;
            break;
        case FactMetaData::valueTypeInt8:
            _mavParamType = MAV_PARAM_TYPE_INT8;
            break;
        case FactMetaData::valueTypeUint16:
            _mavParamType = MAV_PARAM_TYPE_UINT16;
            break;
        case FactMetaData::valueTypeInt16:
            _mavParamType = MAV_PARAM_TYPE_INT16;
            break;
        case FactMetaData::valueTypeUint32:
            _mavParamType = MAV_PARAM_TYPE_UINT32;
            break;
        case FactMetaData::valueTypeFloat:
            _mavParamType = MAV_PARAM_TYPE_REAL32;
            break;
        default:
            qWarning() << "Unsupported fact type" << _fact->type();
            // Fall through
        case FactMetaData::valueTypeInt32:
            _mavParamType = MAV_PARAM_TYPE_INT32;
            break;
    }
64 65 66 67 68 69 70 71 72 73 74 75 76 77 78
}

//-----------------------------------------------------------------------------
void
QGCCameraParamIO::setParamRequest()
{
    _paramRequestReceived = false;
    _requestRetries = 0;
    _paramRequestTimer.start();
}

//-----------------------------------------------------------------------------
void
QGCCameraParamIO::_factChanged(QVariant value)
{
79 80 81 82 83 84
    if(!_forceUIUpdate) {
        Q_UNUSED(value);
        qCDebug(CameraIOLog) << "UI Fact" << _fact->name() << "changed to" << value;
        //-- TODO: Do we really want to update the UI now or only when we receive the ACK?
        _control->factChanged(_fact);
    }
85 86
}

Gus Grubba's avatar
Gus Grubba committed
87 88 89 90
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::_containerRawValueChanged(const QVariant value)
{
91 92 93 94 95 96
    if(!_fact->readOnly()) {
        Q_UNUSED(value);
        qCDebug(CameraIOLog) << "Update Fact" << _fact->name();
        _sentRetries = 0;
        _sendParameter();
    }
Gus Grubba's avatar
Gus Grubba committed
97 98
}

99 100 101 102 103 104 105 106 107 108
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::sendParameter(bool updateUI)
{
    qCDebug(CameraIOLog) << "Send Fact" << _fact->name();
    _sentRetries = 0;
    _updateOnSet = updateUI;
    _sendParameter();
}

109 110 111 112 113
//-----------------------------------------------------------------------------
void
QGCCameraParamIO::_sendParameter()
{
    //-- TODO: We should use something other than mavlink_param_union_t for PARAM_EXT_SET
114 115
    mavlink_param_ext_set_t p;
    memset(&p, 0, sizeof(mavlink_param_ext_set_t));
116
    mavlink_param_union_t       union_value;
117
    mavlink_message_t           msg;
118
    FactMetaData::ValueType_t factType = _fact->type();
119
    p.param_type = _mavParamType;
120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145
    switch (factType) {
        case FactMetaData::valueTypeUint8:
            union_value.param_uint8 = (uint8_t)_fact->rawValue().toUInt();
            break;
        case FactMetaData::valueTypeInt8:
            union_value.param_int8 = (int8_t)_fact->rawValue().toInt();
            break;
        case FactMetaData::valueTypeUint16:
            union_value.param_uint16 = (uint16_t)_fact->rawValue().toUInt();
            break;
        case FactMetaData::valueTypeInt16:
            union_value.param_int16 = (int16_t)_fact->rawValue().toInt();
            break;
        case FactMetaData::valueTypeUint32:
            union_value.param_uint32 = (uint32_t)_fact->rawValue().toUInt();
            break;
        case FactMetaData::valueTypeFloat:
            union_value.param_float = _fact->rawValue().toFloat();
            break;
        default:
            qCritical() << "Unsupported fact type" << factType;
            // fall through
        case FactMetaData::valueTypeInt32:
            union_value.param_int32 = (int32_t)_fact->rawValue().toInt();
            break;
    }
146
    memcpy(&p.param_value[0], &union_value.param_float, sizeof(float));
147 148
    p.target_system = (uint8_t)_vehicle->id();
    p.target_component = (uint8_t)_control->compID();
149 150 151 152 153 154 155 156
    strncpy(p.param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_ID_LEN);
    mavlink_msg_param_ext_set_encode_chan(
        _pMavlink->getSystemId(),
        _pMavlink->getComponentId(),
        _vehicle->priorityLink()->mavlinkChannel(),
        &msg,
        &p);
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
157 158 159 160 161 162 163 164 165
    _paramWriteTimer.start();
}

//-----------------------------------------------------------------------------
void
QGCCameraParamIO::_paramWriteTimeout()
{
    if(++_sentRetries > 3) {
        qCWarning(CameraIOLog) << "No response for param set:" << _fact->name();
166
        _updateOnSet = false;
167 168
    } else {
        //-- Send it again
169
        qCDebug(CameraIOLog) << "Param set retry:" << _fact->name() << _sentRetries;
170
        _sendParameter();
171 172 173 174 175 176 177 178 179 180
        _paramWriteTimer.start();
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraParamIO::handleParamAck(const mavlink_param_ext_ack_t& ack)
{
    _paramWriteTimer.stop();
    if(ack.param_result == PARAM_ACK_ACCEPTED) {
181 182 183
        QVariant val = _valueFromMessage(ack.param_value, ack.param_type);
        if(_fact->rawValue() != val) {
            _fact->_containerSetRawValue(val);
184 185 186 187
            if(_updateOnSet) {
                _updateOnSet = false;
                _control->factChanged(_fact);
            }
188 189
        }
    } else if(ack.param_result == PARAM_ACK_IN_PROGRESS) {
190 191 192 193 194
        //-- Wait a bit longer for this one
        qCDebug(CameraIOLogVerbose) << "Param set in progress:" << _fact->name();
        _paramWriteTimer.start();
    } else {
        if(ack.param_result == PARAM_ACK_FAILED) {
Gus Grubba's avatar
Gus Grubba committed
195
            if(++_sentRetries < 3) {
196 197 198 199 200
                //-- Try again
                qCWarning(CameraIOLog) << "Param set failed:" << _fact->name() << _sentRetries;
                _paramWriteTimer.start();
            }
            return;
201 202 203
        } else if(ack.param_result == PARAM_ACK_VALUE_UNSUPPORTED) {
            qCWarning(CameraIOLog) << "Param set unsuported:" << _fact->name();
        }
204 205 206 207 208
        //-- If UI changed and value was not set, restore UI
        QVariant val = _valueFromMessage(ack.param_value, ack.param_type);
        if(_fact->rawValue() != val) {
            _fact->_containerSetRawValue(val);
        }
209 210 211 212 213 214 215 216
    }
}

//-----------------------------------------------------------------------------
void
QGCCameraParamIO::handleParamValue(const mavlink_param_ext_value_t& value)
{
    _paramRequestTimer.stop();
217 218 219 220
    QVariant newValue = _valueFromMessage(value.param_value, value.param_type);
    if(_control->incomingParameter(_fact, newValue)) {
        _fact->_containerSetRawValue(newValue);
    }
221
    _paramRequestReceived = true;
222 223 224 225 226
    if(_forceUIUpdate) {
        emit _fact->rawValueChanged(_fact->rawValue());
        emit _fact->valueChanged(_fact->rawValue());
        _forceUIUpdate = false;
    }
227 228 229 230
    if(!_done) {
        _done = true;
        _control->_paramDone();
    }
231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277
    qCDebug(CameraIOLog) << QString("handleParamValue() %1 %2").arg(_fact->name()).arg(_fact->rawValueString());
}

//-----------------------------------------------------------------------------
QVariant
QGCCameraParamIO::_valueFromMessage(const char* value, uint8_t param_type)
{
    //-- TODO: Even though we don't use anything larger than 32-bit, this should
    //   probably be updated.
    QVariant var;
    mavlink_param_union_t u;
    memcpy(&u.param_float, value, sizeof(float));
    switch (param_type) {
        case MAV_PARAM_TYPE_REAL32:
            var = QVariant(u.param_float);
            break;
        case MAV_PARAM_TYPE_UINT8:
            var = QVariant(u.param_uint8);
            break;
        case MAV_PARAM_TYPE_INT8:
            var = QVariant(u.param_int8);
            break;
        case MAV_PARAM_TYPE_UINT16:
            var = QVariant(u.param_uint16);
            break;
        case MAV_PARAM_TYPE_INT16:
            var = QVariant(u.param_int16);
            break;
        case MAV_PARAM_TYPE_UINT32:
            var = QVariant(u.param_uint32);
            break;
        case MAV_PARAM_TYPE_INT32:
            var = QVariant(u.param_int32);
            break;
        default:
            var = QVariant(0);
            qCritical() << "Invalid param_type used for camera setting:" << param_type;
    }
    return var;
}

//-----------------------------------------------------------------------------
void
QGCCameraParamIO::_paramRequestTimeout()
{
    if(++_requestRetries > 3) {
        qCWarning(CameraIOLog) << "No response for param request:" << _fact->name();
278 279 280 281
        if(!_done) {
            _done = true;
            _control->_paramDone();
        }
282 283 284
    } else {
        //-- Request it again
        qCDebug(CameraIOLog) << "Param request retry:" << _fact->name();
285
        paramRequest(false);
286 287 288
        _paramRequestTimer.start();
    }
}
289 290 291 292 293 294 295

//-----------------------------------------------------------------------------
void
QGCCameraParamIO::paramRequest(bool reset)
{
    if(reset) {
        _requestRetries = 0;
296
        _forceUIUpdate  = true;
297
    }
298
    qCDebug(CameraIOLog) << "Request parameter:" << _fact->name();
299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314
    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(),
        _pMavlink->getComponentId(),
        _vehicle->priorityLink()->mavlinkChannel(),
        &msg,
        _vehicle->id(),
        _control->compID(),
        param_id,
        -1);
    _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
    _paramRequestTimer.start();
}