Browse Source

Addition of requestReset to LinkInterface, to allow MavLinkProtocol to detect when connected, but at the wrong baud rate, request a reset.

QGC4.4
Michael Carpenter 12 years ago
parent
commit
f418c2e555
  1. 2
      src/comm/LinkInterface.h
  2. 21
      src/comm/MAVLinkProtocol.cc
  3. 2
      src/comm/MAVLinkSimulationLink.h
  4. 16
      src/comm/SerialLink.cc
  5. 5
      src/comm/SerialLink.h
  6. 2
      src/comm/SerialLinkInterface.h
  7. 2
      src/comm/UDPLink.h
  8. 3
      src/comm/XbeeLink.h

2
src/comm/LinkInterface.h

@ -61,6 +61,8 @@ public: @@ -61,6 +61,8 @@ public:
*/
virtual QString getName() = 0;
virtual void requestReset() = 0;
/**
* @brief Determine the connection status
*

21
src/comm/MAVLinkProtocol.cc

@ -215,8 +215,11 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) @@ -215,8 +215,11 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
mavlink_status_t status;
static int mavlink09Count = 0;
static int nonmavlinkCount = 0;
static bool decodedFirstPacket = false;
static bool warnedUser = false;
static bool checkedUserNonMavlink = false;
static bool warnedUserNonMavlink = false;
for (int position = 0; position < b.size(); position++) {
unsigned int decodeState = mavlink_parse_char(link->getId(), (uint8_t)(b[position]), &message, &status);
@ -230,6 +233,24 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) @@ -230,6 +233,24 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
emit protocolStatusMessage("MAVLink Version or Baud Rate Mismatch", "Your MAVLink device seems to use the deprecated version 0.9, while QGroundControl only supports version 1.0+. Please upgrade the MAVLink version of your autopilot. If your autopilot is using version 1.0, check if the baud rates of QGroundControl and your autopilot are the same.");
}
if (decodeState == 0 && !decodedFirstPacket)
{
nonmavlinkCount++;
if (nonmavlinkCount > 500 && !warnedUserNonMavlink)
{
//500 bytes with no mavlink message. Are we connected to a mavlink capable device?
if (!checkedUserNonMavlink)
{
link->requestReset();
checkedUserNonMavlink = true;
}
else
{
warnedUserNonMavlink = true;
emit protocolStatusMessage("MAVLink Baud Rate Mismatch", "Please check if the baud rates of QGroundControl and your autopilot are the same.");
}
}
}
if (decodeState == 1)
{
decodedFirstPacket = true;

2
src/comm/MAVLinkSimulationLink.h

@ -54,7 +54,7 @@ public: @@ -54,7 +54,7 @@ public:
qint64 bytesAvailable();
void run();
void requestReset() { }
bool connect();
bool disconnect();

16
src/comm/SerialLink.cc

@ -213,7 +213,8 @@ SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl, @@ -213,7 +213,8 @@ SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl,
port(NULL),
ports(new QVector<QString>()),
m_stopp(false),
bytesRead(0)
bytesRead(0),
m_reqReset(false)
{
// Setup settings
this->porthandle = portname.trimmed();
@ -265,6 +266,11 @@ SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl, @@ -265,6 +266,11 @@ SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl,
}
loadSettings();
}
void SerialLink::requestReset()
{
QMutexLocker locker(&this->m_stoppMutex);
m_reqReset = true;
}
SerialLink::~SerialLink()
{
@ -417,6 +423,14 @@ void SerialLink::run() @@ -417,6 +423,14 @@ void SerialLink::run()
this->m_stopp = false;
break;
}
if (m_reqReset)
{
this->m_reqReset = false;
communicationUpdate(getName(),"Reset requested via DTR signal");
port->setDtr(true);
this->msleep(250);
port->setDtr(false);
}
}
// Check if new bytes have arrived, if yes, emit the notification signal
checkForBytes();

5
src/comm/SerialLink.h

@ -71,6 +71,8 @@ public: @@ -71,6 +71,8 @@ public:
/** @brief Get a list of the currently available ports */
QVector<QString>* getCurrentPorts();
void requestReset();
bool isConnected();
qint64 bytesAvailable();
@ -170,7 +172,8 @@ protected: @@ -170,7 +172,8 @@ protected:
QVector<QString>* ports;
private:
volatile bool m_stopp;
volatile bool m_stopp;
volatile bool m_reqReset;
QMutex m_stoppMutex;
void setName(QString name);

2
src/comm/SerialLinkInterface.h

@ -47,7 +47,7 @@ public: @@ -47,7 +47,7 @@ public:
virtual int getBaudRate() = 0;
virtual int getDataBits() = 0;
virtual int getStopBits() = 0;
virtual void requestReset() = 0;
virtual int getBaudRateType() = 0;
virtual int getFlowType() = 0;
virtual int getParityType() = 0;

2
src/comm/UDPLink.h

@ -49,6 +49,8 @@ public: @@ -49,6 +49,8 @@ public:
//UDPLink(QHostAddress host = "239.255.76.67", quint16 port = 7667);
~UDPLink();
void requestReset() { }
bool isConnected();
qint64 bytesAvailable();
int getPort() const {

3
src/comm/XbeeLink.h

@ -21,6 +21,7 @@ public: @@ -21,6 +21,7 @@ public:
public: // virtual functions from XbeeLinkInterface
QString getPortName();
void requestReset() { }
int getBaudRate();
public slots: // virtual functions from XbeeLinkInterface
@ -71,4 +72,4 @@ private: @@ -71,4 +72,4 @@ private:
};
#endif // _XBEELINK_H_
#endif // _XBEELINK_H_

Loading…
Cancel
Save