Commit 2cc7c1fd authored by pixhawk's avatar pixhawk
parents 34e8cb2a dcd0715b
......@@ -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() && hudInstrumentsEnabled)
{
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());
......
......@@ -4,6 +4,8 @@ GLOverlayGeode::GLOverlayGeode()
: mDrawable(new GLOverlayDrawable)
, mMessageTimestamp(0.0)
{
setCullingActive(false);
addDrawable(mDrawable);
}
......@@ -150,6 +152,8 @@ GLOverlayGeode::GLOverlayDrawable::drawImplementation(osg::RenderInfo&) const
glMatrixMode(GL_MODELVIEW);
glDisable(GL_LIGHTING);
glEnable(GL_BLEND);
glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
glPushMatrix();
glScalef(-1.0f, 1.0f, -1.0f);
......@@ -404,6 +408,7 @@ GLOverlayGeode::GLOverlayDrawable::drawImplementation(osg::RenderInfo&) const
glPopMatrix();
glEnable(GL_LIGHTING);
glDisable(GL_BLEND);
}
osg::BoundingBox
......
......@@ -31,9 +31,11 @@ This file is part of the QGROUNDCONTROL project
#include "ObstacleGroupNode.h"
#include <limits>
#include <osg/PositionAttitudeTransform>
#include <osg/ShapeDrawable>
#include "gpl.h"
#include "Imagery.h"
ObstacleGroupNode::ObstacleGroupNode()
......@@ -64,6 +66,25 @@ ObstacleGroupNode::update(double robotX, double robotY, double robotZ,
osg::ref_ptr<osg::Geode> geode = new osg::Geode;
// find minimum and maximum height
float zMin = std::numeric_limits<float>::max();
float zMax = std::numeric_limits<float>::min();
for (int i = 0; i < obstacleList.obstacles_size(); ++i)
{
const px::Obstacle& obs = obstacleList.obstacles(i);
float z = robotZ - obs.z();
if (zMin > z)
{
zMin = z;
}
if (zMax < z)
{
zMax = z;
}
}
for (int i = 0; i < obstacleList.obstacles_size(); ++i)
{
const px::Obstacle& obs = obstacleList.obstacles(i);
......@@ -74,8 +95,12 @@ ObstacleGroupNode::update(double robotX, double robotY, double robotZ,
new osg::Box(obsPos, obs.width(), obs.width(), obs.height());
osg::ref_ptr<osg::ShapeDrawable> sd = new osg::ShapeDrawable(box);
int idx = (obsPos.z() - zMin) / (zMax - zMin) * 127.0f;
float r, g, b;
qgc::colormap("jet", idx, r, g, b);
sd->getOrCreateStateSet()->setMode(GL_BLEND, osg::StateAttribute::ON);
sd->setColor(osg::Vec4(0.0f, 0.0f, 1.0f, 1.0f));
sd->setColor(osg::Vec4(r, g, b, 1.0f));
geode->addDrawable(sd);
}
......
......@@ -472,7 +472,10 @@ Pixhawk3DWidget::clearData(void)
systemData.setpointGroupNode()->removeChildren(0, systemData.setpointGroupNode()->getNumChildren());
// clear trail data
systemData.orientationNode()->removeChildren(0, systemData.orientationNode()->getNumChildren());
systemData.trailIndexMap().clear();
systemData.trailMap().clear();
systemData.trailNode()->removeDrawables(0, systemData.trailNode()->getNumDrawables());
}
}
......
#include "SystemViewParams.h"
#include <QCheckBox>
SystemViewParams::SystemViewParams(int systemId)
: mSystemId(systemId)
, mColorPointCloudByDistance(false)
......@@ -240,14 +242,17 @@ SystemViewParams::toggleObstacleList(int state)
}
void
SystemViewParams::toggleOverlay(const QString& name)
SystemViewParams::toggleOverlay(QWidget* widget)
{
const QCheckBox* checkbox = dynamic_cast<QCheckBox*>(widget);
QString name = checkbox->accessibleName();
if (!mDisplayOverlay.contains(name))
{
return;
}
mDisplayOverlay[name] = !mDisplayOverlay[name];
mDisplayOverlay[name] = (checkbox->checkState() == Qt::Checked);
}
void
......
......@@ -5,6 +5,7 @@
#include <QObject>
#include <QSharedPointer>
#include <QVector>
#include <QWidget>
class SystemViewParams : public QObject
{
......@@ -61,7 +62,7 @@ public slots:
void toggleColorPointCloud(int state);
void toggleLocalGrid(int state);
void toggleObstacleList(int state);
void toggleOverlay(const QString& name);
void toggleOverlay(QWidget* widget);
void togglePlannedPath(int state);
void togglePointCloud(int state);
void toggleRGBD(int state);
......
......@@ -65,14 +65,16 @@ ViewParamWidget::overlayCreated(int systemId, const QString& name)
systemViewParams->displayOverlay().insert(name, true);
QCheckBox* checkbox = new QCheckBox(this);
checkbox->setAccessibleName(name);
checkbox->setChecked(systemViewParams->displayOverlay().value(name));
mOverlayLayout[systemId]->addRow(name, checkbox);
mOverlaySignalMapper->setMapping(checkbox, name);
mOverlaySignalMapper->setMapping(checkbox, checkbox);
connect(checkbox, SIGNAL(clicked()),
mOverlaySignalMapper, SLOT(map()));
connect(mOverlaySignalMapper, SIGNAL(mapped(QString)),
systemViewParams.data(), SLOT(toggleOverlay(QString)));
connect(mOverlaySignalMapper, SIGNAL(mapped(QWidget*)),
systemViewParams.data(), SLOT(toggleOverlay(QWidget*)));
}
void
......
......@@ -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