OpalLink.cc 20.7 KB
Newer Older
pixhawk's avatar
pixhawk committed
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29
/*=====================================================================

QGroundControl Open Source Ground Control Station

(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>

This file is part of the QGROUNDCONTROL project

    QGROUNDCONTROL is free software: you can redistribute it and/or modify
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.

    QGROUNDCONTROL is distributed in the hope that it will be useful,
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.

    You should have received a copy of the GNU General Public License
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.

======================================================================*/

/**
 * @file
 *   @brief Implementation of class OpalLink
 *   @author Bryan Godbolt <godbolt@ualberta.ca>
 */

30 31
#include "OpalLink.h"

32
OpalLink::OpalLink() :
33 34 35 36 37 38 39 40 41 42 43 44 45 46
    connectState(false),
    heartbeatTimer(new QTimer(this)),
    heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
    m_heartbeatsEnabled(true),
    getSignalsTimer(new QTimer(this)),
    getSignalsPeriod(10),
    receiveBuffer(new QQueue<QByteArray>()),
    systemID(1),
    componentID(1),
    params(NULL),
    opalInstID(101),
    sendRCValues(false),
    sendRawController(false),
    sendPosition(false)
47
{
48
    start(QThread::LowPriority);
Bryan Godbolt's avatar
Bryan Godbolt committed
49 50 51 52 53

    // Set unique ID and add link to the list of links
    this->id = getNextLinkId();
    this->name = tr("OpalRT link ") + QString::number(getId());
    LinkManager::instance()->add(this);
54 55 56

    // Start heartbeat timer, emitting a heartbeat at the configured rate
    QObject::connect(heartbeatTimer, SIGNAL(timeout()), this, SLOT(heartbeat()));
57 58

    QObject::connect(getSignalsTimer, SIGNAL(timeout()), this, SLOT(getSignals()));
59 60
}

