Commit 1d86c8ac authored by pixhawk's avatar pixhawk

Cleaned up communication structure significantly, should now be easier to add...

Cleaned up communication structure significantly, should now be easier to add new links. Signal bytesReceived(link, QByteArray) is now only way to pass on newly received data
parent 2c1b9f15
...@@ -225,3 +225,9 @@ win32 { ...@@ -225,3 +225,9 @@ win32 {
HEADERS += src/comm/OpalLink.h HEADERS += src/comm/OpalLink.h
DEFINES += OPAL_RT DEFINES += OPAL_RT
} }
macx {
SOURCES += src/comm/OpalLink.cc
HEADERS += src/comm/OpalLink.h
DEFINES += OPAL_RT
}
...@@ -46,6 +46,9 @@ This file is part of the PIXHAWK project ...@@ -46,6 +46,9 @@ This file is part of the PIXHAWK project
#include "MainWindow.h" #include "MainWindow.h"
#include "GAudioOutput.h" #include "GAudioOutput.h"
#ifdef OPAL_RT
#include "OpalLink.h"
#endif
#include "UDPLink.h" #include "UDPLink.h"
#include "MAVLinkSimulationLink.h" #include "MAVLinkSimulationLink.h"
...@@ -136,6 +139,8 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv) ...@@ -136,6 +139,8 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
// Add OpalRT Link, but do not connect // Add OpalRT Link, but do not connect
OpalLink* opalLink = new OpalLink(); OpalLink* opalLink = new OpalLink();
mainWindow->addLink(opalLink); mainWindow->addLink(opalLink);
opalLink->connect();
#warning OPAL LINK NOW AUTO CONNECTING IN CORE.CC
#endif #endif
// MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(MG::DIR::getSupportFilesDirectory() + "/demo-log.txt"); // MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(MG::DIR::getSupportFilesDirectory() + "/demo-log.txt");
MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(":/demo-log.txt"); MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(":/demo-log.txt");
......
...@@ -99,13 +99,13 @@ void AS4Protocol::receiveBytes(LinkInterface* link) ...@@ -99,13 +99,13 @@ void AS4Protocol::receiveBytes(LinkInterface* link)
{ {
// receiveMutex.lock(); // receiveMutex.lock();
// Prepare buffer // Prepare buffer
static const int maxlen = 4096 * 100; //static const int maxlen = 4096 * 100;
static char buffer[maxlen]; //static char buffer[maxlen];
qint64 bytesToRead = link->bytesAvailable(); qint64 bytesToRead = link->bytesAvailable();
// Get all data at once, let link read the bytes in the buffer array // Get all data at once, let link read the bytes in the buffer array
link->readBytes(buffer, maxlen); //link->readBytes(buffer, maxlen);
// //
// /* // /*
// // Debug output // // Debug output
......
This diff is collapsed.
...@@ -56,7 +56,6 @@ LinkManager::LinkManager() ...@@ -56,7 +56,6 @@ LinkManager::LinkManager()
{ {
links = QList<LinkInterface*>(); links = QList<LinkInterface*>();
protocolLinks = QMap<ProtocolInterface*, LinkInterface*>(); protocolLinks = QMap<ProtocolInterface*, LinkInterface*>();
start(QThread::LowPriority);
} }
LinkManager::~LinkManager() LinkManager::~LinkManager()
...@@ -64,11 +63,6 @@ LinkManager::~LinkManager() ...@@ -64,11 +63,6 @@ LinkManager::~LinkManager()
disconnectAll(); disconnectAll();
} }
void LinkManager::run()
{
}
void LinkManager::add(LinkInterface* link) void LinkManager::add(LinkInterface* link)
{ {
links.append(link); links.append(link);
...@@ -79,7 +73,7 @@ void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol) ...@@ -79,7 +73,7 @@ void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol)
{ {
// Connect link to protocol // Connect link to protocol
// the protocol will receive new bytes from the link // the protocol will receive new bytes from the link
connect(link, SIGNAL(bytesReady(LinkInterface*)), protocol, SLOT(receiveBytes(LinkInterface*))); connect(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)), protocol, SLOT(receiveBytes(LinkInterface*, QByteArray)));
// Store the connection information in the protocol links map // Store the connection information in the protocol links map
protocolLinks.insertMulti(protocol, link); protocolLinks.insertMulti(protocol, link);
//qDebug() << __FILE__ << __LINE__ << "ADDED LINK TO PROTOCOL" << link->getName() << protocol->getName() << "NEW SIZE OF LINK LIST:" << protocolLinks.size(); //qDebug() << __FILE__ << __LINE__ << "ADDED LINK TO PROTOCOL" << link->getName() << protocol->getName() << "NEW SIZE OF LINK LIST:" << protocolLinks.size();
......
...@@ -44,7 +44,8 @@ This file is part of the PIXHAWK project ...@@ -44,7 +44,8 @@ This file is part of the PIXHAWK project
* protocol instance to transport the link data into the application. * protocol instance to transport the link data into the application.
* *
**/ **/
class LinkManager : public QThread { class LinkManager : public QObject
{
Q_OBJECT Q_OBJECT
public: public:
......
...@@ -86,51 +86,53 @@ void MAVLinkLightProtocol::sendMessage(LinkInterface* link, mavlink_light_messag ...@@ -86,51 +86,53 @@ void MAVLinkLightProtocol::sendMessage(LinkInterface* link, mavlink_light_messag
* @param link The interface to read from * @param link The interface to read from
* @see LinkInterface * @see LinkInterface
**/ **/
void MAVLinkLightProtocol::receiveBytes(LinkInterface* link) void MAVLinkLightProtocol::receiveBytes(LinkInterface* link, QByteArray b)
{ {
receiveMutex.lock(); Q_UNUSED(link);
// Prepare buffer Q_UNUSED(b);
static const int maxlen = 4096 * 100; // receiveMutex.lock();
static char buffer[maxlen]; // // Prepare buffer
qint64 bytesToRead = link->bytesAvailable(); // static const int maxlen = 4096 * 100;
// static char buffer[maxlen];
// Get all data at once, let link read the bytes in the buffer array // qint64 bytesToRead = link->bytesAvailable();
link->readBytes(buffer, maxlen); //
// // Get all data at once, let link read the bytes in the buffer array
// Run through all bytes // link->readBytes(buffer, maxlen);
for (int position = 0; position < bytesToRead; position++) //
{ // // Run through all bytes
mavlink_light_message_t msg; // for (int position = 0; position < bytesToRead; position++)
// FIXME PARSE // {
if (1 == 0/* parsing returned a message */) // mavlink_light_message_t msg;
{ // // FIXME PARSE
// if (1 == 0/* parsing returned a message */)
int sysid = 0; // system id from message, or always null if only one MAV is supported // {
UASInterface* uas = UASManager::instance()->getUASForId(sysid); //
// int sysid = 0; // system id from message, or always null if only one MAV is supported
// Check and (if necessary) create UAS object // UASInterface* uas = UASManager::instance()->getUASForId(sysid);
if (uas == NULL) //
{ // // Check and (if necessary) create UAS object
ArduPilotMAV* mav = new ArduPilotMAV(this, sysid); // FIXME change to msg.sysid if this field exists // if (uas == NULL)
// Connect this robot to the UAS object // {
// it is IMPORTANT here to use the right object type, // ArduPilotMAV* mav = new ArduPilotMAV(this, sysid); // FIXME change to msg.sysid if this field exists
// else the slot of the parent object is called (and thus the special // // Connect this robot to the UAS object
// packets never reach their goal) // // it is IMPORTANT here to use the right object type,
connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t))); // // else the slot of the parent object is called (and thus the special
uas = mav; // // packets never reach their goal)
// Make UAS aware that this link can be used to communicate with the actual robot // connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
uas->addLink(link); // uas = mav;
// Now add UAS to "official" list, which makes the whole application aware of it // // Make UAS aware that this link can be used to communicate with the actual robot
UASManager::instance()->addUAS(uas); // uas->addLink(link);
} // // Now add UAS to "official" list, which makes the whole application aware of it
// UASManager::instance()->addUAS(uas);
// The packet is emitted as a whole, as it is only 255 - 261 bytes short // }
// kind of inefficient, but no issue for a groundstation pc. //
// It buys as reentrancy for the whole code over all threads // // The packet is emitted as a whole, as it is only 255 - 261 bytes short
emit messageReceived(link, msg); // // kind of inefficient, but no issue for a groundstation pc.
} // // It buys as reentrancy for the whole code over all threads
} // emit messageReceived(link, msg);
receiveMutex.unlock(); // }
// }
// receiveMutex.unlock();
} }
/** /**
......
...@@ -31,6 +31,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -31,6 +31,7 @@ This file is part of the QGROUNDCONTROL project
#define MAVLINKLIGHTPROTOCOL_H #define MAVLINKLIGHTPROTOCOL_H
#include <inttypes.h> #include <inttypes.h>
#include <QByteArray>
#include <MAVLinkProtocol.h> #include <MAVLinkProtocol.h>
#define MAVLINK_LIGHT_MAX_PAYLOAD_LEN 50 #define MAVLINK_LIGHT_MAX_PAYLOAD_LEN 50
...@@ -59,7 +60,7 @@ signals: ...@@ -59,7 +60,7 @@ signals:
public slots: public slots:
void sendMessage(mavlink_light_message_t message); void sendMessage(mavlink_light_message_t message);
void sendMessage(LinkInterface* link, mavlink_light_message_t message); void sendMessage(LinkInterface* link, mavlink_light_message_t message);
void receiveBytes(LinkInterface* link); void receiveBytes(LinkInterface* link, QByteArray b);
}; };
......
...@@ -108,21 +108,14 @@ QString MAVLinkProtocol::getLogfileName() ...@@ -108,21 +108,14 @@ QString MAVLinkProtocol::getLogfileName()
* @param link The interface to read from * @param link The interface to read from
* @see LinkInterface * @see LinkInterface
**/ **/
void MAVLinkProtocol::receiveBytes(LinkInterface* link) void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
{ {
receiveMutex.lock(); receiveMutex.lock();
// Prepare buffer
static const int maxlen = 4096 * 100;
static char buffer[maxlen];
qint64 bytesToRead = link->bytesAvailable();
// Get all data at once, let link read the bytes in the buffer array
link->readBytes(buffer, maxlen);
mavlink_message_t message; mavlink_message_t message;
mavlink_status_t status; mavlink_status_t status;
for (int position = 0; position < bytesToRead; position++) for (int position = 0; position < b.size(); position++)
{ {
unsigned int decodeState = mavlink_parse_char(link->getId(), (uint8_t)*(buffer + position), &message, &status); unsigned int decodeState = mavlink_parse_char(link->getId(), (uint8_t)(b.at(position)), &message, &status);
if (decodeState == 1) if (decodeState == 1)
{ {
......
...@@ -73,7 +73,7 @@ public: ...@@ -73,7 +73,7 @@ public:
public slots: public slots:
/** @brief Receive bytes from a communication interface */ /** @brief Receive bytes from a communication interface */
void receiveBytes(LinkInterface* link); void receiveBytes(LinkInterface* link, QByteArray b);
/** @brief Send MAVLink message through serial interface */ /** @brief Send MAVLink message through serial interface */
void sendMessage(mavlink_message_t message); void sendMessage(mavlink_message_t message);
/** @brief Send MAVLink message through serial interface */ /** @brief Send MAVLink message through serial interface */
......
...@@ -142,13 +142,7 @@ void MAVLinkSimulationLink::run() ...@@ -142,13 +142,7 @@ void MAVLinkSimulationLink::run()
// } // }
// readyBufferMutex.unlock(); // readyBufferMutex.unlock();
readBytes();
emit bytesReady(this);
} }
last = MG::TIME::getGroundTimeNow(); last = MG::TIME::getGroundTimeNow();
} }
...@@ -752,9 +746,11 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) ...@@ -752,9 +746,11 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
} }
void MAVLinkSimulationLink::readBytes(char* const data, qint64 maxLength) { void MAVLinkSimulationLink::readBytes() {
// Lock concurrent resource readyBuffer // Lock concurrent resource readyBuffer
readyBufferMutex.lock(); readyBufferMutex.lock();
const qint64 maxLength = 2048;
char data[maxLength];
qint64 len = maxLength; qint64 len = maxLength;
if (maxLength > readyBuffer.size()) len = readyBuffer.size(); if (maxLength > readyBuffer.size()) len = readyBuffer.size();
......
...@@ -84,7 +84,7 @@ public: ...@@ -84,7 +84,7 @@ public:
public slots: public slots:
void writeBytes(const char* data, qint64 size); void writeBytes(const char* data, qint64 size);
void readBytes(char* const data, qint64 maxLength); void readBytes();
void mainloop(); void mainloop();
bool connectLink(bool connect); bool connectLink(bool connect);
......
...@@ -42,10 +42,11 @@ void OpalLink::writeBytes(const char *bytes, qint64 length) ...@@ -42,10 +42,11 @@ void OpalLink::writeBytes(const char *bytes, qint64 length)
} }
void OpalLink::readBytes(char *bytes, qint64 maxLength) void OpalLink::readBytes()
{ {
receiveDataMutex.lock(); receiveDataMutex.lock();
const qint64 maxLength = 2048;
char bytes[maxLength];
qDebug() << "OpalLink::readBytes(): Reading a message. size of buffer: " << receiveBuffer->count(); qDebug() << "OpalLink::readBytes(): Reading a message. size of buffer: " << receiveBuffer->count();
QByteArray message = receiveBuffer->dequeue(); QByteArray message = receiveBuffer->dequeue();
if (maxLength < message.size()) if (maxLength < message.size())
...@@ -75,7 +76,7 @@ void OpalLink::receiveMessage(mavlink_message_t message) ...@@ -75,7 +76,7 @@ void OpalLink::receiveMessage(mavlink_message_t message)
if (isConnected()) if (isConnected())
{ {
receiveBuffer->enqueue(QByteArray(buffer, len)); receiveBuffer->enqueue(QByteArray(buffer, len));
emit bytesReady(this); readBytes();
} }
} }
...@@ -95,41 +96,41 @@ void OpalLink::heartbeat() ...@@ -95,41 +96,41 @@ void OpalLink::heartbeat()
void OpalLink::getSignals() void OpalLink::getSignals()
{ {
qDebug() << "OpalLink::getSignals(): Attempting to acquire signals"; // qDebug() << "OpalLink::getSignals(): Attempting to acquire signals";
//
//
unsigned long timeout = 0; // unsigned long timeout = 0;
unsigned short acqGroup = 0; //this is actually group 1 in the model // unsigned short acqGroup = 0; //this is actually group 1 in the model
unsigned short allocatedSignals = NUM_OUTPUT_SIGNALS; // unsigned short allocatedSignals = NUM_OUTPUT_SIGNALS;
unsigned short *numSignals = new unsigned short(0); // unsigned short *numSignals = new unsigned short(0);
double *timestep = new double(0); // double *timestep = new double(0);
double values[NUM_OUTPUT_SIGNALS] = {}; // double values[NUM_OUTPUT_SIGNALS] = {};
unsigned short *lastValues = new unsigned short(false); // unsigned short *lastValues = new unsigned short(false);
unsigned short *decimation = new unsigned short(0); // unsigned short *decimation = new unsigned short(0);
//
int returnVal = OpalGetSignals(timeout, acqGroup, allocatedSignals, numSignals, timestep, // int returnVal = OpalGetSignals(timeout, acqGroup, allocatedSignals, numSignals, timestep,
values, lastValues, decimation); // values, lastValues, decimation);
//
if (returnVal == EOK ) // if (returnVal == EOK )
{ // {
qDebug() << "OpalLink::getSignals: Timestep=" << *timestep;// << ", Last? " << (bool)(*lastValues); // qDebug() << "OpalLink::getSignals: Timestep=" << *timestep;// << ", Last? " << (bool)(*lastValues);
} // }
else if (returnVal == EAGAIN) // else if (returnVal == EAGAIN)
{ // {
qDebug() << "OpalLink::getSignals: Data was not ready"; // qDebug() << "OpalLink::getSignals: Data was not ready";
} // }
// if returnVal == EAGAIN => data just wasn't ready // // if returnVal == EAGAIN => data just wasn't ready
else if (returnVal != EAGAIN) // else if (returnVal != EAGAIN)
{ // {
getSignalsTimer->stop(); // getSignalsTimer->stop();
displayErrorMsg(); // displayErrorMsg();
} // }
/* deallocate used memory */ // /* deallocate used memory */
//
delete timestep; // delete timestep;
delete lastValues; // delete lastValues;
delete lastValues; // delete lastValues;
delete decimation; // delete decimation;
} }
...@@ -172,18 +173,18 @@ bool OpalLink::connect() ...@@ -172,18 +173,18 @@ bool OpalLink::connect()
short modelState; short modelState;
/// \todo allow configuration of instid in window /// \todo allow configuration of instid in window
if (OpalConnect(101, false, &modelState) == EOK) // if (OpalConnect(101, false, &modelState) == EOK)
{ // {
connectState = true; connectState = true;
emit connected(); emit connected();
heartbeatTimer->start(1000/heartbeatRate); heartbeatTimer->start(1000/heartbeatRate);
getSignalsTimer->start(getSignalsPeriod); getSignalsTimer->start(getSignalsPeriod);
} // }
else // else
{ // {
connectState = false; // connectState = false;
displayErrorMsg(); // displayErrorMsg();
} // }
emit connected(connectState); emit connected(connectState);
return connectState; return connectState;
...@@ -205,11 +206,11 @@ void OpalLink::displayErrorMsg() ...@@ -205,11 +206,11 @@ void OpalLink::displayErrorMsg()
void OpalLink::setLastErrorMsg() void OpalLink::setLastErrorMsg()
{ {
char buf[512]; // char buf[512];
unsigned short len; // unsigned short len;
OpalGetLastErrMsg(buf, sizeof(buf), &len); // OpalGetLastErrMsg(buf, sizeof(buf), &len);
lastErrorMsg.clear(); // lastErrorMsg.clear();
lastErrorMsg.append(buf); // lastErrorMsg.append(buf);
} }
......
...@@ -23,7 +23,17 @@ ...@@ -23,7 +23,17 @@
#include "configuration.h" #include "configuration.h"
#include "errno.h" #include "errno.h"
#include "OpalApi.h"
// FIXME
//#include "OpalApi.h"
#include "string.h" #include "string.h"
/* /*
...@@ -74,7 +84,7 @@ public slots: ...@@ -74,7 +84,7 @@ public slots:
void writeBytes(const char *bytes, qint64 length); void writeBytes(const char *bytes, qint64 length);
void readBytes(char *bytes, qint64 maxLength); void readBytes();
void heartbeat(); void heartbeat();
......
...@@ -34,6 +34,7 @@ This file is part of the PIXHAWK project ...@@ -34,6 +34,7 @@ This file is part of the PIXHAWK project
#include <QThread> #include <QThread>
#include <QString> #include <QString>
#include <QByteArray>
#include "LinkInterface.h" #include "LinkInterface.h"
/** /**
...@@ -53,7 +54,7 @@ public: ...@@ -53,7 +54,7 @@ public:
virtual QString getName() = 0; virtual QString getName() = 0;
public slots: public slots:
virtual void receiveBytes(LinkInterface *link) = 0; virtual void receiveBytes(LinkInterface *link, QByteArray b) = 0;
signals: signals:
/** @brief Update the packet loss from one system */ /** @brief Update the packet loss from one system */
......
...@@ -114,13 +114,14 @@ SerialLink::~SerialLink() ...@@ -114,13 +114,14 @@ SerialLink::~SerialLink()
* @brief Runs the thread * @brief Runs the thread
* *
**/ **/
void SerialLink::run() { void SerialLink::run()
{
// Initialize the connection // Initialize the connection
hardwareConnect(); hardwareConnect();
// Qt way to make clear what a while(1) loop does // Qt way to make clear what a while(1) loop does
forever { forever
{
// Check if new bytes have arrived, if yes, emit the notification signal // Check if new bytes have arrived, if yes, emit the notification signal
checkForBytes(); checkForBytes();
/* Serial data isn't arriving that fast normally, this saves the thread /* Serial data isn't arriving that fast normally, this saves the thread
...@@ -128,30 +129,33 @@ void SerialLink::run() { ...@@ -128,30 +129,33 @@ void SerialLink::run() {
*/ */
MG::SLEEP::msleep(SerialLink::poll_interval); MG::SLEEP::msleep(SerialLink::poll_interval);
} }
} }
void SerialLink::checkForBytes() { void SerialLink::checkForBytes()
{
/* Check if bytes are available */ /* Check if bytes are available */
if(port->isOpen()) { if(port->isOpen())
{
dataMutex.lock(); dataMutex.lock();
qint64 available = port->bytesAvailable(); qint64 available = port->bytesAvailable();
dataMutex.unlock(); dataMutex.unlock();
if(available > 0) { if(available > 0)
emit bytesReady(this); {
//qDebug() << "Bytes available" << available << "connected:" << port->isOpen(); readBytes();
} }
} else { }
else
{
emit disconnected(); emit disconnected();
} }
} }
void SerialLink::writeBytes(const char* data, qint64 size) { void SerialLink::writeBytes(const char* data, qint64 size)
{
if(port->isOpen()) if(port->isOpen())
{ {
int b = port->write(data, size); int b = port->write(data, size);
...@@ -176,17 +180,20 @@ void SerialLink::writeBytes(const char* data, qint64 size) { ...@@ -176,17 +180,20 @@ void SerialLink::writeBytes(const char* data, qint64 size) {
* @param data Pointer to the data byte array to write the bytes to * @param data Pointer to the data byte array to write the bytes to
* @param maxLength The maximum number of bytes to write * @param maxLength The maximum number of bytes to write
**/ **/
void SerialLink::readBytes(char* data, qint64 maxLength) { void SerialLink::readBytes()
{
dataMutex.lock(); dataMutex.lock();
if(port->isOpen()) { if(port->isOpen())
{
const qint64 maxLength = 2048;
char data[maxLength];
qint64 numBytes = port->bytesAvailable(); qint64 numBytes = port->bytesAvailable();
if(numBytes > 0) { if(numBytes > 0)
{
/* Read as much data in buffer as possible without overflow */ /* Read as much data in buffer as possible without overflow */
if(maxLength < numBytes) numBytes = maxLength; if(maxLength < numBytes) numBytes = maxLength;
port->read(data, numBytes); port->read(data, numBytes);
// FIXME TODO Check if this method should be preferred over manual read by process
QByteArray b(data, numBytes); QByteArray b(data, numBytes);
emit bytesReceived(this, b); emit bytesReceived(this, b);
...@@ -210,23 +217,18 @@ void SerialLink::readBytes(char* data, qint64 maxLength) { ...@@ -210,23 +217,18 @@ void SerialLink::readBytes(char* data, qint64 maxLength) {
* *
* @return The number of bytes to read * @return The number of bytes to read
**/ **/
qint64 SerialLink::bytesAvailable() { qint64 SerialLink::bytesAvailable()
{
return port->bytesAvailable(); return port->bytesAvailable();
} }
/**
* @brief Convenience method to emit the bytesReady signal
**/
void SerialLink::emitBytesReady() {
emit bytesReady(this);
}
/** /**
* @brief Disconnect the connection. * @brief Disconnect the connection.
* *
* @return True if connection has been disconnected, false if connection couldn't be disconnected. * @return True if connection has been disconnected, false if connection couldn't be disconnected.
**/ **/
bool SerialLink::disconnect() { bool SerialLink::disconnect()
{
//#if !defined _WIN32 || !defined _WIN64 //#if !defined _WIN32 || !defined _WIN64
/* Block the thread until it returns from run() */ /* Block the thread until it returns from run() */
//#endif //#endif
...@@ -276,10 +278,8 @@ bool SerialLink::connect() ...@@ -276,10 +278,8 @@ bool SerialLink::connect()
* @return True if the connection could be established, false otherwise * @return True if the connection could be established, false otherwise
* @see connect() For the right function to establish the connection. * @see connect() For the right function to establish the connection.
**/ **/
bool SerialLink::hardwareConnect() { bool SerialLink::hardwareConnect()
{
qDebug() << "Opening serial port" << porthandle;
QObject::connect(port, SIGNAL(aboutToClose()), this, SIGNAL(disconnected())); QObject::connect(port, SIGNAL(aboutToClose()), this, SIGNAL(disconnected()));
port->open(QIODevice::ReadWrite); port->open(QIODevice::ReadWrite);
...@@ -300,12 +300,15 @@ bool SerialLink::hardwareConnect() { ...@@ -300,12 +300,15 @@ bool SerialLink::hardwareConnect() {
return connectionUp; return connectionUp;
} }
/** /**
* @brief Check if connection is active. * @brief Check if connection is active.
* *
* @return True if link is connected, false otherwise. * @return True if link is connected, false otherwise.
**/ **/
bool SerialLink::isConnected() { bool SerialLink::isConnected()
{
return port->isOpen(); return port->isOpen();
} }
...@@ -326,7 +329,8 @@ void SerialLink::setName(QString name) ...@@ -326,7 +329,8 @@ void SerialLink::setName(QString name)
} }
qint64 SerialLink::getNominalDataRate() { qint64 SerialLink::getNominalDataRate()
{
qint64 dataRate = 0; qint64 dataRate = 0;
switch (baudrate) { switch (baudrate) {
case BAUD50: case BAUD50:
...@@ -399,77 +403,94 @@ qint64 SerialLink::getNominalDataRate() { ...@@ -399,77 +403,94 @@ qint64 SerialLink::getNominalDataRate() {
return dataRate; return dataRate;
} }
qint64 SerialLink::getTotalUpstream() { qint64 SerialLink::getTotalUpstream()
{
statisticsMutex.lock(); statisticsMutex.lock();
return bitsSentTotal / ((MG::TIME::getGroundTimeNow() - connectionStartTime) / 1000); return bitsSentTotal / ((MG::TIME::getGroundTimeNow() - connectionStartTime) / 1000);
statisticsMutex.unlock(); statisticsMutex.unlock();
} }
qint64 SerialLink::getCurrentUpstream() { qint64 SerialLink::getCurrentUpstream()
{
return 0; // TODO return 0; // TODO
} }
qint64 SerialLink::getMaxUpstream() { qint64 SerialLink::getMaxUpstream()
{
return 0; // TODO return 0; // TODO
} }
qint64 SerialLink::getBitsSent() { qint64 SerialLink::getBitsSent()
{
return bitsSentTotal; return bitsSentTotal;
} }
qint64 SerialLink::getBitsReceived() { qint64 SerialLink::getBitsReceived()
{
return bitsReceivedTotal; return bitsReceivedTotal;
} }
qint64 SerialLink::getTotalDownstream() { qint64 SerialLink::getTotalDownstream()
{
statisticsMutex.lock(); statisticsMutex.lock();
return bitsReceivedTotal / ((MG::TIME::getGroundTimeNow() - connectionStartTime) / 1000); return bitsReceivedTotal / ((MG::TIME::getGroundTimeNow() - connectionStartTime) / 1000);
statisticsMutex.unlock(); statisticsMutex.unlock();
} }
qint64 SerialLink::getCurrentDownstream() { qint64 SerialLink::getCurrentDownstream()
{
return 0; // TODO return 0; // TODO
} }
qint64 SerialLink::getMaxDownstream() { qint64 SerialLink::getMaxDownstream()
{
return 0; // TODO return 0; // TODO
} }
bool SerialLink::isFullDuplex() { bool SerialLink::isFullDuplex()
{
/* Serial connections are always half duplex */ /* Serial connections are always half duplex */
return false; return false;
} }
int SerialLink::getLinkQuality() { int SerialLink::getLinkQuality()
{
/* This feature is not supported with this interface */ /* This feature is not supported with this interface */
return -1; return -1;
} }
QString SerialLink::getPortName() { QString SerialLink::getPortName()
{
return porthandle; return porthandle;
} }
int SerialLink::getBaudRate() { int SerialLink::getBaudRate()
{
return getNominalDataRate(); return getNominalDataRate();
} }
int SerialLink::getBaudRateType() { int SerialLink::getBaudRateType()
{
return baudrate; return baudrate;
} }
int SerialLink::getFlowType() { int SerialLink::getFlowType()
{
return flow; return flow;
} }
int SerialLink::getParityType() { int SerialLink::getParityType()
{
return parity; return parity;
} }
int SerialLink::getDataBitsType() { int SerialLink::getDataBitsType()
{
return dataBits; return dataBits;
} }
int SerialLink::getStopBitsType() { int SerialLink::getStopBitsType()
{
return stopBits; return stopBits;
} }
...@@ -689,7 +710,8 @@ bool SerialLink::setBaudRate(int rate) ...@@ -689,7 +710,8 @@ bool SerialLink::setBaudRate(int rate)
return accepted; return accepted;
} }
bool SerialLink::setFlowType(int flow) { bool SerialLink::setFlowType(int flow)
{
bool reconnect = false; bool reconnect = false;
bool accepted = true; bool accepted = true;
if(isConnected()) { if(isConnected()) {
...@@ -717,7 +739,8 @@ bool SerialLink::setFlowType(int flow) { ...@@ -717,7 +739,8 @@ bool SerialLink::setFlowType(int flow) {
return accepted; return accepted;
} }
bool SerialLink::setParityType(int parity) { bool SerialLink::setParityType(int parity)
{
bool reconnect = false; bool reconnect = false;
bool accepted = true; bool accepted = true;
if(isConnected()) { if(isConnected()) {
...@@ -752,7 +775,8 @@ bool SerialLink::setParityType(int parity) { ...@@ -752,7 +775,8 @@ bool SerialLink::setParityType(int parity) {
return accepted; return accepted;
} }
bool SerialLink::setDataBitsType(int dataBits) { bool SerialLink::setDataBitsType(int dataBits)
{
bool accepted = true; bool accepted = true;
switch (dataBits) { switch (dataBits) {
...@@ -783,7 +807,8 @@ bool SerialLink::setDataBitsType(int dataBits) { ...@@ -783,7 +807,8 @@ bool SerialLink::setDataBitsType(int dataBits) {
return accepted; return accepted;
} }
bool SerialLink::setStopBitsType(int stopBits) { bool SerialLink::setStopBitsType(int stopBits)
{
bool reconnect = false; bool reconnect = false;
bool accepted = true; bool accepted = true;
if(isConnected()) { if(isConnected()) {
......
...@@ -106,7 +106,7 @@ public slots: ...@@ -106,7 +106,7 @@ public slots:
bool setDataBitsType(int dataBits); bool setDataBitsType(int dataBits);
bool setStopBitsType(int stopBits); bool setStopBitsType(int stopBits);
void readBytes(char* data, qint64 maxLength); void readBytes();
/** /**
* @brief Write a number of bytes to the interface. * @brief Write a number of bytes to the interface.
* *
...@@ -118,7 +118,6 @@ public slots: ...@@ -118,7 +118,6 @@ public slots:
bool disconnect(); bool disconnect();
protected slots: protected slots:
void emitBytesReady();
void checkForBytes(); void checkForBytes();
protected: protected:
......
This diff is collapsed.
...@@ -95,7 +95,7 @@ public slots: ...@@ -95,7 +95,7 @@ public slots:
void readLine(); void readLine();
void writeBytes(char *bytes, qint64 length); void writeBytes(char *bytes, qint64 length);
void readBytes(char *bytes, qint64 maxLength); void readBytes();
bool connect(); bool connect();
bool disconnect(); bool disconnect();
......
...@@ -120,8 +120,10 @@ void UDPLink::writeBytes(const char* data, qint64 size) ...@@ -120,8 +120,10 @@ void UDPLink::writeBytes(const char* data, qint64 size)
* @param data Pointer to the data byte array to write the bytes to * @param data Pointer to the data byte array to write the bytes to
* @param maxLength The maximum number of bytes to write * @param maxLength The maximum number of bytes to write
**/ **/
void UDPLink::readBytes(char* data, qint64 maxLength) void UDPLink::readBytes()
{ {
const qint64 maxLength = 2048;
char data[maxLength];
QHostAddress sender; QHostAddress sender;
quint16 senderPort; quint16 senderPort;
...@@ -169,14 +171,6 @@ qint64 UDPLink::bytesAvailable() { ...@@ -169,14 +171,6 @@ qint64 UDPLink::bytesAvailable() {
return socket->pendingDatagramSize(); return socket->pendingDatagramSize();
} }
/**
* @brief Convenience method to emit the bytesReady signal
**/
void UDPLink::emitBytesReady()
{
emit bytesReady(this);
}
/** /**
* @brief Disconnect the connection. * @brief Disconnect the connection.
* *
...@@ -204,7 +198,7 @@ bool UDPLink::connect() ...@@ -204,7 +198,7 @@ bool UDPLink::connect()
socket = new QUdpSocket(this); socket = new QUdpSocket(this);
//QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readPendingDatagrams())); //QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readPendingDatagrams()));
QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(emitBytesReady())); QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes()));
connectState = socket->bind(host, port); connectState = socket->bind(host, port);
...@@ -244,6 +238,7 @@ void UDPLink::setName(QString name) ...@@ -244,6 +238,7 @@ void UDPLink::setName(QString name)
emit nameChanged(this->name); emit nameChanged(this->name);
} }
qint64 UDPLink::getNominalDataRate() { qint64 UDPLink::getNominalDataRate() {
return 54000000; // 54 Mbit return 54000000; // 54 Mbit
} }
......
...@@ -48,8 +48,6 @@ public: ...@@ -48,8 +48,6 @@ public:
UDPLink(QHostAddress host = QHostAddress::Any, quint16 port = 14550); UDPLink(QHostAddress host = QHostAddress::Any, quint16 port = 14550);
~UDPLink(); ~UDPLink();
static const int poll_interval = UDP_POLL_INTERVAL; ///< Polling interval, defined in configuration.h
bool isConnected(); bool isConnected();
qint64 bytesAvailable(); qint64 bytesAvailable();
...@@ -86,7 +84,7 @@ public slots: ...@@ -86,7 +84,7 @@ public slots:
void setPort(quint16 port); void setPort(quint16 port);
// void readPendingDatagrams(); // void readPendingDatagrams();
void readBytes(char* data, qint64 maxLength); void readBytes();
/** /**
* @brief Write a number of bytes to the interface. * @brief Write a number of bytes to the interface.
* *
...@@ -97,10 +95,6 @@ public slots: ...@@ -97,10 +95,6 @@ public slots:
bool connect(); bool connect();
bool disconnect(); bool disconnect();
protected slots:
void emitBytesReady();
//void checkForBytes();
protected: protected:
QString name; QString name;
QHostAddress host; QHostAddress host;
......
...@@ -2,9 +2,7 @@ ...@@ -2,9 +2,7 @@
#define CONFIGURATION_H #define CONFIGURATION_H
/** @brief Polling interval in ms */ /** @brief Polling interval in ms */
#define SERIAL_POLL_INTERVAL 1 #define SERIAL_POLL_INTERVAL 2
/** @brief UDP polling interval in ms */
#define UDP_POLL_INTERVAL 1
/** @brief Heartbeat emission rate, in Hertz (times per second) */ /** @brief Heartbeat emission rate, in Hertz (times per second) */
#define MAVLINK_HEARTBEAT_DEFAULT_RATE 1 #define MAVLINK_HEARTBEAT_DEFAULT_RATE 1
...@@ -12,6 +10,6 @@ ...@@ -12,6 +10,6 @@
#define WITH_TEXT_TO_SPEECH 1 #define WITH_TEXT_TO_SPEECH 1
#define QGC_APPLICATION_NAME "QGroundControl" #define QGC_APPLICATION_NAME "QGroundControl"
#define QGC_APPLICATION_VERSION "v. 0.7.6 (Beta)" #define QGC_APPLICATION_VERSION "v. 0.7.7 (Beta)"
#endif // CONFIGURATION_H #endif // CONFIGURATION_H
...@@ -39,8 +39,12 @@ This file is part of the PIXHAWK project ...@@ -39,8 +39,12 @@ This file is part of the PIXHAWK project
#include "CommConfigurationWindow.h" #include "CommConfigurationWindow.h"
#include "SerialConfigurationWindow.h" #include "SerialConfigurationWindow.h"
#include "SerialLinkInterface.h" #include "SerialLink.h"
#include "UDPLink.h" #include "UDPLink.h"
#include "MAVLinkSimulationLink.h"
#ifdef OPAL_RT
#include "OpalLink.h"
#endif
#include "MAVLinkProtocol.h" #include "MAVLinkProtocol.h"
#include "MAVLinkSettingsWidget.h" #include "MAVLinkSettingsWidget.h"
...@@ -86,7 +90,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn ...@@ -86,7 +90,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
// TODO Move these calls to each link so that dynamic casts vanish // TODO Move these calls to each link so that dynamic casts vanish
// Open details pane for serial link if necessary // Open details pane for serial link if necessary
SerialLinkInterface* serial = dynamic_cast<SerialLinkInterface*>(link); SerialLink* serial = dynamic_cast<SerialLink*>(link);
if(serial != 0) if(serial != 0)
{ {
QWidget* conf = new SerialConfigurationWindow(serial, this); QWidget* conf = new SerialConfigurationWindow(serial, this);
...@@ -97,17 +101,28 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn ...@@ -97,17 +101,28 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
//ui.linkGroupBox->setTitle(link->getName()); //ui.linkGroupBox->setTitle(link->getName());
//connect(link, SIGNAL(nameChanged(QString)), ui.linkGroupBox, SLOT(setTitle(QString))); //connect(link, SIGNAL(nameChanged(QString)), ui.linkGroupBox, SLOT(setTitle(QString)));
} }
else if (dynamic_cast<UDPLink*>(link) != 0) UDPLink* udp = dynamic_cast<UDPLink*>(link);
if (udp != 0)
{ {
ui.linkGroupBox->setTitle(tr("UDP Link")); ui.linkGroupBox->setTitle(tr("UDP Link"));
} }
MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
if (sim != 0)
{
ui.linkGroupBox->setTitle(tr("MAVLink Simulation Link"));
}
#ifdef OPAL_RT #ifdef OPAL_RT
else if (dynamic_cast<OpalLink*>(link) != 0) OpalLink* opal = dynamic_cast<OpalLink*>(link);
if (opal != 0)
{ {
ui.linkGroupBox->setTitle(tr("Opal-RT Link")); ui.linkGroupBox->setTitle(tr("Opal-RT Link"));
} }
#endif #endif
else if (serial == 0 && udp == 0 && sim == 0
#ifdef OPAL_RT
&& opal == 0
#endif
)
{ {
qDebug() << "Link is NOT a known link, can't open configuration window"; qDebug() << "Link is NOT a known link, can't open configuration window";
} }
......
...@@ -574,7 +574,7 @@ void HUD::paintHUD() ...@@ -574,7 +574,7 @@ void HUD::paintHUD()
if ((yawTrans < 5.0) && (yawTrans > -5.0)) yawTrans = 0; if ((yawTrans < 5.0) && (yawTrans > -5.0)) yawTrans = 0;
qDebug() << "yaw translation" << yawTrans << "integral" << yawInt << "difference" << yawDiff << "yaw" << yaw; //qDebug() << "yaw translation" << yawTrans << "integral" << yawInt << "difference" << yawDiff << "yaw" << yaw;
// Update scaling factor // Update scaling factor
// adjust scaling to fit both horizontally and vertically // adjust scaling to fit both horizontally and vertically
......
...@@ -374,9 +374,9 @@ void MainWindow::addLink() ...@@ -374,9 +374,9 @@ void MainWindow::addLink()
void MainWindow::addLink(LinkInterface *link) void MainWindow::addLink(LinkInterface *link)
{ {
LinkManager::instance()->addProtocol(link, mavlink);
CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this); CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this);
ui.menuNetwork->addAction(commWidget->getAction()); ui.menuNetwork->addAction(commWidget->getAction());
LinkManager::instance()->addProtocol(link, mavlink);
// Special case for simulationlink // Special case for simulationlink
MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link); MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
......
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