Browse Source

Changed many functions in the abstract *Link classes to be const. This facilitates setting other functions as const. The metadata for specific links are reset when the links are added.

QGC4.4
Bryant 12 years ago
parent
commit
7095cf2824
  1. 6
      src/comm/LinkInterface.cpp
  2. 16
      src/comm/LinkInterface.h
  3. 2
      src/comm/LinkManager.cc
  4. 24
      src/comm/MAVLinkProtocol.cc
  5. 10
      src/comm/MAVLinkProtocol.h
  6. 16
      src/comm/MAVLinkSimulationLink.cc
  7. 32
      src/comm/MAVLinkSimulationLink.h
  8. 16
      src/comm/OpalLink.cc
  9. 16
      src/comm/OpalLink.h
  10. 12
      src/comm/ProtocolInterface.h
  11. 34
      src/comm/SerialLink.cc
  12. 34
      src/comm/SerialLink.h
  13. 20
      src/comm/SerialLinkInterface.h
  14. 16
      src/comm/UDPLink.cc
  15. 30
      src/comm/UDPLink.h
  16. 20
      src/comm/XbeeLink.cpp
  17. 32
      src/comm/XbeeLink.h

6
src/comm/LinkInterface.cpp

@ -1,6 +0,0 @@ @@ -1,6 +0,0 @@
//#include "LinkInterface.h"
//LinkInterface::~LinkInterface()
//{
//}

16
src/comm/LinkInterface.h