61
void OpalLink::writeBytes(const char *bytes, qint64 length)
Bryan Godbolt's avatar
Bryan Godbolt committed
62
{
63 64
    /* decode the message */
    mavlink_message_t msg;
65
    mavlink_status_t status;
66
    int decodeSuccess = 0;
67
    for (int i=0; (!(decodeSuccess=mavlink_parse_char(this->getId(), bytes[i], &msg, &status))&& i<length); ++i);
68 69

    /* perform the appropriate action */
70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88
    if (decodeSuccess) {
        switch(msg.msgid) {
        case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: {
            qDebug() << "OpalLink::writeBytes(): request params";

            mavlink_message_t param;


            OpalRT::ParameterList::const_iterator paramIter;
            for (paramIter = params->begin(); paramIter != params->end(); ++paramIter) {
                mavlink_msg_param_value_pack(systemID,
                                             (*paramIter).getComponentID(),
                                             &param,
                                             (*paramIter).getParamID().toInt8_t(),
                                             (static_cast<OpalRT::Parameter>(*paramIter)).getValue(),
                                             params->count(),
                                             params->indexOf(*paramIter));
                receiveMessage(param);
            }
89 90


91 92
        }
        case MAVLINK_MSG_ID_PARAM_SET: {
93 94 95

//                qDebug() << "OpalLink::writeBytes(): Attempt to set a parameter";

96 97 98
            mavlink_param_set_t param;
            mavlink_msg_param_set_decode(&msg, &param);
            OpalRT::QGCParamID paramName((char*)param.param_id);
99 100 101

//                qDebug() << "OpalLink::writeBytes():paramName: " << paramName;

102 103
            if ((*params).contains(param.target_component, paramName)) {
                OpalRT::Parameter p = (*params)(param.target_component, paramName);
104
//                    qDebug() << __FILE__ << ":" << __LINE__ << ": "  << p;
105 106 107 108 109 110 111 112 113 114 115 116 117
                // Set the param value in Opal-RT
                p.setValue(param.param_value);

                // Get the param value from Opal-RT to make sure it was set properly
                mavlink_message_t paramMsg;
                mavlink_msg_param_value_pack(systemID,
                                             p.getComponentID(),
                                             &paramMsg,
                                             p.getParamID().toInt8_t(),
                                             p.getValue(),
                                             params->count(),
                                             params->indexOf(p));
                receiveMessage(paramMsg);
118
            }
119 120
        }
        break;
121 122 123 124 125 126 127
//        case MAVLINK_MSG_ID_REQUEST_RC_CHANNELS:
//        {
//        	mavlink_request_rc_channels_t rc;
//        	mavlink_msg_request_rc_channels_decode(&msg, &rc);
//        	this->sendRCValues = static_cast<bool>(rc.enabled);
//        }
//        break;
128
#ifdef MAVLINK_ENABLED_UALBERTA_MESSAGES
129
        case MAVLINK_MSG_ID_RADIO_CALIBRATION: {
130 131
            mavlink_radio_calibration_t radio;
            mavlink_msg_radio_calibration_decode(&msg, &radio);
132 133 134 135 136 137 138 139 140
//            qDebug() << "RADIO CALIBRATION RECEIVED";
//            qDebug() << "AILERON: " << radio.aileron[0] << " " << radio.aileron[1] << " " << radio.aileron[2];
//            qDebug() << "ELEVATOR: " << radio.elevator[0] << " " << radio.elevator[1] << " " << radio.elevator[2];
//            qDebug() << "RUDDER: " << radio.rudder[0] << " " << radio.rudder[1] << " " << radio.rudder[2];
//            qDebug() << "GYRO: " << radio.gyro[0] << " " << radio.gyro[1];
//            qDebug() << "PITCH: " << radio.pitch[0] << radio.pitch[1] << radio.pitch[2] << radio.pitch[3] << radio.pitch[4];
//            qDebug() << "THROTTLE: " << radio.throttle[0] << radio.throttle[1] << radio.throttle[2] << radio.throttle[3] << radio.throttle[4];

            /* AILERON SERVO */
141
            if (params->contains(OpalRT::SERVO_INPUTS, "AIL_RIGHT_IN"))
142
                params->getParameter(OpalRT::SERVO_INPUTS, "AIL_RIGHT_IN").setValue(((radio.aileron[0]>900 /*in us?*/)?radio.aileron[0]/1000:radio.aileron[0]));
143 144
            if (params->contains(OpalRT::SERVO_OUTPUTS, "AIL_RIGHT_OUT"))
                params->getParameter(OpalRT::SERVO_OUTPUTS, "AIL_RIGHT_OUT").setValue(((radio.aileron[0]>900 /*in us?*/)?radio.aileron[0]/1000:radio.aileron[0]));
145
            if (params->contains(OpalRT::SERVO_INPUTS, "AIL_CENTER_IN"))
146
                params->getParameter(OpalRT::SERVO_INPUTS, "AIL_CENTER_IN").setValue(((radio.aileron[1]>900 /*in us?*/)?radio.aileron[1]/1000:radio.aileron[1]));
147 148
            if (params->contains(OpalRT::SERVO_OUTPUTS, "AIL_CENTER_OUT"))
                params->getParameter(OpalRT::SERVO_OUTPUTS, "AIL_CENTER_OUT").setValue(((radio.aileron[1]>900 /*in us?*/)?radio.aileron[1]/1000:radio.aileron[1]));
149
            if (params->contains(OpalRT::SERVO_INPUTS, "AIL_LEFT_IN"))
150
                params->getParameter(OpalRT::SERVO_INPUTS, "AIL_LEFT_IN").setValue(((radio.aileron[2]>900 /*in us?*/)?radio.aileron[2]/1000:radio.aileron[2]));
151 152
            if (params->contains(OpalRT::SERVO_OUTPUTS, "AIL_LEFT_OUT"))
                params->getParameter(OpalRT::SERVO_OUTPUTS, "AIL_LEFT_OUT").setValue(((radio.aileron[2]>900 /*in us?*/)?radio.aileron[2]/1000:radio.aileron[2]));
153 154 155
            /* ELEVATOR SERVO */
            if (params->contains(OpalRT::SERVO_INPUTS, "ELE_DOWN_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "ELE_DOWN_IN").setValue(((radio.elevator[0]>900 /*in us?*/)?radio.elevator[0]/1000:radio.elevator[0]));
156 157
            if (params->contains(OpalRT::SERVO_OUTPUTS, "ELE_DOWN_OUT"))
                params->getParameter(OpalRT::SERVO_OUTPUTS, "ELE_DOWN_OUT").setValue(((radio.elevator[0]>900 /*in us?*/)?radio.elevator[0]/1000:radio.elevator[0]));
158 159
            if (params->contains(OpalRT::SERVO_INPUTS, "ELE_CENTER_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "ELE_CENTER_IN").setValue(((radio.elevator[1]>900 /*in us?*/)?radio.elevator[1]/1000:radio.elevator[1]));
160 161
            if (params->contains(OpalRT::SERVO_OUTPUTS, "ELE_CENTER_OUT"))
                params->getParameter(OpalRT::SERVO_OUTPUTS, "ELE_CENTER_OUT").setValue(((radio.elevator[1]>900 /*in us?*/)?radio.elevator[1]/1000:radio.elevator[1]));
162 163
            if (params->contains(OpalRT::SERVO_INPUTS, "ELE_UP_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "ELE_UP_IN").setValue(((radio.elevator[2]>900 /*in us?*/)?radio.elevator[2]/1000:radio.elevator[2]));
164 165
            if (params->contains(OpalRT::SERVO_OUTPUTS, "ELE_UP_OUT"))
                params->getParameter(OpalRT::SERVO_OUTPUTS, "ELE_UP_OUT").setValue(((radio.elevator[2]>900 /*in us?*/)?radio.elevator[2]/1000:radio.elevator[2]));
166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199
            /* THROTTLE SERVO */
            if (params->contains(OpalRT::SERVO_INPUTS, "THR_SET0_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "THR_SET0_IN").setValue(((radio.throttle[0]>900 /*in us?*/)?radio.throttle[0]/1000:radio.throttle[0]));
            if (params->contains(OpalRT::SERVO_INPUTS, "THR_SET1_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "THR_SET1_IN").setValue(((radio.throttle[1]>900 /*in us?*/)?radio.throttle[1]/1000:radio.throttle[1]));
            if (params->contains(OpalRT::SERVO_INPUTS, "THR_SET2_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "THR_SET2_IN").setValue(((radio.throttle[2]>900 /*in us?*/)?radio.throttle[2]/1000:radio.throttle[2]));
            if (params->contains(OpalRT::SERVO_INPUTS, "THR_SET3_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "THR_SET3_IN").setValue(((radio.throttle[3]>900 /*in us?*/)?radio.throttle[3]/1000:radio.throttle[3]));
            if (params->contains(OpalRT::SERVO_INPUTS, "THR_SET4_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "THR_SET4_IN").setValue(((radio.throttle[4]>900 /*in us?*/)?radio.throttle[4]/1000:radio.throttle[4]));
            /* RUDDER SERVO */
            if (params->contains(OpalRT::SERVO_INPUTS, "RUD_LEFT_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "RUD_LEFT_IN").setValue(((radio.rudder[0]>900 /*in us?*/)?radio.rudder[0]/1000:radio.rudder[0]));
            if (params->contains(OpalRT::SERVO_INPUTS, "RUD_CENTER_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "RUD_CENTER_IN").setValue(((radio.rudder[1]>900 /*in us?*/)?radio.rudder[1]/1000:radio.rudder[1]));
            if (params->contains(OpalRT::SERVO_INPUTS, "RUD_RIGHT_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "RUD_RIGHT_IN").setValue(((radio.rudder[2]>900 /*in us?*/)?radio.rudder[2]/1000:radio.rudder[2]));
            /* GYRO MODE/GAIN SWITCH */
            if (params->contains(OpalRT::SERVO_INPUTS, "GYRO_DEF_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "GYRO_DEF_IN").setValue(((radio.gyro[0]>900 /*in us?*/)?radio.gyro[0]/1000:radio.gyro[0]));
            if (params->contains(OpalRT::SERVO_INPUTS, "GYRO_TOG_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "GYRO_TOG_IN").setValue(((radio.gyro[1]>900 /*in us?*/)?radio.gyro[1]/1000:radio.gyro[1]));
            /* PITCH SERVO */
            if (params->contains(OpalRT::SERVO_INPUTS, "PIT_SET0_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "PIT_SET0_IN").setValue(((radio.pitch[0]>900 /*in us?*/)?radio.pitch[0]/1000:radio.pitch[0]));
            if (params->contains(OpalRT::SERVO_INPUTS, "PIT_SET1_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "PIT_SET1_IN").setValue(((radio.pitch[1]>900 /*in us?*/)?radio.pitch[1]/1000:radio.pitch[1]));
            if (params->contains(OpalRT::SERVO_INPUTS, "PIT_SET2_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "PIT_SET2_IN").setValue(((radio.pitch[2]>900 /*in us?*/)?radio.pitch[2]/1000:radio.pitch[2]));
            if (params->contains(OpalRT::SERVO_INPUTS, "PIT_SET3_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "PIT_SET3_IN").setValue(((radio.pitch[3]>900 /*in us?*/)?radio.pitch[3]/1000:radio.pitch[3]));
            if (params->contains(OpalRT::SERVO_INPUTS, "PIT_SET4_IN"))
                params->getParameter(OpalRT::SERVO_INPUTS, "PIT_SET4_IN").setValue(((radio.pitch[4]>900 /*in us?*/)?radio.pitch[4]/1000:radio.pitch[4]));
200 201
        }
        break;
202
#endif
203
    }
204 205 206 207

    // Log the amount and time written out for future data rate calculations.
    QMutexLocker dataRateLocker(&dataRateMutex);
    logDataRateToBuffer(outDataWriteAmounts, outDataWriteTimes, &outDataIndex, size, QDateTime::currentMSecsSinceEpoch());
Bryan Godbolt's avatar
Bryan Godbolt committed
208 209
}

210

211
void OpalLink::readBytes()
Bryan Godbolt's avatar
Bryan Godbolt committed
212
{
213
    receiveDataMutex.lock();
Bryan Godbolt's avatar
Bryan Godbolt committed
214
    emit bytesReceived(this, receiveBuffer->dequeue());
215 216
    receiveDataMutex.unlock();

217 218 219
    // Log the amount and time received for future data rate calculations.
    QMutexLocker dataRateLocker(&dataRateMutex);
    logDataRateToBuffer(inDataWriteAmounts, inDataWriteTimes, &inDataIndex, s, QDateTime::currentMSecsSinceEpoch());
Bryan Godbolt's avatar
Bryan Godbolt committed
220 221
}

222
void OpalLink::receiveMessage(mavlink_message_t message)
Bryan Godbolt's avatar
Bryan Godbolt committed
223 224
{

225 226 227 228 229
    // Create buffer
    char buffer[MAVLINK_MAX_PACKET_LEN];
    // Write message into buffer, prepending start sign
    int len = mavlink_msg_to_send_buffer((uint8_t*)(buffer), &message);
    // If link is connected
230
    if (isConnected()) {
Bryan Godbolt's avatar
Bryan Godbolt committed
231
        receiveDataMutex.lock();
232
        receiveBuffer->enqueue(QByteArray(buffer, len));
Bryan Godbolt's avatar
Bryan Godbolt committed
233
        receiveDataMutex.unlock();
234
        readBytes();
235 236
    }

Bryan Godbolt's avatar
Bryan Godbolt committed
237 238
}

239
void OpalLink::heartbeat()
Bryan Godbolt's avatar
Bryan Godbolt committed
240
{
241

242
    if (m_heartbeatsEnabled) {
243 244 245 246 247
        mavlink_message_t beat;
        mavlink_msg_heartbeat_pack(systemID, componentID,&beat, MAV_HELICOPTER, MAV_AUTOPILOT_GENERIC);
        receiveMessage(beat);
    }

Bryan Godbolt's avatar
Bryan Godbolt committed
248
}
249 250
void OpalLink::setSignals(double *values)
{
Bryan Godbolt's avatar
Bryan Godbolt committed
251
    unsigned short numSignals = 2;
252 253 254 255 256
    unsigned short logicalId = 1;
    unsigned short signalIndex[] = {0,1};

    int returnValue;
    returnValue =  OpalSetSignals( numSignals, logicalId, signalIndex, values);
257
    if (returnValue != EOK) {
258
        OpalRT::OpalErrorMsg::displayLastErrorMsg();
259 260
    }
}
261
void OpalLink::getSignals()
Bryan Godbolt's avatar
Bryan Godbolt committed
262
{
Bryan Godbolt's avatar
Bryan Godbolt committed
263 264 265 266
    unsigned long  timeout = 0;
    unsigned short acqGroup = 0; //this is actually group 1 in the model
    unsigned short *numSignals = new unsigned short(0);
    double *timestep = new double(0);
267
    double values[OpalRT::NUM_OUTPUT_SIGNALS] = {};
Bryan Godbolt's avatar
Bryan Godbolt committed
268 269 270
    unsigned short *lastValues = new unsigned short(false);
    unsigned short *decimation = new unsigned short(0);

271
    while (!(*lastValues)) {
272
        int returnVal = OpalGetSignals(timeout, acqGroup, OpalRT::NUM_OUTPUT_SIGNALS, numSignals, timestep,
Bryan Godbolt's avatar
Bryan Godbolt committed
273 274
                                       values, lastValues, decimation);

275
        if (returnVal == EOK ) {
276
            /* Send position info to qgroundcontrol */
277
            if (sendPosition) {
278 279 280 281 282 283 284 285 286 287 288
                mavlink_message_t local_position;
                mavlink_msg_local_position_pack(systemID, componentID, &local_position,
                                                (*timestep)*1000000,
                                                values[OpalRT::X_POS],
                                                values[OpalRT::Y_POS],
                                                values[OpalRT::Z_POS],
                                                values[OpalRT::X_VEL],
                                                values[OpalRT::Y_VEL],
                                                values[OpalRT::Z_VEL]);
                receiveMessage(local_position);
            }
289 290 291 292 293 294 295
            /* send attitude info to qgroundcontrol */
            mavlink_message_t attitude;
            mavlink_msg_attitude_pack(systemID, componentID, &attitude,
                                      (*timestep)*1000000,
                                      values[OpalRT::ROLL],
                                      values[OpalRT::PITCH],
                                      values[OpalRT::YAW],
296 297 298
                                      values[OpalRT::ROLL_SPEED],
                                      values[OpalRT::PITCH_SPEED],
                                      values[OpalRT::YAW_SPEED]
299
                                     );
300 301 302 303 304 305 306 307 308 309 310 311
            receiveMessage(attitude);

            /* send bias info to qgroundcontrol */
            mavlink_message_t bias;
            mavlink_msg_nav_filter_bias_pack(systemID, componentID, &bias,
                                             (*timestep)*1000000,
                                             values[OpalRT::B_F_0],
                                             values[OpalRT::B_F_1],
                                             values[OpalRT::B_F_2],
                                             values[OpalRT::B_W_0],
                                             values[OpalRT::B_W_1],
                                             values[OpalRT::B_W_2]
312
                                            );
313
            receiveMessage(bias);
Bryan Godbolt's avatar
Bryan Godbolt committed
314 315

            /* send radio outputs */
316
            if (sendRCValues) {
317
                mavlink_message_t rc;
318
                mavlink_msg_rc_channels_raw_pack(systemID, componentID, &rc,
319 320 321 322 323 324 325 326 327 328
                                                 duty2PulseMicros(values[OpalRT::RAW_CHANNEL_1]),
                                                 duty2PulseMicros(values[OpalRT::RAW_CHANNEL_2]),
                                                 duty2PulseMicros(values[OpalRT::RAW_CHANNEL_3]),
                                                 duty2PulseMicros(values[OpalRT::RAW_CHANNEL_4]),
                                                 duty2PulseMicros(values[OpalRT::RAW_CHANNEL_5]),
                                                 duty2PulseMicros(values[OpalRT::RAW_CHANNEL_6]),
                                                 duty2PulseMicros(values[OpalRT::RAW_CHANNEL_7]),
                                                 duty2PulseMicros(values[OpalRT::RAW_CHANNEL_8]),
                                                 0 //rssi unused
                                                );
329 330
                receiveMessage(rc);
            }
331
            if (sendRawController) {
332 333
                mavlink_message_t rawController;
                mavlink_msg_attitude_controller_output_pack(systemID, componentID, &rawController,
334 335 336 337 338 339
                        1,
                        rescaleControllerOutput(values[OpalRT::CONTROLLER_AILERON]),
                        rescaleControllerOutput(values[OpalRT::CONTROLLER_ELEVATOR]),
                        0, // yaw not used
                        0 // thrust not used
                                                           );
340 341
                receiveMessage(rawController);
            }
342
        } else if (returnVal != EAGAIN) { // if returnVal == EAGAIN => data just wasn't ready
Bryan Godbolt's avatar
Bryan Godbolt committed
343
            getSignalsTimer->stop();
344
            OpalRT::OpalErrorMsg::displayLastErrorMsg();
Bryan Godbolt's avatar
Bryan Godbolt committed
345 346 347 348 349 350 351 352 353
        }
    }

    /* deallocate used memory */

    delete numSignals;
    delete timestep;
    delete lastValues;
    delete decimation;
354

Bryan Godbolt's avatar
Bryan Godbolt committed
355 356
}

357

358 359 360 361 362 363
/*
 *
  Administrative
 *
 */
void OpalLink::run()
Bryan Godbolt's avatar
Bryan Godbolt committed
364
{
Bryan Godbolt's avatar
Bryan Godbolt committed
365
//    qDebug() << "OpalLink::run():: Starting the thread";
366 367
}

368
int OpalLink::getId() const
369 370
{
    return id;
Bryan Godbolt's avatar
Bryan Godbolt committed
371 372
}

373
QString OpalLink::getName() const
Bryan Godbolt's avatar
Bryan Godbolt committed
374
{
375
    return name;
Bryan Godbolt's avatar
Bryan Godbolt committed
376 377
}

378
void OpalLink::setName(QString name)
Bryan Godbolt's avatar
Bryan Godbolt committed
379
{
380 381
    this->name = name;
    emit nameChanged(this->name);
Bryan Godbolt's avatar
Bryan Godbolt committed
382 383
}

384
bool OpalLink::isConnected() const
385
{
386
    return connectState;
Bryan Godbolt's avatar
Bryan Godbolt committed
387 388
}

Bryan Godbolt's avatar
Bryan Godbolt committed
389 390 391 392 393 394
uint16_t OpalLink::duty2PulseMicros(double duty)
{
    /* duty cycle assumed to be of a signal at 70 Hz */
    return static_cast<uint16_t>(duty/70*1000000);
}

395
uint8_t OpalLink::rescaleNorm(double norm, int ch)
396
{
397
    switch(ch) {
398 399 400 401 402 403 404 405 406 407
    case OpalRT::NORM_CHANNEL_1:
    case OpalRT::NORM_CHANNEL_2:
    case OpalRT::NORM_CHANNEL_4:
    default:
        // three setpoints
        return static_cast<uint8_t>((norm+1)/2*255);
        break;
    case OpalRT::NORM_CHANNEL_5:
        //two setpoints
    case OpalRT::NORM_CHANNEL_3:
408
    case OpalRT::NORM_CHANNEL_6:
409 410 411
        return static_cast<uint8_t>(norm*255);
        break;
    }
412
}
Bryan Godbolt's avatar
Bryan Godbolt committed
413

414 415 416 417
int8_t OpalLink::rescaleControllerOutput(double raw)
{
    return static_cast<int8_t>((raw>=0?raw*127:raw*128));
}
418

419
bool OpalLink::_connect(void)
420
{
Bryan Godbolt's avatar
Bryan Godbolt committed
421
    short modelState;
422

423
    if ((OpalConnect(opalInstID, false, &modelState) == EOK)
424 425
            && (OpalGetSignalControl(0, true) == EOK)
            && (OpalGetParameterControl(true) == EOK)) {
426
        connectState = true;
427 428
        if (params)
            delete params;
429
        params = new OpalRT::ParameterList();
430 431 432
        emit connected();
        heartbeatTimer->start(1000/heartbeatRate);
        getSignalsTimer->start(getSignalsPeriod);
433
    } else {
Bryan Godbolt's avatar
Bryan Godbolt committed
434
        connectState = false;
435
        OpalRT::OpalErrorMsg::displayLastErrorMsg();
Bryan Godbolt's avatar
Bryan Godbolt committed
436
    }
437 438 439

    emit connected(connectState);
    return connectState;
440 441
}

442
bool OpalLink::_disconnect(void)
443
{
444 445 446 447
    // OpalDisconnect returns void so its success or failure cannot be tested
    OpalDisconnect();
    heartbeatTimer->stop();
    getSignalsTimer->stop();
448 449
    connectState = false;
    emit connected(connectState);
450
    return true;
451 452
}

453 454 455 456 457
// Data rate functions
qint64 OpalLink::getConnectionSpeed() const
{
    return 0; //unknown
}
458

459 460 461 462
qint64 OpalLink::getCurrentInDataRate() const
{
    return 0;
}
463

464
qint64 OpalLink::getCurrentOutDataRate() const
465
{
466 467
    return 0;
}