Browse Source

Enabled 921600 and other high baud rates on all platforms

QGC4.4
LM 13 years ago
parent
commit
5348f704f4
  1. 6
      src/comm/MAVLinkProtocol.cc
  2. 206
      src/comm/SerialLink.cc
  3. 4
      src/uas/UAS.cc
  4. 2
      src/ui/HUD.cc
  5. 18
      src/ui/SerialConfigurationWindow.cc
  6. 2
      thirdParty/qserialport/src/posix/termioshelper.cpp

6
src/comm/MAVLinkProtocol.cc

@ -190,16 +190,18 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) @@ -190,16 +190,18 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
static int mavlink09Count = 0;
static bool decodedFirstPacket = false;
static bool warnedUser = false;
for (int position = 0; position < b.size(); position++) {
unsigned int decodeState = mavlink_parse_char(link->getId(), (uint8_t)(b[position]), &message, &status);
if ((uint8_t)b[position] == 0x55) mavlink09Count++;
if ((mavlink09Count > 100) && !decodedFirstPacket)
if ((mavlink09Count > 100) && !decodedFirstPacket && !warnedUser)
{
warnedUser = true;
// Obviously the user tries to use a 0.9 autopilot
// with QGroundControl built for version 1.0
emit protocolStatusMessage("MAVLink Version 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.");
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 == 1)

206
src/comm/SerialLink.cc

@ -174,9 +174,9 @@ static kern_return_t GetModemPath(io_iterator_t serialPortIterator, char *bsdPat @@ -174,9 +174,9 @@ static kern_return_t GetModemPath(io_iterator_t serialPortIterator, char *bsdPat
// incoming calls, e.g. a fax listener.
bsdPathAsCFString = IORegistryEntryCreateCFProperty(modemService,
CFSTR(kIOCalloutDeviceKey),
kCFAllocatorDefault,
0);
CFSTR(kIOCalloutDeviceKey),
kCFAllocatorDefault,
0);
if (bsdPathAsCFString) {
Boolean result;
@ -213,7 +213,7 @@ SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl, @@ -213,7 +213,7 @@ SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl,
int dataBits, int stopBits) :
port(NULL),
ports(new QVector<QString>()),
m_stopp(false)
m_stopp(false)
{
// Setup settings
this->porthandle = portname.trimmed();
@ -395,14 +395,14 @@ void SerialLink::run() @@ -395,14 +395,14 @@ void SerialLink::run()
// Qt way to make clear what a while(1) loop does
forever
{
{
QMutexLocker locker(&this->m_stoppMutex);
if(this->m_stopp)
{
this->m_stopp = false;
break;
}
}
{
QMutexLocker locker(&this->m_stoppMutex);
if(this->m_stopp)
{
this->m_stopp = false;
break;
}
}
// 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
@ -410,13 +410,13 @@ void SerialLink::run() @@ -410,13 +410,13 @@ void SerialLink::run()
*/
MG::SLEEP::msleep(SerialLink::poll_interval);
}
if (port) {
if (port) {
port->flushInBuffer();
port->flushOutBuffer();
port->close();
delete port;
port = NULL;
}
}
}
@ -449,18 +449,18 @@ void SerialLink::writeBytes(const char* data, qint64 size) @@ -449,18 +449,18 @@ void SerialLink::writeBytes(const char* data, qint64 size)
if (b > 0) {
// qDebug() << "Serial link " << this->getName() << "transmitted" << b << "bytes:";
// qDebug() << "Serial link " << this->getName() << "transmitted" << b << "bytes:";
// Increase write counter
bitsSentTotal += size * 8;
// int i;
// for (i=0; i<size; i++)
// {
// unsigned char v =data[i];
// qDebug("%02x ", v);
// }
// qDebug("\n");
// int i;
// for (i=0; i<size; i++)
// {
// unsigned char v =data[i];
// qDebug("%02x ", v);
// }
// qDebug("\n");
} else {
disconnect();
// Error occured
@ -528,33 +528,33 @@ qint64 SerialLink::bytesAvailable() @@ -528,33 +528,33 @@ qint64 SerialLink::bytesAvailable()
**/
bool SerialLink::disconnect()
{
if(this->isRunning())
{
{
QMutexLocker locker(&this->m_stoppMutex);
this->m_stopp = true;
}
this->wait();
// if (port) {
if(this->isRunning())
{
{
QMutexLocker locker(&this->m_stoppMutex);
this->m_stopp = true;
}
this->wait();
// if (port) {
//#if !defined _WIN32 || !defined _WIN64
/* Block the thread until it returns from run() */
//#endif
// port->flushInBuffer();
// port->flushOutBuffer();
// port->close();
// delete port;
// port = NULL;
// if(this->isRunning()) this->terminate(); //stop running the thread, restart it upon connect
// port->flushInBuffer();
// port->flushOutBuffer();
// port->close();
// delete port;
// port = NULL;
// if(this->isRunning()) this->terminate(); //stop running the thread, restart it upon connect
bool closed = true;
//port->isOpen();
emit disconnected();
emit connected(false);
return closed;
}
}
else {
// No port, so we're disconnected
return true;
@ -570,10 +570,10 @@ bool SerialLink::disconnect() @@ -570,10 +570,10 @@ bool SerialLink::disconnect()
bool SerialLink::connect()
{
if (this->isRunning()) this->disconnect();
{
QMutexLocker locker(&this->m_stoppMutex);
this->m_stopp = false;
}
{
QMutexLocker locker(&this->m_stoppMutex);
this->m_stopp = false;
}
this->start(LowPriority);
return true;
}
@ -654,7 +654,7 @@ qint64 SerialLink::getNominalDataRate() @@ -654,7 +654,7 @@ qint64 SerialLink::getNominalDataRate()
qint64 dataRate = 0;
switch (portSettings.baudRate()) {
// Baud rates supported only by POSIX systems
// Baud rates supported only by POSIX systems
#if defined(Q_OS_UNIX) || defined(Q_OS_LINUX) || defined(Q_OS_DARWIN)
case QPortSettings::BAUDR_50:
dataRate = 50;
@ -676,26 +676,7 @@ qint64 SerialLink::getNominalDataRate() @@ -676,26 +676,7 @@ qint64 SerialLink::getNominalDataRate()
break;
#endif
// Baud rates supported only by Linux
#ifdef Q_OS_LINUX
case QPortSettings::BAUDR_230400:
dataRate = 230400;
break;
case QPortSettings::BAUDR_460800:
dataRate = 460800;
break;
case QPortSettings::BAUDR_500000:
dataRate = 500000;
break;
case QPortSettings::BAUDR_576000:
dataRate = 576000;
break;
case QPortSettings::BAUDR_921600:
dataRate = 921600;
break;
#endif
// Baud rates supported only by Windows
// Baud rates supported only by Windows
#if defined(Q_OS_WIN32) || defined(Q_OS_WINCE)
case QPortSettings::BAUDR_14400:
dataRate = 14400;
@ -743,8 +724,23 @@ qint64 SerialLink::getNominalDataRate() @@ -743,8 +724,23 @@ qint64 SerialLink::getNominalDataRate()
case QPortSettings::BAUDR_115200:
dataRate = 115200;
break;
case QPortSettings::BAUDR_230400:
dataRate = 230400;
break;
case QPortSettings::BAUDR_460800:
dataRate = 460800;
break;
case QPortSettings::BAUDR_500000:
dataRate = 500000;
break;
case QPortSettings::BAUDR_576000:
dataRate = 576000;
break;
case QPortSettings::BAUDR_921600:
dataRate = 921600;
break;
// Otherwise do nothing.
// Otherwise do nothing.
case QPortSettings::BAUDR_UNKNOWN:
default:
break;
@ -869,17 +865,17 @@ int SerialLink::getDataBits() @@ -869,17 +865,17 @@ int SerialLink::getDataBits()
int SerialLink::getStopBits()
{
int ret = -1;
switch (portSettings.stopBits()) {
case QPortSettings::STOP_1:
ret = 1;
break;
case QPortSettings::STOP_2:
ret = 2;
break;
default:
ret = -1;
break;
}
switch (portSettings.stopBits()) {
case QPortSettings::STOP_1:
ret = 1;
break;
case QPortSettings::STOP_2:
ret = 2;
break;
default:
ret = -1;
break;
}
return ret;
}
@ -916,16 +912,16 @@ bool SerialLink::setBaudRateType(int rateIndex) @@ -916,16 +912,16 @@ bool SerialLink::setBaudRateType(int rateIndex)
if(isConnected()) reconnect = true;
disconnect();
// These minimum and maximum baud rates were based on those enumerated in qportsettings.h.
// These minimum and maximum baud rates were based on those enumerated in qportsettings.h.
#if defined(Q_OS_WIN32) || defined(Q_OS_WINCE)
const int minBaud = (int)QPortSettings::BAUDR_110;
const int maxBaud = (int)QPortSettings::BAUDR_256000;
const int minBaud = (int)QPortSettings::BAUDR_110;
const int maxBaud = (int)QPortSettings::BAUDR_256000;
#elif defined(Q_OS_LINUX)
const int minBaud = (int)QPortSettings::BAUDR_50;
const int maxBaud = (int)QPortSettings::BAUDR_921600;
const int minBaud = (int)QPortSettings::BAUDR_50;
const int maxBaud = (int)QPortSettings::BAUDR_921600;
#elif defined(Q_OS_UNIX) || defined(Q_OS_DARWIN)
const int minBaud = (int)QPortSettings::BAUDR_50;
const int maxBaud = (int)QPortSettings::BAUDR_115200;
const int minBaud = (int)QPortSettings::BAUDR_50;
const int maxBaud = (int)QPortSettings::BAUDR_115200;
#endif
if (rateIndex >= minBaud && rateIndex <= maxBaud)
@ -953,11 +949,11 @@ bool SerialLink::setBaudRate(int rate) @@ -953,11 +949,11 @@ bool SerialLink::setBaudRate(int rate)
reconnect = true;
}
disconnect();
// This switch-statment relies on the mapping given in qportsettings.h from the QSerialPort library.
switch (rate) {
// Baud rates supported only by non-Windows systems
// Baud rates supported only by non-Windows systems
#if defined(Q_OS_UNIX) || defined(Q_OS_LINUX) || defined(Q_OS_DARWIN)
case 50:
portSettings.setBaudRate(QPortSettings::BAUDR_50);
@ -979,26 +975,7 @@ bool SerialLink::setBaudRate(int rate) @@ -979,26 +975,7 @@ bool SerialLink::setBaudRate(int rate)
break;
#endif
// Supported only by Linux
#ifdef Q_OS_LINUX
case 230400:
portSettings.setBaudRate(QPortSettings::BAUDR_230400);
break;
case 460800:
portSettings.setBaudRate(QPortSettings::BAUDR_460800);
break;
case 500000:
portSettings.setBaudRate(QPortSettings::BAUDR_500000);
break;
case 576000:
portSettings.setBaudRate(QPortSettings::BAUDR_576000);
break;
case 921600:
portSettings.setBaudRate(QPortSettings::BAUDR_921600);
break;
#endif
// Baud rates supported only by windows
// Baud rates supported only by windows
#if defined(Q_OS_WIN32) || defined(Q_OS_WINCE)
case 14400:
portSettings.setBaudRate(QPortSettings::BAUDR_14400);
@ -1014,7 +991,7 @@ bool SerialLink::setBaudRate(int rate) @@ -1014,7 +991,7 @@ bool SerialLink::setBaudRate(int rate)
break;
#endif
// Supported by all OSes:
// Supported by all OSes:
case 110:
portSettings.setBaudRate(QPortSettings::BAUDR_110);
break;
@ -1048,6 +1025,21 @@ bool SerialLink::setBaudRate(int rate) @@ -1048,6 +1025,21 @@ bool SerialLink::setBaudRate(int rate)
case 115200:
portSettings.setBaudRate(QPortSettings::BAUDR_115200);
break;
case 230400:
portSettings.setBaudRate(QPortSettings::BAUDR_230400);
break;
case 460800:
portSettings.setBaudRate(QPortSettings::BAUDR_460800);
break;
case 500000:
portSettings.setBaudRate(QPortSettings::BAUDR_500000);
break;
case 576000:
portSettings.setBaudRate(QPortSettings::BAUDR_576000);
break;
case 921600:
portSettings.setBaudRate(QPortSettings::BAUDR_921600);
break;
default:
// If none of the above cases matches, there must be an error
accepted = false;

4
src/uas/UAS.cc

@ -984,7 +984,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) @@ -984,7 +984,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// Restart statemachine
imagePacketsArrived = 0;
emit imageReady(this);
qDebug() << "imageReady emitted. all packets arrived";
//qDebug() << "imageReady emitted. all packets arrived";
}
}
break;
@ -1632,7 +1632,7 @@ QImage UAS::getImage() @@ -1632,7 +1632,7 @@ QImage UAS::getImage()
{
#ifdef MAVLINK_ENABLED_PIXHAWK
qDebug() << "IMAGE TYPE:" << imageType;
// qDebug() << "IMAGE TYPE:" << imageType;
// RAW greyscale
if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)

2
src/ui/HUD.cc

@ -1465,7 +1465,7 @@ void HUD::copyImage() @@ -1465,7 +1465,7 @@ void HUD::copyImage()
{
if (isVisible())
{
qDebug() << "HUD::copyImage()";
//qDebug() << "HUD::copyImage()";
UAS* u = dynamic_cast<UAS*>(this->uas);
if (u)
{

18
src/ui/SerialConfigurationWindow.cc

@ -73,14 +73,6 @@ SerialConfigurationWindow::SerialConfigurationWindow(LinkInterface* link, QWidge @@ -73,14 +73,6 @@ SerialConfigurationWindow::SerialConfigurationWindow(LinkInterface* link, QWidge
supportedBaudRates << 200;
supportedBaudRates << 1800;
#endif
// Baud rates supported only by Linux
#if defined(Q_OS_LINUX)
supportedBaudRates << 230400;
supportedBaudRates << 460800;
supportedBaudRates << 500000;
supportedBaudRates << 576000;
supportedBaudRates << 921600;
#endif
// Baud rates supported only by Windows
#if defined(Q_OS_WIN)
@ -102,6 +94,16 @@ SerialConfigurationWindow::SerialConfigurationWindow(LinkInterface* link, QWidge @@ -102,6 +94,16 @@ SerialConfigurationWindow::SerialConfigurationWindow(LinkInterface* link, QWidge
supportedBaudRates << 38400;
supportedBaudRates << 57600;
supportedBaudRates << 115200;
supportedBaudRates << 230400;
supportedBaudRates << 460800;
#if defined(Q_OS_LINUX)
// Baud rates supported only by Linux
supportedBaudRates << 500000;
supportedBaudRates << 576000;
#endif
supportedBaudRates << 921600;
// Now actually add all of our supported baud rates to the UI.
qSort(supportedBaudRates.begin(), supportedBaudRates.end());

2
thirdParty/qserialport/src/posix/termioshelper.cpp vendored

@ -327,6 +327,8 @@ void TermiosHelper::setBaudRate(QPortSettings::BaudRate baudRate) @@ -327,6 +327,8 @@ void TermiosHelper::setBaudRate(QPortSettings::BaudRate baudRate)
// }
//#else
qCritical() << "Baud rate is now: " << baud;
if ( cfsetspeed(currentAttrs_, baud) == -1 ) {
qCritical() << QString("TermiosHelper::setBaudRate(file: %1) failed: %2(%3)")
.arg(fileDescriptor_)

Loading…
Cancel
Save