@ -54,19 +54,19 @@ public: @@ -54,19 +54,19 @@ public:
* The ID is an unsigned integer, starting at 0
* @return ID of this link
**/
virtual int getId() = 0;
virtual int getId() const = 0;
/**
* @brief Get the human readable name of this link
*/
virtual QString getName() = 0;
virtual QString getName() const = 0;
/**
* @brief Determine the connection status
*
* @return True if the connection is established, false otherwise
**/
virtual bool isConnected() = 0;
virtual bool isConnected() const = 0;
/* Connection characteristics */
@ -83,7 +83,7 @@ public: @@ -83,7 +83,7 @@ public:
* @see getCurrentDataRate() For the data rate of the last transferred chunk
* @see getMaxDataRate() For the maximum data rate
**/
virtual qint64 getNominalDataRate() = 0;
virtual qint64 getNominalDataRate() const = 0;
/**
* @brief Full duplex support of this interface.
@ -93,7 +93,7 @@ public: @@ -93,7 +93,7 @@ public:
*
* @return True if the interface supports full duplex, false otherwise
**/
virtual bool isFullDuplex() = 0;
virtual bool isFullDuplex() const = 0;
/**
* @brief Get the link quality.
@ -103,7 +103,7 @@ public: @@ -103,7 +103,7 @@ public:
*
* @return The link quality in integer percent or -1 if not supported
**/
virtual int getLinkQuality() = 0;
virtual int getLinkQuality() const = 0;
/**
* @Brief Get the long term (complete) mean of the data rate
@ -150,7 +150,7 @@ public: @@ -150,7 +150,7 @@ public:
*
* @return The number of sent bits
**/
virtual qint64 getBitsSent() = 0;
virtual qint64 getBitsSent() const = 0;
/**
* @Brief Get the total number of bits received
@ -158,7 +158,7 @@ public: @@ -158,7 +158,7 @@ public:
* @return The number of received bits
* @bug Decide if the bits should be counted fromt the instantiation of the interface or if the counter should reset on disconnect.
**/
virtual qint64 getBitsReceived() = 0;
virtual qint64 getBitsReceived() const = 0;
/**
* @brief Connect this interface logically

2
src/comm/LinkManager.cc

@ -98,6 +98,8 @@ void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol) @@ -98,6 +98,8 @@ void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol)
connect(link, SIGNAL(connected(bool)), protocol, SLOT(linkStatusChanged(bool)));
// Store the connection information in the protocol links map
protocolLinks.insertMulti(protocol, link);
// Make sure the protocol clears its metadata for this link.
protocol->resetMetadataForLink(link);
}
//qDebug() << __FILE__ << __LINE__ << "ADDED LINK TO PROTOCOL" << link->getName() << protocol->getName() << "NEW SIZE OF LINK LIST:" << protocolLinks.size();
}

24
src/comm/MAVLinkProtocol.cc

@ -63,14 +63,11 @@ MAVLinkProtocol::MAVLinkProtocol() : @@ -63,14 +63,11 @@ MAVLinkProtocol::MAVLinkProtocol() :
// Start heartbeat timer, emitting a heartbeat at the configured rate
connect(heartbeatTimer, SIGNAL(timeout()), this, SLOT(sendHeartbeat()));
heartbeatTimer->start(1000/heartbeatRate);
for (int i = 0; i < MAVLINK_COMM_NUM_BUFFERS; i++)
{
totalReceiveCounter[i] = 0;
totalLossCounter[i] = 0;
totalErrorCounter[i] = 0;
currReceiveCounter[i] = 0;
currLossCounter[i] = 0;
}
// All the *Counter variables are not initialized here, as they should be initialized
// on a per-link basis before those links are used. @see resetMetadataForLink().
// Initialize the list for tracking dropped messages to invalid.
for (int i = 0; i < 256; i++)
{
for (int j = 0; j < 256; j++)
@ -178,6 +175,16 @@ QString MAVLinkProtocol::getLogfileName() @@ -178,6 +175,16 @@ QString MAVLinkProtocol::getLogfileName()
}
}
void MAVLinkProtocol::resetMetadataForLink(const LinkInterface *link)
{
int linkId = link->getId();
totalReceiveCounter[linkId] = 0;
totalLossCounter[linkId] = 0;
totalErrorCounter[linkId] = 0;
currReceiveCounter[linkId] = 0;
currLossCounter[linkId] = 0;
}
void MAVLinkProtocol::linkStatusChanged(bool connected)
{
LinkInterface* link = qobject_cast<LinkInterface*>(QObject::sender());
@ -205,7 +212,6 @@ void MAVLinkProtocol::linkStatusChanged(bool connected) @@ -205,7 +212,6 @@ void MAVLinkProtocol::linkStatusChanged(bool connected)
}
/**
* The bytes are copied by calling the LinkInterface::readBytes() method.
* This method parses all incoming bytes and constructs a MAVLink packet.
* It can handle multiple links in parallel, as each link has it's own buffer/
* parsing state machine.

10
src/comm/MAVLinkProtocol.h

@ -128,23 +128,27 @@ public: @@ -128,23 +128,27 @@ public:
* Retrieve a total of all successfully parsed packets for the specified link.
* @returns -1 if this is not available for this protocol, # of packets otherwise.
*/
qint32 getReceivedPacketCount(LinkInterface *link) const {
qint32 getReceivedPacketCount(const LinkInterface *link) const {
return totalReceiveCounter[link->getId()];
}
/**
* Retrieve a total of all parsing errors for the specified link.
* @returns -1 if this is not available for this protocol, # of errors otherwise.
*/
qint32 getParsingErrorCount(LinkInterface *link) const {
qint32 getParsingErrorCount(const LinkInterface *link) const {
return totalErrorCounter[link->getId()];
}
/**
* Retrieve a total of all dropped packets for the specified link.
* @returns -1 if this is not available for this protocol, # of packets otherwise.
*/
qint32 getDroppedPacketCount(LinkInterface *link) const {
qint32 getDroppedPacketCount(const LinkInterface *link) const {
return totalLossCounter[link->getId()];
}
/**
* Reset the counters for all metadata for this link.
*/
virtual void resetMetadataForLink(const LinkInterface *link);
public slots:
/** @brief Receive bytes from a communication interface */

16
src/comm/MAVLinkSimulationLink.cc

@ -988,22 +988,22 @@ bool MAVLinkSimulationLink::connectLink(bool connect) @@ -988,22 +988,22 @@ bool MAVLinkSimulationLink::connectLink(bool connect)
*
* @return True if link is connected, false otherwise.
**/
bool MAVLinkSimulationLink::isConnected()
bool MAVLinkSimulationLink::isConnected() const
{
return _isConnected;
}
int MAVLinkSimulationLink::getId()
int MAVLinkSimulationLink::getId() const
{
return id;
}
QString MAVLinkSimulationLink::getName()
QString MAVLinkSimulationLink::getName() const
{
return name;
}
qint64 MAVLinkSimulationLink::getNominalDataRate()
qint64 MAVLinkSimulationLink::getNominalDataRate() const
{
/* 100 Mbit is reasonable fast and sufficient for all embedded applications */
return 100000000;
@ -1031,12 +1031,12 @@ qint64 MAVLinkSimulationLink::getMaxUpstream() @@ -1031,12 +1031,12 @@ qint64 MAVLinkSimulationLink::getMaxUpstream()
return 0;
}
qint64 MAVLinkSimulationLink::getBitsSent()
qint64 MAVLinkSimulationLink::getBitsSent() const
{
return 0;
}
qint64 MAVLinkSimulationLink::getBitsReceived()
qint64 MAVLinkSimulationLink::getBitsReceived() const
{
return 0;
}
@ -1061,13 +1061,13 @@ qint64 MAVLinkSimulationLink::getMaxDownstream() @@ -1061,13 +1061,13 @@ qint64 MAVLinkSimulationLink::getMaxDownstream()
return 0;
}
bool MAVLinkSimulationLink::isFullDuplex()
bool MAVLinkSimulationLink::isFullDuplex() const
{
/* Full duplex is no problem when running in pure software, but this is a serial simulation */
return false;
}
int MAVLinkSimulationLink::getLinkQuality()
int MAVLinkSimulationLink::getLinkQuality() const
{
/* The Link quality is always perfect when running in software */
return 100;

32
src/comm/MAVLinkSimulationLink.h

@ -50,7 +50,7 @@ class MAVLinkSimulationLink : public LinkInterface @@ -50,7 +50,7 @@ class MAVLinkSimulationLink : public LinkInterface
public:
MAVLinkSimulationLink(QString readFile="", QString writeFile="", int rate=5, QObject* parent = 0);
~MAVLinkSimulationLink();
bool isConnected();
bool isConnected() const;
qint64 bytesAvailable();
void run();
@ -59,7 +59,7 @@ public: @@ -59,7 +59,7 @@ public:
bool disconnect();
/* Extensive statistics for scientific purposes */
qint64 getNominalDataRate();
qint64 getNominalDataRate() const;
qint64 getTotalUpstream();
qint64 getShortTermUpstream();
qint64 getCurrentUpstream();
@ -68,20 +68,20 @@ public: @@ -68,20 +68,20 @@ public:
qint64 getShortTermDownstream();
qint64 getCurrentDownstream();
qint64 getMaxDownstream();
qint64 getBitsSent();
qint64 getBitsReceived();
QString getName();
int getId();
int getBaudRate();
int getBaudRateType();
int getFlowType();
int getParityType();
int getDataBitsType();
int getStopBitsType();
int getLinkQuality();
bool isFullDuplex();
qint64 getBitsSent() const;
qint64 getBitsReceived() const;
QString getName() const;
int getId() const;
int getBaudRate() const;
int getBaudRateType() const;
int getFlowType() const;
int getParityType() const;
int getDataBitsType() const;
int getStopBitsType() const;
int getLinkQuality() const;
bool isFullDuplex() const;
public slots:
void writeBytes(const char* data, qint64 size);

16
src/comm/OpalLink.cc

@ -411,12 +411,12 @@ void OpalLink::run() @@ -411,12 +411,12 @@ void OpalLink::run()
// qDebug() << "OpalLink::run():: Starting the thread";
}
int OpalLink::getId()
int OpalLink::getId() const
{
return id;
}
QString OpalLink::getName()
QString OpalLink::getName() const
{
return name;
}
@ -427,7 +427,7 @@ void OpalLink::setName(QString name) @@ -427,7 +427,7 @@ void OpalLink::setName(QString name)
emit nameChanged(this->name);
}
bool OpalLink::isConnected()
bool OpalLink::isConnected() const
{
return connectState;
}
@ -505,12 +505,12 @@ bool OpalLink::disconnect() @@ -505,12 +505,12 @@ bool OpalLink::disconnect()
*
*/
qint64 OpalLink::getNominalDataRate()
qint64 OpalLink::getNominalDataRate() const
{
return 0; //unknown
}
int OpalLink::getLinkQuality()
int OpalLink::getLinkQuality() const
{
return -1; //not supported
}
@ -541,18 +541,18 @@ qint64 OpalLink::getMaxUpstream() @@ -541,18 +541,18 @@ qint64 OpalLink::getMaxUpstream()
return 0; //unknown
}
qint64 OpalLink::getBitsSent()
qint64 OpalLink::getBitsSent() const
{
return bitsSentTotal;
}
qint64 OpalLink::getBitsReceived()
qint64 OpalLink::getBitsReceived() const
{
return bitsReceivedTotal;
}
bool OpalLink::isFullDuplex()
bool OpalLink::isFullDuplex() const
{
return false;
}

