Commit 5348f704 authored by LM's avatar LM

Enabled 921600 and other high baud rates on all platforms

parent 69c9cb1f
......@@ -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)
......
This diff is collapsed.
......@@ -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()
{
#ifdef MAVLINK_ENABLED_PIXHAWK
qDebug() << "IMAGE TYPE:" << imageType;
// qDebug() << "IMAGE TYPE:" << imageType;
// RAW greyscale
if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U)
......
......@@ -1465,7 +1465,7 @@ void HUD::copyImage()
{
if (isVisible())
{
qDebug() << "HUD::copyImage()";
//qDebug() << "HUD::copyImage()";
UAS* u = dynamic_cast<UAS*>(this->uas);
if (u)
{
......
......@@ -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
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());
......
......@@ -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_)
......
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