Newer
Older
OpalLink::OpalLink() :
connectState(false),
heartbeatTimer(new QTimer(this)),
heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
m_heartbeatsEnabled(true),
getSignalsTimer(new QTimer(this)),
getSignalsPeriod(1000),
receiveBuffer(new QQueue<QByteArray>()),
systemID(1),
componentID(1)
// 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);
// Start heartbeat timer, emitting a heartbeat at the configured rate
QObject::connect(heartbeatTimer, SIGNAL(timeout()), this, SLOT(heartbeat()));
QObject::connect(getSignalsTimer, SIGNAL(timeout()), this, SLOT(getSignals()));
/*
*
Communication
*
*/
qint64 OpalLink::bytesAvailable()
void OpalLink::writeBytes(const char *bytes, qint64 length)
void OpalLink::readBytes(char *bytes, qint64 maxLength)
receiveDataMutex.lock();
qDebug() << "OpalLink::readBytes(): Reading a message. size of buffer: " << receiveBuffer->count();
QByteArray message = receiveBuffer->dequeue();
if (maxLength < message.size())
{
qDebug() << "OpalLink::readBytes:: Buffer Overflow";
memcpy(bytes, message.data(), maxLength);
}
else
{
memcpy(bytes, message.data(), message.size());
}
emit bytesReceived(this, message);
receiveDataMutex.unlock();
void OpalLink::receiveMessage(mavlink_message_t message)
// 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
if (isConnected())
{
receiveBuffer->enqueue(QByteArray(buffer, len));
emit bytesReady(this);
}
if (m_heartbeatsEnabled)
{
qDebug() << "OpalLink::heartbeat(): Generate a heartbeat";
mavlink_message_t beat;
mavlink_msg_heartbeat_pack(systemID, componentID,&beat, MAV_HELICOPTER, MAV_AUTOPILOT_GENERIC);
receiveMessage(beat);
}
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
qDebug() << "OpalLink::getSignals(): Attempting to acquire signals";
unsigned long timeout = 0;
unsigned short acqGroup = 0; //this is actually group 1 in the model
unsigned short allocatedSignals = NUM_OUTPUT_SIGNALS;
unsigned short *numSignals = new unsigned short(0);
double *timestep = new double(0);
double values[NUM_OUTPUT_SIGNALS] = {};
unsigned short *lastValues = new unsigned short(false);
unsigned short *decimation = new unsigned short(0);
int returnVal = OpalGetSignals(timeout, acqGroup, allocatedSignals, numSignals, timestep,
values, lastValues, decimation);
if (returnVal == EOK )
{
qDebug() << "OpalLink::getSignals: Timestep=" << *timestep;// << ", Last? " << (bool)(*lastValues);
}
else if (returnVal == EAGAIN)
{
qDebug() << "OpalLink::getSignals: Data was not ready";
}
// if returnVal == EAGAIN => data just wasn't ready
else if (returnVal != EAGAIN)
{
getSignalsTimer->stop();
displayErrorMsg();
}
/* deallocate used memory */
delete timestep;
delete lastValues;
delete lastValues;
delete decimation;
/*
*
Administrative
*
*/
void OpalLink::run()
qDebug() << "OpalLink::run():: Starting the thread";
int OpalLink::getId()
{
return id;
QString OpalLink::getName()
void OpalLink::setName(QString name)
this->name = name;
emit nameChanged(this->name);
bool OpalLink::isConnected() {
//qDebug() << "OpalLink::isConnected:: connectState: " << connectState;
return connectState;
/// \todo allow configuration of instid in window
if (OpalConnect(101, false, &modelState) == EOK)
{
connectState = true;
emit connected();
heartbeatTimer->start(1000/heartbeatRate);
getSignalsTimer->start(getSignalsPeriod);
}
else
{
connectState = false;
}
emit connected(connectState);
return connectState;
}
bool OpalLink::disconnect()
{
return false;
}
void OpalLink::displayErrorMsg()
{
setLastErrorMsg();
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Critical);
msgBox.setText(lastErrorMsg);
msgBox.exec();
}
void OpalLink::setLastErrorMsg()
{
char buf[512];
unsigned short len;
OpalGetLastErrMsg(buf, sizeof(buf), &len);
lastErrorMsg.clear();
lastErrorMsg.append(buf);
}
/*
*
Statisctics
*
*/
qint64 OpalLink::getNominalDataRate()
int OpalLink::getLinkQuality()
qint64 OpalLink::getTotalUpstream()
statisticsMutex.lock();
qint64 totalUpstream = bitsSentTotal / ((MG::TIME::getGroundTimeNow() - connectionStartTime) / 1000);
statisticsMutex.unlock();
return totalUpstream;
}
qint64 OpalLink::getTotalDownstream() {
statisticsMutex.lock();
qint64 totalDownstream = bitsReceivedTotal / ((MG::TIME::getGroundTimeNow() - connectionStartTime) / 1000);
statisticsMutex.unlock();
return totalDownstream;
qint64 OpalLink::getCurrentUpstream()
qint64 OpalLink::getMaxUpstream()
{
return 0; //unknown
}
qint64 OpalLink::getBitsSent() {
return bitsSentTotal;
qint64 OpalLink::getBitsReceived() {
return bitsReceivedTotal;
}
bool OpalLink::isFullDuplex()
{
return false;