16
src/comm/OpalLink.h

@ -71,22 +71,22 @@ public: @@ -71,22 +71,22 @@ public:
OpalLink();
/* Connection management */
int getId();
QString getName();
bool isConnected();
int getId() const;
QString getName() const;
bool isConnected() const;
/* Connection characteristics */
qint64 getNominalDataRate();
bool isFullDuplex();
int getLinkQuality();
qint64 getNominalDataRate() const;
bool isFullDuplex() const;
int getLinkQuality() const;
qint64 getTotalUpstream();
qint64 getTotalDownstream();
qint64 getCurrentUpstream();
qint64 getMaxUpstream();
qint64 getBitsSent();
qint64 getBitsReceived();
qint64 getBitsSent() const;
qint64 getBitsReceived() const;
bool connect();

12
src/comm/ProtocolInterface.h

@ -57,19 +57,25 @@ public: @@ -57,19 +57,25 @@ public:
* @param link The link to return metadata about.
* @returns -1 if this is not available for this protocol, # of packets otherwise.
*/
virtual qint32 getReceivedPacketCount(LinkInterface *link) const = 0;
virtual qint32 getReceivedPacketCount(const LinkInterface *link) const = 0;
/**
* Retrieve a total of all parsing errors for the specified link.
* @param link The link to return metadata about.
* @returns -1 if this is not available for this protocol, # of errors otherwise.
*/
virtual qint32 getParsingErrorCount(LinkInterface *link) const = 0;
virtual qint32 getParsingErrorCount(const LinkInterface *link) const = 0;
/**
* Retrieve a total of all dropped packets for the specified link.
* @param link The link to return metadata about.
* @returns -1 if this is not available for this protocol, # of packets otherwise.
*/
virtual qint32 getDroppedPacketCount(LinkInterface *link) const = 0;
virtual qint32 getDroppedPacketCount(const LinkInterface *link) const = 0;
/**
* Reset the received, error, and dropped counts for the given link. Useful for
* when reconnecting a link.
* @param link The link to reset metadata for.
*/
virtual void resetMetadataForLink(const LinkInterface *link) = 0;
public slots:
virtual void receiveBytes(LinkInterface *link, QByteArray b) = 0;

