1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2025-03-16 08:29:15 +01:00

Merged in filnet/librepilot/LP-410_silence_gcs_logs (pull request #328)

LP-410 silence gcs logs
This commit is contained in:
Alessio Morale 2016-09-21 21:23:42 +02:00
commit e5c180977c
18 changed files with 78 additions and 70 deletions

View File

@ -97,7 +97,7 @@ public:
void updateClearColor() void updateClearColor()
{ {
if (!camera.valid()) { if (!camera.valid()) {
qDebug() << "OSGCamera::updateClearColor - invalid camera"; qWarning() << "OSGCamera::updateClearColor - invalid camera";
return; return;
} }
// qDebug() << "OSGCamera::updateClearColor" << clearColor; // qDebug() << "OSGCamera::updateClearColor" << clearColor;
@ -107,11 +107,11 @@ public:
void updateFieldOfView() void updateFieldOfView()
{ {
if (!camera.valid()) { if (!camera.valid()) {
qDebug() << "OSGCamera::updateFieldOfView - invalid camera"; qWarning() << "OSGCamera::updateFieldOfView - invalid camera";
return; return;
} }
qDebug() << "OSGCamera::updateFieldOfView" << fieldOfView; // qDebug() << "OSGCamera::updateFieldOfView" << fieldOfView;
double fovy, ar, zn, zf; double fovy, ar, zn, zf;
camera->getProjectionMatrixAsPerspective(fovy, ar, zn, zf); camera->getProjectionMatrixAsPerspective(fovy, ar, zn, zf);
@ -122,18 +122,18 @@ public:
void updateAspectRatio() void updateAspectRatio()
{ {
if (!camera.valid()) { if (!camera.valid()) {
qDebug() << "OSGCamera::updateAspectRatio - invalid camera"; qWarning() << "OSGCamera::updateAspectRatio - invalid camera";
return; return;
} }
osg::Viewport *viewport = camera->getViewport(); osg::Viewport *viewport = camera->getViewport();
if (!viewport) { if (!viewport) {
qDebug() << "OSGCamera::updateAspectRatio - no viewport" << viewport; qWarning() << "OSGCamera::updateAspectRatio - no viewport" << viewport;
return; return;
} }
double aspectRatio = static_cast<double>(viewport->width()) / static_cast<double>(viewport->height()); double aspectRatio = static_cast<double>(viewport->width()) / static_cast<double>(viewport->height());
qDebug() << "OSGCamera::updateAspectRatio" << aspectRatio; // qDebug() << "OSGCamera::updateAspectRatio" << aspectRatio;
double fovy, ar, zn, zf; double fovy, ar, zn, zf;
camera->getProjectionMatrixAsPerspective(fovy, ar, zn, zf); camera->getProjectionMatrixAsPerspective(fovy, ar, zn, zf);
@ -152,12 +152,12 @@ public:
#ifdef USE_OSGEARTH #ifdef USE_OSGEARTH
// install log depth buffer if requested // install log depth buffer if requested
if (logDepthBufferEnabled && !logDepthBuffer) { if (logDepthBufferEnabled && !logDepthBuffer) {
qDebug() << "OSGCamera::updateLogDepthBuffer - installing logarithmic depth buffer"; // qDebug() << "OSGCamera::updateLogDepthBuffer - installing logarithmic depth buffer";
logDepthBuffer = new osgEarth::Util::LogarithmicDepthBuffer(); logDepthBuffer = new osgEarth::Util::LogarithmicDepthBuffer();
logDepthBuffer->setUseFragDepth(true); logDepthBuffer->setUseFragDepth(true);
logDepthBuffer->install(camera); logDepthBuffer->install(camera);
} else if (!logDepthBufferEnabled && logDepthBuffer) { } else if (!logDepthBufferEnabled && logDepthBuffer) {
qDebug() << "OSGCamera::updateLogDepthBuffer - uninstalling logarithmic depth buffer"; // qDebug() << "OSGCamera::updateLogDepthBuffer - uninstalling logarithmic depth buffer";
logDepthBuffer->uninstall(camera); logDepthBuffer->uninstall(camera);
delete logDepthBuffer; delete logDepthBuffer;
logDepthBuffer = NULL; logDepthBuffer = NULL;
@ -168,11 +168,11 @@ public:
void setGraphicsContext(osg::GraphicsContext *gc) void setGraphicsContext(osg::GraphicsContext *gc)
{ {
if (!camera.valid()) { if (!camera.valid()) {
qDebug() << "OSGCamera::setGraphicsContext - invalid camera"; qWarning() << "OSGCamera::setGraphicsContext - invalid camera";
return; return;
} }
qDebug() << "OSGCamera::setGraphicsContext" << gc; // qDebug() << "OSGCamera::setGraphicsContext" << gc;
camera->setGraphicsContext(gc); camera->setGraphicsContext(gc);
camera->setViewport(0, 0, gc->getTraits()->width, gc->getTraits()->height); camera->setViewport(0, 0, gc->getTraits()->width, gc->getTraits()->height);

View File

@ -90,7 +90,7 @@ public:
void updateSource() void updateSource()
{ {
qDebug() << "OSGFileNode::updateNode" << source; // qDebug() << "OSGFileNode::updateNode" << source;
if (!source.isValid()) { if (!source.isValid()) {
self->setNode(NULL); self->setNode(NULL);
if (!source.isEmpty()) { if (!source.isEmpty()) {

View File

@ -72,7 +72,7 @@ public:
bool acceptSceneNode(OSGNode *node) bool acceptSceneNode(OSGNode *node)
{ {
qDebug() << "OSGGeoTransformNode::acceptSceneNode" << node; // qDebug() << "OSGGeoTransformNode::acceptSceneNode" << node;
if (sceneNode == node) { if (sceneNode == node) {
return false; return false;
} }
@ -92,7 +92,7 @@ public:
void updateSceneNode() void updateSceneNode()
{ {
qDebug() << "OSGGeoTransformNode::updateSceneNode" << sceneNode; // qDebug() << "OSGGeoTransformNode::updateSceneNode" << sceneNode;
if (sceneNode && sceneNode->node()) { if (sceneNode && sceneNode->node()) {
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneNode->node()); osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneNode->node());
if (mapNode) { if (mapNode) {
@ -148,7 +148,7 @@ public:
private slots: private slots:
void onSceneNodeChanged(osg::Node *node) void onSceneNodeChanged(osg::Node *node)
{ {
qDebug() << "OSGGeoTransformNode::onSceneNodeChanged" << node; // qDebug() << "OSGGeoTransformNode::onSceneNodeChanged" << node;
updateSceneNode(); updateSceneNode();
updatePosition(); updatePosition();
} }

View File

@ -88,7 +88,7 @@ public:
void updateChildren() void updateChildren()
{ {
qDebug() << "OSGGroup::updateChildren"; // qDebug() << "OSGGroup::updateChildren";
osg::Group *group = static_cast<osg::Group *>(self->node()); osg::Group *group = static_cast<osg::Group *>(self->node());
if (!group) { if (!group) {

View File

@ -70,7 +70,7 @@ public:
bool acceptSceneNode(OSGNode *node) bool acceptSceneNode(OSGNode *node)
{ {
qDebug() << "OSGSkyNode::acceptSceneNode" << node; // qDebug() << "OSGSkyNode::acceptSceneNode" << node;
if (sceneNode == node) { if (sceneNode == node) {
return false; return false;
} }
@ -95,7 +95,7 @@ public:
self->setNode(NULL); self->setNode(NULL);
return; return;
} }
qDebug() << "OSGSkyNode::updateScene - scene node" << sceneNode->node(); // qDebug() << "OSGSkyNode::updateScene - scene node" << sceneNode->node();
osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneNode->node()); osgEarth::MapNode *mapNode = osgEarth::MapNode::findMapNode(sceneNode->node());
if (!mapNode) { if (!mapNode) {
qWarning() << "OSGSkyNode::updateScene - scene node does not contain a map node"; qWarning() << "OSGSkyNode::updateScene - scene node does not contain a map node";
@ -151,12 +151,12 @@ public:
void updateViewport() void updateViewport()
{ {
qDebug() << "OSGSkyNode::updateViewport" << skyNode; // qDebug() << "OSGSkyNode::updateViewport" << skyNode;
if (!skyNode.valid()) { if (!skyNode.valid()) {
qWarning() << "OSGSkyNode::updateViewport - invalid sky node" << skyNode; qWarning() << "OSGSkyNode::updateViewport - invalid sky node" << skyNode;
return; return;
} }
qDebug() << "OSGSkyNode::updateViewport - attaching to" << viewport->asView(); // qDebug() << "OSGSkyNode::updateViewport - attaching to" << viewport->asView();
skyNode->attach(viewport->asView()); skyNode->attach(viewport->asView());
} }
@ -216,7 +216,7 @@ public:
private slots: private slots:
void onSceneNodeChanged(osg::Node *node) void onSceneNodeChanged(osg::Node *node)
{ {
qDebug() << "OSGSkyNode::onSceneNodeChanged" << node; // qDebug() << "OSGSkyNode::onSceneNodeChanged" << node;
updateScene(); updateScene();
} }
}; };

View File

@ -271,7 +271,7 @@ private slots:
public: public:
bool acceptSceneNode(OSGNode *node) bool acceptSceneNode(OSGNode *node)
{ {
qDebug() << "OSGViewport::acceptSceneNode" << node; // qDebug() << "OSGViewport::acceptSceneNode" << node;
if (sceneNode == node) { if (sceneNode == node) {
return true; return true;
} }
@ -291,7 +291,7 @@ public:
bool acceptCameraNode(OSGCamera *node) bool acceptCameraNode(OSGCamera *node)
{ {
qDebug() << "OSGViewport::acceptCameraNode" << node; // qDebug() << "OSGViewport::acceptCameraNode" << node;
if (cameraNode == node) { if (cameraNode == node) {
return true; return true;
} }
@ -311,7 +311,7 @@ public:
bool acceptManipulator(OSGCameraManipulator *m) bool acceptManipulator(OSGCameraManipulator *m)
{ {
qDebug() << "OSGViewport::acceptManipulator" << manipulator; // qDebug() << "OSGViewport::acceptManipulator" << manipulator;
if (manipulator == m) { if (manipulator == m) {
return true; return true;
} }
@ -370,7 +370,7 @@ private:
void onAboutToBeDestroyed() void onAboutToBeDestroyed()
{ {
qDebug() << "OSGViewport::Hidden::onAboutToBeDestroyed"; // qDebug() << "OSGViewport::Hidden::onAboutToBeDestroyed";
osgQtQuick::openGLContextInfo(QOpenGLContext::currentContext(), "OSGViewport::Hidden::onAboutToBeDestroyed"); osgQtQuick::openGLContextInfo(QOpenGLContext::currentContext(), "OSGViewport::Hidden::onAboutToBeDestroyed");
// context is not current and don't know how to make it current... // context is not current and don't know how to make it current...
} }

View File

@ -69,7 +69,7 @@ public:
bool acceptSceneNode(OSGNode *node) bool acceptSceneNode(OSGNode *node)
{ {
qDebug() << "OSGCameraManipulator::acceptSceneNode" << node; // qDebug() << "OSGCameraManipulator::acceptSceneNode" << node;
if (sceneNode == node) { if (sceneNode == node) {
return true; return true;
} }
@ -93,14 +93,14 @@ public:
qWarning() << "OSGCameraManipulator::updateSceneNode - no scene node"; qWarning() << "OSGCameraManipulator::updateSceneNode - no scene node";
return; return;
} }
qDebug() << "OSGCameraManipulator::updateSceneNode" << sceneNode; // qDebug() << "OSGCameraManipulator::updateSceneNode" << sceneNode;
manipulator->setNode(sceneNode->node()); manipulator->setNode(sceneNode->node());
} }
private slots: private slots:
void onSceneNodeChanged(osg::Node *node) void onSceneNodeChanged(osg::Node *node)
{ {
qDebug() << "OSGCameraManipulator::onSceneNodeChanged" << node; // qDebug() << "OSGCameraManipulator::onSceneNodeChanged" << node;
updateSceneNode(); updateSceneNode();
} }
}; };
@ -150,7 +150,7 @@ void OSGCameraManipulator::classBegin()
void OSGCameraManipulator::componentComplete() void OSGCameraManipulator::componentComplete()
{ {
qDebug() << "OSGCameraManipulator::componentComplete" << this; // qDebug() << "OSGCameraManipulator::componentComplete" << this;
update(); update();
clearDirty(); clearDirty();
} }

View File

@ -65,7 +65,7 @@ public:
bool acceptTrackNode(OSGNode *node) bool acceptTrackNode(OSGNode *node)
{ {
qDebug() << "OSGNodeTrackerManipulator::acceptTrackNode" << node; // qDebug() << "OSGNodeTrackerManipulator::acceptTrackNode" << node;
if (trackNode == node) { if (trackNode == node) {
return false; return false;
} }
@ -89,7 +89,7 @@ public:
qWarning() << "OSGNodeTrackerManipulator::updateTrackNode - no track node"; qWarning() << "OSGNodeTrackerManipulator::updateTrackNode - no track node";
return; return;
} }
qDebug() << "OSGNodeTrackerManipulator::updateTrackNode" << trackNode->node(); // qDebug() << "OSGNodeTrackerManipulator::updateTrackNode" << trackNode->node();
manipulator->setTrackNode(trackNode->node()); manipulator->setTrackNode(trackNode->node());
} }
@ -117,7 +117,7 @@ public:
private slots: private slots:
void onTrackNodeChanged(osg::Node *node) void onTrackNodeChanged(osg::Node *node)
{ {
qDebug() << "OSGNodeTrackerManipulator::onTrackNodeChanged" << node; // qDebug() << "OSGNodeTrackerManipulator::onTrackNodeChanged" << node;
qWarning() << "OSGNodeTrackerManipulator::onTrackNodeChanged - needs to be implemented"; qWarning() << "OSGNodeTrackerManipulator::onTrackNodeChanged - needs to be implemented";
} }
}; };

View File

@ -89,7 +89,7 @@ void AntennaTrackGadget::loadConfiguration(IUAVGadgetConfiguration *config)
} }
} }
m_widget->dataStreamGroupBox->setHidden(false); m_widget->dataStreamGroupBox->setHidden(false);
qDebug() << "Using Telemetry parser";
parser = new TelemetryParser(); parser = new TelemetryParser();
connect(parser, SIGNAL(position(double, double, double)), m_widget, SLOT(setPosition(double, double, double))); connect(parser, SIGNAL(position(double, double, double)), m_widget, SLOT(setPosition(double, double, double)));

View File

@ -874,7 +874,7 @@ void ConfigMultiRotorWidget::reverseMultirotorMotor()
void ConfigMultiRotorWidget::updateAirframe(QString frameType) void ConfigMultiRotorWidget::updateAirframe(QString frameType)
{ {
qDebug() << "ConfigMultiRotorWidget::updateAirframe - frame type" << frameType; // qDebug() << "ConfigMultiRotorWidget::updateAirframe - frame type" << frameType;
QString elementId; QString elementId;
if (frameType == "Tri" || frameType == "Tricopter Y") { if (frameType == "Tri" || frameType == "Tricopter Y") {

View File

@ -441,7 +441,7 @@ void ConnectionManager::devChanged(IConnection *connection)
updateConnectionDropdown(); updateConnectionDropdown();
qDebug() << "# devices " << m_devList.count(); qDebug() << "ConnectionManager::devChanged - device count:" << m_devList.count();
emit availableDevicesChanged(m_devList); emit availableDevicesChanged(m_devList);
@ -464,9 +464,8 @@ void ConnectionManager::updateConnectionDropdown()
m_availableDevList->setCurrentIndex(m_availableDevList->count() - 1); m_availableDevList->setCurrentIndex(m_availableDevList->count() - 1);
} }
if (m_mainWindow->generalSettings()->autoConnect() && polling) { if (m_mainWindow->generalSettings()->autoConnect() && polling) {
qDebug() << "Automatically opening device"; qDebug() << "ConnectionManager::updateConnectionDropdown - auto-connecting USB device";
connectDevice(d); connectDevice(d);
qDebug() << "ConnectionManager::updateConnectionDropdown autoconnected USB device";
} }
} }
} }

View File

@ -41,7 +41,6 @@
#include <QtCore/QDebug> #include <QtCore/QDebug>
#include <QMessageBox> #include <QMessageBox>
using namespace Core; using namespace Core;
static const UAVConfigVersion m_versionUAVGadgetConfigurations = UAVConfigVersion("1.2.0"); static const UAVConfigVersion m_versionUAVGadgetConfigurations = UAVConfigVersion("1.2.0");
@ -116,7 +115,7 @@ void UAVGadgetInstanceManager::readConfigs_1_2_0(QSettings *qs)
configs = qs->childGroups(); configs = qs->childGroups();
foreach(QString configName, configs) { foreach(QString configName, configs) {
qDebug() << "Loading config: " << classId << "," << configName; // qDebug() << "Loading config: " << classId << "," << configName;
qs->beginGroup(configName); qs->beginGroup(configName);
configInfo.read(qs); configInfo.read(qs);
configInfo.setNameOfConfigurable(classId + "-" + configName); configInfo.setNameOfConfigurable(classId + "-" + configName);
@ -166,7 +165,7 @@ void UAVGadgetInstanceManager::readConfigs_1_1_0(QSettings *qs)
configs = qs->childGroups(); configs = qs->childGroups();
foreach(QString configName, configs) { foreach(QString configName, configs) {
qDebug().nospace() << "Loading config: " << classId << ", " << configName; // qDebug().nospace() << "Loading config: " << classId << ", " << configName;
qs->beginGroup(configName); qs->beginGroup(configName);
bool locked = qs->value("config.locked").toBool(); bool locked = qs->value("config.locked").toBool();
configInfo.setNameOfConfigurable(classId + "-" + configName); configInfo.setNameOfConfigurable(classId + "-" + configName);
@ -250,8 +249,8 @@ void UAVGadgetInstanceManager::createOptionsPages()
m_pm->addObject(page); m_pm->addObject(page);
} else { } else {
qWarning() qWarning()
<< "UAVGadgetInstanceManager::createOptionsPages - failed to create options page for configuration " << "UAVGadgetInstanceManager::createOptionsPages - failed to create options page for configuration"
+ config->classId() + ":" + config->name() + ", configuration will be removed."; << (config->classId() + ":" + config->name()) << ", configuration will be removed.";
// The m_optionsPages list and m_configurations list must be in synch otherwise nasty issues happen later // The m_optionsPages list and m_configurations list must be in synch otherwise nasty issues happen later
// so if we fail to create an options page we must remove the associated configuration // so if we fail to create an options page we must remove the associated configuration
ite.remove(); ite.remove();

View File

@ -91,7 +91,6 @@ void GpsDisplayGadget::loadConfiguration(IUAVGadgetConfiguration *config)
} }
m_widget->dataStreamGroupBox->setHidden(false); m_widget->dataStreamGroupBox->setHidden(false);
} else if (gpsDisplayConfig->connectionMode() == "Telemetry") { } else if (gpsDisplayConfig->connectionMode() == "Telemetry") {
qDebug() << "Using Telemetry parser";
parser = new TelemetryParser(); parser = new TelemetryParser();
m_widget->disconnectButton->setHidden(true); m_widget->disconnectButton->setHidden(true);
m_widget->connectButton->setHidden(true); m_widget->connectButton->setHidden(true);

View File

@ -67,7 +67,7 @@ QList<QQmlError> PfdQmlGadgetWidget::errors() const
void PfdQmlGadgetWidget::loadConfiguration(PfdQmlGadgetConfiguration *config) void PfdQmlGadgetWidget::loadConfiguration(PfdQmlGadgetConfiguration *config)
{ {
qDebug() << "PfdQmlGadgetWidget::loadConfiguration" << config->name(); // qDebug() << "PfdQmlGadgetWidget::loadConfiguration" << config->name();
if (!m_quickWidgetProxy) { if (!m_quickWidgetProxy) {
m_quickWidgetProxy = new QuickWidgetProxy(this); m_quickWidgetProxy = new QuickWidgetProxy(this);
@ -85,7 +85,7 @@ void PfdQmlGadgetWidget::loadConfiguration(PfdQmlGadgetConfiguration *config)
layout()->addWidget(m_quickWidgetProxy->widget()); layout()->addWidget(m_quickWidgetProxy->widget());
} }
setQmlFile(""); clear();
m_pfdQmlContext->loadConfiguration(config); m_pfdQmlContext->loadConfiguration(config);
@ -110,28 +110,35 @@ void PfdQmlGadgetWidget::setQmlFile(QString fn)
m_qmlFileName = fn; m_qmlFileName = fn;
if (fn.isEmpty()) { if (fn.isEmpty()) {
setSource(QUrl()); clear();
return;
engine()->removeImageProvider("svg");
engine()->rootContext()->setContextProperty("svgRenderer", NULL);
// calling clearComponentCache() causes crashes (see https://bugreports.qt-project.org/browse/QTBUG-41465)
// but not doing it causes almost systematic crashes when switching PFD gadget to "Model View (Without Terrain)" configuration
engine()->clearComponentCache();
} else {
SvgImageProvider *svgProvider = new SvgImageProvider(fn);
engine()->addImageProvider("svg", svgProvider);
// it's necessary to allow qml side to query svg element position
engine()->rootContext()->setContextProperty("svgRenderer", svgProvider);
QUrl url = QUrl::fromLocalFile(fn);
engine()->setBaseUrl(url);
setSource(url);
} }
SvgImageProvider *svgProvider = new SvgImageProvider(fn);
engine()->addImageProvider("svg", svgProvider);
// it's necessary to allow qml side to query svg element position
engine()->rootContext()->setContextProperty("svgRenderer", svgProvider);
QUrl url = QUrl::fromLocalFile(fn);
engine()->setBaseUrl(url);
setSource(url);
foreach(const QQmlError &error, errors()) { foreach(const QQmlError &error, errors()) {
qDebug() << "PfdQmlGadgetWidget - " << error.description(); qDebug() << "PfdQmlGadgetWidget - " << error.description();
} }
} }
void PfdQmlGadgetWidget::clear()
{
// qDebug() << "PfdQmlGadgetWidget::clear";
setSource(QUrl());
engine()->removeImageProvider("svg");
engine()->rootContext()->setContextProperty("svgRenderer", NULL);
// calling clearComponentCache() causes crashes (see https://bugreports.qt-project.org/browse/QTBUG-41465)
// but not doing it causes almost systematic crashes when switching PFD gadget to "Model View (Without Terrain)" configuration
engine()->clearComponentCache();
}

View File

@ -50,16 +50,18 @@ public:
void restoreState(QSettings *); void restoreState(QSettings *);
private: private:
QuickWidgetProxy *m_quickWidgetProxy;
PfdQmlContext *m_pfdQmlContext;
QString m_qmlFileName;
void setQmlFile(QString); void setQmlFile(QString);
void clear();
void setSource(const QUrl &url); void setSource(const QUrl &url);
QQmlEngine *engine() const; QQmlEngine *engine() const;
QList<QQmlError> errors() const; QList<QQmlError> errors() const;
QuickWidgetProxy *m_quickWidgetProxy;
PfdQmlContext *m_pfdQmlContext;
QString m_qmlFileName;
}; };
#endif /* PFDQMLGADGETWIDGET_H_ */ #endif /* PFDQMLGADGETWIDGET_H_ */

View File

@ -73,12 +73,12 @@ void SerialPluginConfiguration::restoresettings()
{ {
settings->beginGroup(QLatin1String("SerialConnection")); settings->beginGroup(QLatin1String("SerialConnection"));
QString str = (settings->value(QLatin1String("speed"), tr("")).toString()); QString str = (settings->value(QLatin1String("speed"), tr("")).toString());
qDebug() << "SerialPluginConfiguration::restoresettings - speed" << str;
if (str.isEmpty()) { if (str.isEmpty()) {
m_speed = "57600"; m_speed = "57600";
} else { } else {
m_speed = str; m_speed = str;
} }
// qDebug() << "SerialPluginConfiguration::restoresettings - speed" << str;
settings->endGroup(); settings->endGroup();
} }

View File

@ -59,7 +59,9 @@ UAVTalk::UAVTalk(QIODevice *iodev, UAVObjectManager *objMngr) : io(iodev), objMn
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>(); Core::Internal::GeneralSettings *settings = pm->getObject<Core::Internal::GeneralSettings>();
useUDPMirror = settings->useUDPMirror(); useUDPMirror = settings->useUDPMirror();
qDebug() << "USE UDP:::::::::::." << useUDPMirror; if (useUDPMirror) {
qDebug() << "UAVTalk::UAVTalk -*** UDP mirror is enabled ***";
}
if (useUDPMirror) { if (useUDPMirror) {
udpSocketTx = new QUdpSocket(this); udpSocketTx = new QUdpSocket(this);
udpSocketRx = new QUdpSocket(this); udpSocketRx = new QUdpSocket(this);

View File

@ -66,7 +66,7 @@ void RunningDeviceWidget::populate()
myDevice->lblDeviceID->setText(QString("Device ID: ") + QString::number(id, 16)); myDevice->lblDeviceID->setText(QString("Device ID: ") + QString::number(id, 16));
myDevice->lblBoardName->setText(deviceDescriptorStruct::idToBoardName(id)); myDevice->lblBoardName->setText(deviceDescriptorStruct::idToBoardName(id));
myDevice->lblHWRev->setText(QString(tr("HW Revision: ")) + QString::number(id & 0x00FF, 16)); myDevice->lblHWRev->setText(QString(tr("HW Revision: ")) + QString::number(id & 0x00FF, 16));
qDebug() << "CRC" << utilMngr->getFirmwareCRC(); // qDebug() << "CRC" << utilMngr->getFirmwareCRC();
myDevice->lblCRC->setText(QString(tr("Firmware CRC: ")) + QVariant(utilMngr->getFirmwareCRC()).toString()); myDevice->lblCRC->setText(QString(tr("Firmware CRC: ")) + QVariant(utilMngr->getFirmwareCRC()).toString());
// DeviceID tells us what sort of HW we have detected: // DeviceID tells us what sort of HW we have detected:
// display a nice icon: // display a nice icon: