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 {
HEADERS += src/comm/OpalLink.h
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
#include "MainWindow.h"
#include "GAudioOutput.h"
#ifdef OPAL_RT
#include "OpalLink.h"
#endif
#include "UDPLink.h"
#include "MAVLinkSimulationLink.h"
......@@ -136,6 +139,8 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
// Add OpalRT Link, but do not connect
OpalLink* opalLink = new OpalLink();
mainWindow->addLink(opalLink);
opalLink->connect();
#warning OPAL LINK NOW AUTO CONNECTING IN CORE.CC
#endif
// MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(MG::DIR::getSupportFilesDirectory() + "/demo-log.txt");
MAVLinkSimulationLink* simulationLink = new MAVLinkSimulationLink(":/demo-log.txt");
......
......@@ -99,13 +99,13 @@ void AS4Protocol::receiveBytes(LinkInterface* link)
{
// receiveMutex.lock();
// Prepare buffer
static const int maxlen = 4096 * 100;
static char buffer[maxlen];
//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);
//link->readBytes(buffer, maxlen);
//
// /*
// // Debug output
......
This diff is collapsed.
......@@ -56,7 +56,6 @@ LinkManager::LinkManager()
{
links = QList<LinkInterface*>();
protocolLinks = QMap<ProtocolInterface*, LinkInterface*>();
start(QThread::LowPriority);
}
LinkManager::~LinkManager()
......@@ -64,11 +63,6 @@ LinkManager::~LinkManager()
disconnectAll();
}
void LinkManager::run()
{
}
void LinkManager::add(LinkInterface* link)
{
links.append(link);
......@@ -79,7 +73,7 @@ void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol)
{
// Connect link to protocol
// 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
protocolLinks.insertMulti(protocol, link);
//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
* protocol instance to transport the link data into the application.
*
**/
class LinkManager : public QThread {
class LinkManager : public QObject
{
Q_OBJECT
public:
......
......@@ -86,51 +86,53 @@ void MAVLinkLightProtocol::sendMessage(LinkInterface* link, mavlink_light_messag
* @param link The interface to read from
* @see LinkInterface
**/
void MAVLinkLightProtocol::receiveBytes(LinkInterface* link)
void MAVLinkLightProtocol::receiveBytes(LinkInterface* link, QByteArray b)
{
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);
// Run through all bytes
for (int position = 0; position < bytesToRead; position++)
{
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);
// Check and (if necessary) create UAS object
if (uas == NULL)
{
ArduPilotMAV* mav = new ArduPilotMAV(this, sysid); // FIXME change to msg.sysid if this field exists
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
// packets never reach their goal)
connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
uas = mav;
// Make UAS aware that this link can be used to communicate with the actual robot
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
emit messageReceived(link, msg);
}
}
receiveMutex.unlock();
Q_UNUSED(link);
Q_UNUSED(b);
// 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);
//
// // Run through all bytes
// for (int position = 0; position < bytesToRead; position++)
// {
// 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);
//
// // Check and (if necessary) create UAS object
// if (uas == NULL)
// {
// ArduPilotMAV* mav = new ArduPilotMAV(this, sysid); // FIXME change to msg.sysid if this field exists
// // Connect this robot to the UAS object
// // it is IMPORTANT here to use the right object type,
// // else the slot of the parent object is called (and thus the special
// // packets never reach their goal)
// connect(this, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
// uas = mav;
// // Make UAS aware that this link can be used to communicate with the actual robot
// 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
// emit messageReceived(link, msg);
// }
// }
// receiveMutex.unlock();
}
/**
......
......@@ -31,6 +31,7 @@ This file is part of the QGROUNDCONTROL project
#define MAVLINKLIGHTPROTOCOL_H
#include <inttypes.h>
#include <QByteArray>
#include <MAVLinkProtocol.h>
#define MAVLINK_LIGHT_MAX_PAYLOAD_LEN 50
......@@ -59,7 +60,7 @@ signals:
public slots:
void sendMessage(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()
* @param link The interface to read from
* @see LinkInterface
**/
void MAVLinkProtocol::receiveBytes(LinkInterface* link)
void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
{
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_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)
{
......
......@@ -73,7 +73,7 @@ public:
public slots:
/** @brief Receive bytes from a communication interface */
void receiveBytes(LinkInterface* link);
void receiveBytes(LinkInterface* link, QByteArray b);
/** @brief Send MAVLink message through serial interface */
void sendMessage(mavlink_message_t message);
/** @brief Send MAVLink message through serial interface */
......
......@@ -142,13 +142,7 @@ void MAVLinkSimulationLink::run()
// }
// readyBufferMutex.unlock();
emit bytesReady(this);
readBytes();
}
last = MG::TIME::getGroundTimeNow();
}
......@@ -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
readyBufferMutex.lock();
const qint64 maxLength = 2048;
char data[maxLength];
qint64 len = maxLength;
if (maxLength > readyBuffer.size()) len = readyBuffer.size();
......
......@@ -84,7 +84,7 @@ public:
public slots:
void writeBytes(const char* data, qint64 size);
void readBytes(char* const data, qint64 maxLength);
void readBytes();
void mainloop();
bool connectLink(bool connect);
......
......@@ -42,10 +42,11 @@ void OpalLink::writeBytes(const char *bytes, qint64 length)
}
void OpalLink::readBytes(char *bytes, qint64 maxLength)
void OpalLink::readBytes()
{
receiveDataMutex.lock();
const qint64 maxLength = 2048;
char bytes[maxLength];
qDebug() << "OpalLink::readBytes(): Reading a message. size of buffer: " << receiveBuffer->count();
QByteArray message = receiveBuffer->dequeue();
if (maxLength < message.size())
......@@ -75,7 +76,7 @@ void OpalLink::receiveMessage(mavlink_message_t message)
if (isConnected())
{
receiveBuffer->enqueue(QByteArray(buffer, len));
emit bytesReady(this);
readBytes();
}
}
......@@ -95,41 +96,41 @@ void OpalLink::heartbeat()
void OpalLink::getSignals()
{
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;
// 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;
}
......@@ -172,18 +173,18 @@ bool OpalLink::connect()
short modelState;
/// \todo allow configuration of instid in window
if (OpalConnect(101, false, &modelState) == EOK)
{
// if (OpalConnect(101, false, &modelState) == EOK)
// {
connectState = true;
emit connected();
heartbeatTimer->start(1000/heartbeatRate);
getSignalsTimer->start(getSignalsPeriod);
}
else
{
connectState = false;
displayErrorMsg();
}
// }
// else
// {
// connectState = false;
// displayErrorMsg();
// }
emit connected(connectState);
return connectState;
......@@ -205,11 +206,11 @@ void OpalLink::displayErrorMsg()
void OpalLink::setLastErrorMsg()
{
char buf[512];
unsigned short len;
OpalGetLastErrMsg(buf, sizeof(buf), &len);
lastErrorMsg.clear();
lastErrorMsg.append(buf);
// char buf[512];
// unsigned short len;
// OpalGetLastErrMsg(buf, sizeof(buf), &len);
// lastErrorMsg.clear();
// lastErrorMsg.append(buf);
}
......
......@@ -23,7 +23,17 @@
#include "configuration.h"
#include "errno.h"
#include "OpalApi.h"
// FIXME
//#include "OpalApi.h"
#include "string.h"
/*
......@@ -74,7 +84,7 @@ public slots:
void writeBytes(const char *bytes, qint64 length);
void readBytes(char *bytes, qint64 maxLength);
void readBytes();
void heartbeat();
......
......@@ -34,6 +34,7 @@ This file is part of the PIXHAWK project
#include <QThread>
#include <QString>
#include <QByteArray>
#include "LinkInterface.h"
/**
......@@ -53,7 +54,7 @@ public:
virtual QString getName() = 0;
public slots:
virtual void receiveBytes(LinkInterface *link) = 0;
virtual void receiveBytes(LinkInterface *link, QByteArray b) = 0;
signals:
/** @brief Update the packet loss from one system */
......
......@@ -114,13 +114,14 @@ SerialLink::~SerialLink()
* @brief Runs the thread
*
**/
void SerialLink::run() {
void SerialLink::run()
{
// Initialize the connection
hardwareConnect();
// 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
checkForBytes();
/* Serial data isn't arriving that fast normally, this saves the thread
......@@ -128,30 +129,33 @@ void SerialLink::run() {
*/
MG::SLEEP::msleep(SerialLink::poll_interval);
}
}
void SerialLink::checkForBytes() {
void SerialLink::checkForBytes()
{
/* Check if bytes are available */
if(port->isOpen()) {
if(port->isOpen())
{
dataMutex.lock();
qint64 available = port->bytesAvailable();
dataMutex.unlock();
if(available > 0) {
emit bytesReady(this);
//qDebug() << "Bytes available" << available << "connected:" << port->isOpen();
if(available > 0)
{
readBytes();
}
} else {
}
else
{
emit disconnected();
}
}
void SerialLink::writeBytes(const char* data, qint64 size) {
void SerialLink::writeBytes(const char* data, qint64 size)
{
if(port->isOpen())
{
int b = port->write(data, 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 maxLength The maximum number of bytes to write
**/
void SerialLink::readBytes(char* data, qint64 maxLength) {
void SerialLink::readBytes()
{
dataMutex.lock();
if(port->isOpen()) {
if(port->isOpen())
{
const qint64 maxLength = 2048;
char data[maxLength];
qint64 numBytes = port->bytesAvailable();
if(numBytes > 0) {
if(numBytes > 0)
{
/* Read as much data in buffer as possible without overflow */
if(maxLength < numBytes) numBytes = maxLength;
port->read(data, numBytes);
// FIXME TODO Check if this method should be preferred over manual read by process
QByteArray b(data, numBytes);
emit bytesReceived(this, b);
......@@ -210,23 +217,18 @@ void SerialLink::readBytes(char* data, qint64 maxLength) {
*
* @return The number of bytes to read
**/
qint64 SerialLink::bytesAvailable() {
qint64 SerialLink::bytesAvailable()
{
return port->bytesAvailable();
}
/**
* @brief Convenience method to emit the bytesReady signal
**/
void SerialLink::emitBytesReady() {
emit bytesReady(this);
}
/**
* @brief Disconnect the connection.
*
* @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
/* Block the thread until it returns from run() */
//#endif
......@@ -276,10 +278,8 @@ bool SerialLink::connect()
* @return True if the connection could be established, false otherwise
* @see connect() For the right function to establish the connection.
**/
bool SerialLink::hardwareConnect() {
qDebug() << "Opening serial port" << porthandle;
bool SerialLink::hardwareConnect()
{
QObject::connect(port, SIGNAL(aboutToClose()), this, SIGNAL(disconnected()));
port->open(QIODevice::ReadWrite);
......@@ -300,12 +300,15 @@ bool SerialLink::hardwareConnect() {
return connectionUp;
}
/**
* @brief Check if connection is active.
*
* @return True if link is connected, false otherwise.
**/
bool SerialLink::isConnected() {
bool SerialLink::isConnected()
{
return port->isOpen();
}
......@@ -326,7 +329,8 @@ void SerialLink::setName(QString name)
}
qint64 SerialLink::getNominalDataRate() {
qint64 SerialLink::getNominalDataRate()
{
qint64 dataRate = 0;
switch (baudrate) {
case BAUD50:
......@@ -399,77 +403,94 @@ qint64 SerialLink::getNominalDataRate() {
return dataRate;
}
qint64 SerialLink::getTotalUpstream() {
qint64 SerialLink::getTotalUpstream()
{
statisticsMutex.lock();
return bitsSentTotal / ((MG::TIME::getGroundTimeNow() - connectionStartTime) / 1000);
statisticsMutex.unlock();
}
qint64 SerialLink::getCurrentUpstream() {
qint64 SerialLink::getCurrentUpstream()
{
return 0; // TODO
}
qint64 SerialLink::getMaxUpstream() {
qint64 SerialLink::getMaxUpstream()
{
return 0; // TODO
}
qint64 SerialLink::getBitsSent() {
qint64 SerialLink::getBitsSent()
{
return bitsSentTotal;
}
qint64 SerialLink::getBitsReceived() {
qint64 SerialLink::getBitsReceived()
{
return bitsReceivedTotal;
}
qint64 SerialLink::getTotalDownstream() {
qint64 SerialLink::getTotalDownstream()
{
statisticsMutex.lock();
return bitsReceivedTotal / ((MG::TIME::getGroundTimeNow() - connectionStartTime) / 1000);
statisticsMutex.unlock();
}
qint64 SerialLink::getCurrentDownstream() {
qint64 SerialLink::getCurrentDownstream()
{
return 0; // TODO
}
qint64 SerialLink::getMaxDownstream() {
qint64 SerialLink::getMaxDownstream()
{
return 0; // TODO
}
bool SerialLink::isFullDuplex() {
bool SerialLink::isFullDuplex()
{
/* Serial connections are always half duplex */
return false;
}
int SerialLink::getLinkQuality() {
int SerialLink::getLinkQuality()
{
/* This feature is not supported with this interface */
return -1;
}
QString SerialLink::getPortName() {
QString SerialLink::getPortName()
{
return porthandle;
}
int SerialLink::getBaudRate() {
int SerialLink::getBaudRate()
{
return getNominalDataRate();
}
int SerialLink::getBaudRateType() {
int SerialLink::getBaudRateType()
{
return baudrate;
}
int SerialLink::getFlowType() {
int SerialLink::getFlowType()
{
return flow;
}
int SerialLink::getParityType() {
int SerialLink::getParityType()
{
return parity;
}
int SerialLink::getDataBitsType() {
int SerialLink::getDataBitsType()
{
return dataBits;
}
int SerialLink::getStopBitsType() {
int SerialLink::getStopBitsType()
{
return stopBits;
}
......@@ -689,7 +710,8 @@ bool SerialLink::setBaudRate(int rate)
return accepted;
}
bool SerialLink::setFlowType(int flow) {
bool SerialLink::setFlowType(int flow)
{
bool reconnect = false;
bool accepted = true;
if(isConnected()) {
......@@ -717,7 +739,8 @@ bool SerialLink::setFlowType(int flow) {
return accepted;
}
bool SerialLink::setParityType(int parity) {
bool SerialLink::setParityType(int parity)
{
bool reconnect = false;
bool accepted = true;
if(isConnected()) {
......@@ -752,7 +775,8 @@ bool SerialLink::setParityType(int parity) {
return accepted;
}
bool SerialLink::setDataBitsType(int dataBits) {
bool SerialLink::setDataBitsType(int dataBits)
{
bool accepted = true;
switch (dataBits) {
......@@ -783,7 +807,8 @@ bool SerialLink::setDataBitsType(int dataBits) {
return accepted;
}
bool SerialLink::setStopBitsType(int stopBits) {
bool SerialLink::setStopBitsType(int stopBits)
{
bool reconnect = false;
bool accepted = true;
if(isConnected()) {
......
......@@ -106,7 +106,7 @@ public slots:
bool setDataBitsType(int dataBits);
bool setStopBitsType(int stopBits);
void readBytes(char* data, qint64 maxLength);
void readBytes();
/**
* @brief Write a number of bytes to the interface.
*
......@@ -118,7 +118,6 @@ public slots:
bool disconnect();
protected slots:
void emitBytesReady();
void checkForBytes();
protected:
......
This diff is collapsed.
......@@ -95,7 +95,7 @@ public slots:
void readLine();
void writeBytes(char *bytes, qint64 length);
void readBytes(char *bytes, qint64 maxLength);
void readBytes();
bool connect();
bool disconnect();
......
......@@ -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 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;
quint16 senderPort;
......@@ -169,14 +171,6 @@ qint64 UDPLink::bytesAvailable() {
return socket->pendingDatagramSize();
}
/**
* @brief Convenience method to emit the bytesReady signal
**/
void UDPLink::emitBytesReady()
{
emit bytesReady(this);
}
/**
* @brief Disconnect the connection.
*
......@@ -204,7 +198,7 @@ bool UDPLink::connect()
socket = new QUdpSocket(this);
//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);
......@@ -244,6 +238,7 @@ void UDPLink::setName(QString name)
emit nameChanged(this->name);
}
qint64 UDPLink::getNominalDataRate() {
return 54000000; // 54 Mbit
}
......
......@@ -48,8 +48,6 @@ public:
UDPLink(QHostAddress host = QHostAddress::Any, quint16 port = 14550);
~UDPLink();
static const int poll_interval = UDP_POLL_INTERVAL; ///< Polling interval, defined in configuration.h
bool isConnected();
qint64 bytesAvailable();
......@@ -86,7 +84,7 @@ public slots:
void setPort(quint16 port);
// void readPendingDatagrams();
void readBytes(char* data, qint64 maxLength);
void readBytes();
/**
* @brief Write a number of bytes to the interface.
*
......@@ -97,10 +95,6 @@ public slots:
bool connect();
bool disconnect();
protected slots:
void emitBytesReady();
//void checkForBytes();
protected:
QString name;
QHostAddress host;
......
......@@ -2,9 +2,7 @@
#define CONFIGURATION_H
/** @brief Polling interval in ms */
#define SERIAL_POLL_INTERVAL 1
/** @brief UDP polling interval in ms */
#define UDP_POLL_INTERVAL 1
#define SERIAL_POLL_INTERVAL 2
/** @brief Heartbeat emission rate, in Hertz (times per second) */
#define MAVLINK_HEARTBEAT_DEFAULT_RATE 1
......@@ -12,6 +10,6 @@
#define WITH_TEXT_TO_SPEECH 1
#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
......@@ -39,8 +39,12 @@ This file is part of the PIXHAWK project
#include "CommConfigurationWindow.h"
#include "SerialConfigurationWindow.h"
#include "SerialLinkInterface.h"
#include "SerialLink.h"
#include "UDPLink.h"
#include "MAVLinkSimulationLink.h"
#ifdef OPAL_RT
#include "OpalLink.h"
#endif
#include "MAVLinkProtocol.h"
#include "MAVLinkSettingsWidget.h"
......@@ -86,7 +90,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
// TODO Move these calls to each link so that dynamic casts vanish
// Open details pane for serial link if necessary
SerialLinkInterface* serial = dynamic_cast<SerialLinkInterface*>(link);
SerialLink* serial = dynamic_cast<SerialLink*>(link);
if(serial != 0)
{
QWidget* conf = new SerialConfigurationWindow(serial, this);
......@@ -97,17 +101,28 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
//ui.linkGroupBox->setTitle(link->getName());
//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"));
}
MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
if (sim != 0)
{
ui.linkGroupBox->setTitle(tr("MAVLink Simulation Link"));
}
#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"));
}
#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";
}
......
......@@ -574,7 +574,7 @@ void HUD::paintHUD()
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
// adjust scaling to fit both horizontally and vertically
......
......@@ -374,9 +374,9 @@ void MainWindow::addLink()
void MainWindow::addLink(LinkInterface *link)
{
LinkManager::instance()->addProtocol(link, mavlink);
CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this);
ui.menuNetwork->addAction(commWidget->getAction());
LinkManager::instance()->addProtocol(link, mavlink);
// Special case for simulationlink
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