34
src/comm/SerialLink.cc

@ -683,7 +683,7 @@ bool SerialLink::hardwareConnect() @@ -683,7 +683,7 @@ bool SerialLink::hardwareConnect()
*
* @return True if link is connected, false otherwise.
**/
bool SerialLink::isConnected()
bool SerialLink::isConnected() const
{
if (port) {
return port->isOpen();
@ -692,12 +692,12 @@ bool SerialLink::isConnected() @@ -692,12 +692,12 @@ bool SerialLink::isConnected()
}
}
int SerialLink::getId()
int SerialLink::getId() const
{
return id;
}
QString SerialLink::getName()
QString SerialLink::getName() const
{
return name;
}
@ -713,7 +713,7 @@ void SerialLink::setName(QString name) @@ -713,7 +713,7 @@ void SerialLink::setName(QString name)
* This function maps baud rate constants to numerical equivalents.
* It relies on the mapping given in qportsettings.h from the QSerialPort library.
*/
qint64 SerialLink::getNominalDataRate()
qint64 SerialLink::getNominalDataRate() const
{
qint64 dataRate = 0;
switch (portSettings.baudRate()) {
@ -829,12 +829,12 @@ qint64 SerialLink::getMaxUpstream() @@ -829,12 +829,12 @@ qint64 SerialLink::getMaxUpstream()
return 0; // TODO
}
qint64 SerialLink::getBitsSent()
qint64 SerialLink::getBitsSent() const
{
return bitsSentTotal;
}
qint64 SerialLink::getBitsReceived()
qint64 SerialLink::getBitsReceived() const
{
return bitsReceivedTotal;
}
@ -856,54 +856,54 @@ qint64 SerialLink::getMaxDownstream() @@ -856,54 +856,54 @@ qint64 SerialLink::getMaxDownstream()
return 0; // TODO
}
bool SerialLink::isFullDuplex()
bool SerialLink::isFullDuplex() const
{
/* Serial connections are always half duplex */
return false;
}
int SerialLink::getLinkQuality()
int SerialLink::getLinkQuality() const
{
/* This feature is not supported with this interface */
return -1;
}
QString SerialLink::getPortName()
QString SerialLink::getPortName() const
{
return porthandle;
}
int SerialLink::getBaudRate()
int SerialLink::getBaudRate() const
{
return getNominalDataRate();
}
int SerialLink::getBaudRateType()
int SerialLink::getBaudRateType() const
{
return portSettings.baudRate();
}
int SerialLink::getFlowType()
int SerialLink::getFlowType() const
{
return portSettings.flowControl();
}
int SerialLink::getParityType()
int SerialLink::getParityType() const
{
return portSettings.parity();
}
int SerialLink::getDataBitsType()
int SerialLink::getDataBitsType() const
{
return portSettings.dataBits();
}
int SerialLink::getStopBitsType()
int SerialLink::getStopBitsType() const
{
return portSettings.stopBits();
}
int SerialLink::getDataBits()
int SerialLink::getDataBits() const
{
int ret = -1;
switch (portSettings.dataBits()) {
@ -926,7 +926,7 @@ int SerialLink::getDataBits() @@ -926,7 +926,7 @@ int SerialLink::getDataBits()
return ret;
}
int SerialLink::getStopBits()
int SerialLink::getStopBits() const
{
int ret = -1;
switch (portSettings.stopBits()) {

34
src/comm/SerialLink.h

@ -71,47 +71,47 @@ public: @@ -71,47 +71,47 @@ public:
/** @brief Get a list of the currently available ports */
QVector<QString>* getCurrentPorts();
bool isConnected();
bool isConnected() const;
qint64 bytesAvailable();
/**
* @brief The port handle
*/
QString getPortName();
QString getPortName() const;
/**
* @brief The human readable port name
*/
QString getName();
int getBaudRate();
int getDataBits();
int getStopBits();
QString getName() const;
int getBaudRate() const;
int getDataBits() const;
int getStopBits() const;
// ENUM values
int getBaudRateType();
int getFlowType();
int getParityType();
int getDataBitsType();
int getStopBitsType();
int getBaudRateType() const;
int getFlowType() const;
int getParityType() const;
int getDataBitsType() const;
int getStopBitsType() const;
/* Extensive statistics for scientific purposes */
qint64 getNominalDataRate();
qint64 getNominalDataRate() const;
qint64 getTotalUpstream();
qint64 getCurrentUpstream();
qint64 getMaxUpstream();
qint64 getTotalDownstream();
qint64 getCurrentDownstream();
qint64 getMaxDownstream();
qint64 getBitsSent();
qint64 getBitsReceived();
qint64 getBitsSent() const;
qint64 getBitsReceived() const;
void loadSettings();
void writeSettings();
void run();
int getLinkQuality();
bool isFullDuplex();
int getId();
int getLinkQuality() const;
bool isFullDuplex() const;
int getId() const;
public slots:
bool setPortName(QString portName);

20
src/comm/SerialLinkInterface.h

@ -43,16 +43,16 @@ class SerialLinkInterface : public LinkInterface @@ -43,16 +43,16 @@ class SerialLinkInterface : public LinkInterface
public:
virtual QVector<QString>* getCurrentPorts() = 0;
virtual QString getPortName() = 0;
virtual int getBaudRate() = 0;
virtual int getDataBits() = 0;
virtual int getStopBits() = 0;
virtual int getBaudRateType() = 0;
virtual int getFlowType() = 0;
virtual int getParityType() = 0;
virtual int getDataBitsType() = 0;
virtual int getStopBitsType() = 0;
virtual QString getPortName() const = 0;
virtual int getBaudRate() const = 0;
virtual int getDataBits() const = 0;
virtual int getStopBits() const = 0;
virtual int getBaudRateType() const = 0;
virtual int getFlowType() const = 0;
virtual int getParityType() const = 0;
virtual int getDataBitsType() const = 0;
virtual int getStopBitsType() const = 0;
public slots:
virtual bool setPortName(QString portName) = 0;

16
src/comm/UDPLink.cc

@ -354,17 +354,17 @@ bool UDPLink::hardwareConnect(void) @@ -354,17 +354,17 @@ bool UDPLink::hardwareConnect(void)
*
* @return True if link is connected, false otherwise.
**/
bool UDPLink::isConnected()
bool UDPLink::isConnected() const
{
return connectState;
}
int UDPLink::getId()
int UDPLink::getId() const
{
return id;
}
QString UDPLink::getName()
QString UDPLink::getName() const
{
return name;
}
@ -376,7 +376,7 @@ void UDPLink::setName(QString name) @@ -376,7 +376,7 @@ void UDPLink::setName(QString name)
}
qint64 UDPLink::getNominalDataRate()
qint64 UDPLink::getNominalDataRate() const
{
return 54000000; // 54 Mbit
}
@ -399,12 +399,12 @@ qint64 UDPLink::getMaxUpstream() @@ -399,12 +399,12 @@ qint64 UDPLink::getMaxUpstream()
return 0; // TODO
}
qint64 UDPLink::getBitsSent()
qint64 UDPLink::getBitsSent() const
{
return bitsSentTotal;
}
qint64 UDPLink::getBitsReceived()
qint64 UDPLink::getBitsReceived() const
{
return bitsReceivedTotal;
}
@ -427,12 +427,12 @@ qint64 UDPLink::getMaxDownstream() @@ -427,12 +427,12 @@ qint64 UDPLink::getMaxDownstream()
return 0; // TODO
}
bool UDPLink::isFullDuplex()
bool UDPLink::isFullDuplex() const
{
return true;
}
int UDPLink::getLinkQuality()
int UDPLink::getLinkQuality() const
{
/* This feature is not supported with this interface */
return -1;

30
src/comm/UDPLink.h

@ -49,7 +49,7 @@ public: @@ -49,7 +49,7 @@ public:
//UDPLink(QHostAddress host = "239.255.76.67", quint16 port = 7667);
~UDPLink();
bool isConnected();
bool isConnected() const;
qint64 bytesAvailable();
int getPort() const {
return port;
@ -58,33 +58,33 @@ public: @@ -58,33 +58,33 @@ public:
/**
* @brief The human readable port name
*/
QString getName();
int getBaudRate();
int getBaudRateType();
int getFlowType();
int getParityType();
int getDataBitsType();
int getStopBitsType();
QList<QHostAddress> getHosts() {
QString getName() const;
int getBaudRate() const;
int getBaudRateType() const;
int getFlowType() const;
int getParityType() const;
int getDataBitsType() const;
int getStopBitsType() const;
QList<QHostAddress> getHosts() const {
return hosts;
}
/* Extensive statistics for scientific purposes */
qint64 getNominalDataRate();
qint64 getNominalDataRate() const;
qint64 getTotalUpstream();
qint64 getCurrentUpstream();
qint64 getMaxUpstream();
qint64 getTotalDownstream();
qint64 getCurrentDownstream();
qint64 getMaxDownstream();
qint64 getBitsSent();
qint64 getBitsReceived();
qint64 getBitsSent() const;
qint64 getBitsReceived() const;
void run();
int getLinkQuality();
bool isFullDuplex();
int getId();
int getLinkQuality() const;
bool isFullDuplex() const;
int getId() const;
public slots:
void setAddress(QHostAddress host);

20
src/comm/XbeeLink.cpp

@ -32,7 +32,7 @@ XbeeLink::~XbeeLink() @@ -32,7 +32,7 @@ XbeeLink::~XbeeLink()
this->disconnect();
}
QString XbeeLink::getPortName()
QString XbeeLink::getPortName() const
{
QString portName;
for(unsigned int i = 0;i<this->m_portNameLength;i++)
@ -42,7 +42,7 @@ QString XbeeLink::getPortName() @@ -42,7 +42,7 @@ QString XbeeLink::getPortName()
return portName;
}
int XbeeLink::getBaudRate()
int XbeeLink::getBaudRate() const
{
return this->m_baudRate;
}
@ -104,32 +104,32 @@ bool XbeeLink::setBaudRate(int rate) @@ -104,32 +104,32 @@ bool XbeeLink::setBaudRate(int rate)
return retVal;
}
int XbeeLink::getId()
int XbeeLink::getId() const
{
return this->m_id;
}
QString XbeeLink::getName()
QString XbeeLink::getName() const
{
return this->m_name;
}
bool XbeeLink::isConnected()
bool XbeeLink::isConnected() const
{
return this->m_connected;
}
qint64 XbeeLink::getNominalDataRate()
qint64 XbeeLink::getNominalDataRate() const
{
return this->m_baudRate;
}
bool XbeeLink::isFullDuplex()
bool XbeeLink::isFullDuplex() const
{
return false;
}
int XbeeLink::getLinkQuality()
int XbeeLink::getLinkQuality() const
{
return -1; // TO DO:
}
@ -149,12 +149,12 @@ qint64 XbeeLink::getMaxUpstream() @@ -149,12 +149,12 @@ qint64 XbeeLink::getMaxUpstream()
return 0; // TO DO:
}
qint64 XbeeLink::getBitsSent()
qint64 XbeeLink::getBitsSent() const
{
return 0; // TO DO:
}
qint64 XbeeLink::getBitsReceived()
qint64 XbeeLink::getBitsReceived() const
{
return 0; // TO DO:
}

32
src/comm/XbeeLink.h

@ -20,8 +20,8 @@ public: @@ -20,8 +20,8 @@ public:
~XbeeLink();
public: // virtual functions from XbeeLinkInterface
QString getPortName();
int getBaudRate();
QString getPortName() const;
int getBaudRate() const;
public slots: // virtual functions from XbeeLinkInterface
bool setPortName(QString portName);
@ -30,20 +30,20 @@ public slots: // virtual functions from XbeeLinkInterface @@ -30,20 +30,20 @@ public slots: // virtual functions from XbeeLinkInterface
bool setRemoteAddressLow(quint32 low);
public: // virtual functions from LinkInterface
int getId();
QString getName();
bool isConnected();
qint64 getNominalDataRate();
bool isFullDuplex();
int getLinkQuality();
qint64 getTotalUpstream();
qint64 getCurrentUpstream();
qint64 getMaxUpstream();
qint64 getBitsSent();
qint64 getBitsReceived();
bool connect();
bool disconnect();
qint64 bytesAvailable();
int getId() const;
QString getName() const;
bool isConnected() const;
qint64 getNominalDataRate() const;
bool isFullDuplex() const;
int getLinkQuality() const;
qint64 getTotalUpstream();
qint64 getCurrentUpstream();
qint64 getMaxUpstream();
qint64 getBitsSent() const;
qint64 getBitsReceived() const;
bool connect();
bool disconnect();
qint64 bytesAvailable();
public slots: // virtual functions from LinkInterface
void writeBytes(const char *bytes, qint64 length);

Loading…
Cancel
Save