diff --git a/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp b/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp index de7d35721376bb26957ddf5b4708b8269ddfea5e..ff5eba2305fb76681e5fed9f83a0a3a1d79ca3d4 100644 --- a/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp +++ b/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp @@ -133,13 +133,15 @@ namespace mapcontrol temp=QImage(size, QImage::Format_ARGB32_Premultiplied); temp.fill(0); - QPainter imagePainter(&temp); - imagePainter.translate(-boundingRect().topLeft()); - imagePainter.scale(2*zoomdiff,2*zoomdiff); - paintImage(&imagePainter); - imagePainter.end(); - lastimagepoint=Point(core->GetrenderOffset().X()*2*zoomdiff,core->GetrenderOffset().Y()*2*zoomdiff); - lastimage=temp; + if (!temp.isNull()) { + QPainter imagePainter(&temp); + imagePainter.translate(-boundingRect().topLeft()); + imagePainter.scale(2*zoomdiff,2*zoomdiff); + paintImage(&imagePainter); + imagePainter.end(); + lastimagepoint=Point(core->GetrenderOffset().X()*2*zoomdiff,core->GetrenderOffset().Y()*2*zoomdiff); + lastimage=temp; + } } void MapGraphicItem::paintImage(QPainter *painter) { diff --git a/src/comm/ParameterList.cc b/src/comm/ParameterList.cc index 98bac5a1b736ec0c2493718c8fa92f09761e6f35..ecb627e39cdbff893834aa10eb474a90d518befe 100644 --- a/src/comm/ParameterList.cc +++ b/src/comm/ParameterList.cc @@ -78,7 +78,7 @@ ParameterList::ParameterList() (*paramIter).setOpalID(opalParams->value(s)); // qDebug() << __FILE__ << " Line:" << __LINE__ << ": Successfully added " << s; } else { - qWarning() << __FILE__ << " Line:" << __LINE__ << ": " << s << " was not found in param list"; + qDebug() << __FILE__ << " Line:" << __LINE__ << ": " << s << " was not found in param list"; } } } diff --git a/src/uas/QGCUASParamManager.cc b/src/uas/QGCUASParamManager.cc index 333d73383d123fddf600f099db71112062d196ae..4fa648a3f12a754906f5bab0ffc0e12ad20fadd5 100644 --- a/src/uas/QGCUASParamManager.cc +++ b/src/uas/QGCUASParamManager.cc @@ -5,13 +5,11 @@ #include #include "UASInterface.h" -#include "UASParameterCommsMgr.h" QGCUASParamManager::QGCUASParamManager(QObject *parent) : QGCUASParamManagerInterface(parent), mav(NULL), - paramDataModel(this), - paramCommsMgr(NULL) + paramDataModel(this) { @@ -25,8 +23,7 @@ QGCUASParamManager* QGCUASParamManager::initWithUAS(UASInterface* uas) loadParamMetaInfoCSV(); paramDataModel.setUASID(mav->getUASID()); - paramCommsMgr = new UASParameterCommsMgr(this); - paramCommsMgr->initWithUAS(uas); + paramCommsMgr.initWithUAS(uas); connectToModelAndComms(); @@ -36,10 +33,10 @@ QGCUASParamManager* QGCUASParamManager::initWithUAS(UASInterface* uas) void QGCUASParamManager::connectToModelAndComms() { // Pass along comms mgr status msgs - connect(paramCommsMgr, SIGNAL(parameterStatusMsgUpdated(QString,int)), + connect(¶mCommsMgr, SIGNAL(parameterStatusMsgUpdated(QString,int)), this, SIGNAL(parameterStatusMsgUpdated(QString,int))); - connect(paramCommsMgr, SIGNAL(parameterListUpToDate()), + connect(¶mCommsMgr, SIGNAL(parameterListUpToDate()), this, SIGNAL(parameterListUpToDate())); // Pass along data model updates @@ -81,7 +78,7 @@ bool QGCUASParamManager::getParameterValue(int component, const QString& paramet void QGCUASParamManager::requestParameterUpdate(int component, const QString& parameter) { if (mav) { - paramCommsMgr->requestParameterUpdate(component,parameter); + paramCommsMgr.requestParameterUpdate(component,parameter); } } @@ -95,7 +92,7 @@ void QGCUASParamManager::requestParameterList() { if (mav) { emit parameterStatusMsgUpdated(tr("Requested param list.. waiting"), UASParameterCommsMgr::ParamCommsStatusLevel_OK); - paramCommsMgr->requestParameterList(); + paramCommsMgr.requestParameterList(); } } @@ -126,7 +123,7 @@ void QGCUASParamManager::setParameter(int compId, QString paramName, QVariant va void QGCUASParamManager::sendPendingParameters(bool persistAfterSend, bool forceSend) { - paramCommsMgr->sendPendingParameters(persistAfterSend, forceSend); + paramCommsMgr.sendPendingParameters(persistAfterSend, forceSend); } @@ -156,7 +153,7 @@ void QGCUASParamManager::loadParamMetaInfoCSV() qDebug() << "loadParamMetaInfoCSV for autopilot: " << autopilot << " from file: " << fileName; if (!paramMetaFile.open(QIODevice::ReadOnly | QIODevice::Text)) { - qWarning() << "loadParamMetaInfoCSV couldn't open:" << fileName; + qDebug() << "loadParamMetaInfoCSV couldn't open:" << fileName; return; } @@ -201,7 +198,7 @@ void QGCUASParamManager::copyVolatileParamsToPersistent() msgBox.exec(); } else { - paramCommsMgr->writeParamsToPersistentStorage(); + paramCommsMgr.writeParamsToPersistentStorage(); } } @@ -215,5 +212,5 @@ void QGCUASParamManager::copyPersistentParamsToVolatile() void QGCUASParamManager::requestRcCalibrationParamsUpdate() { - paramCommsMgr->requestRcCalibrationParamsUpdate(); + paramCommsMgr.requestRcCalibrationParamsUpdate(); } diff --git a/src/uas/QGCUASParamManager.h b/src/uas/QGCUASParamManager.h index 156bf453dd06ad88b6c2b58b2bcb5402a3236c96..6d63ee9ee35ad4d624516cc3048160d6ac409dbc 100644 --- a/src/uas/QGCUASParamManager.h +++ b/src/uas/QGCUASParamManager.h @@ -8,11 +8,11 @@ #include "UASParameterDataModel.h" #include "QGCUASParamManagerInterface.h" +#include "UASParameterCommsMgr.h" //forward declarations class QTextStream; class UASInterface; -class UASParameterCommsMgr; class QGCUASParamManager : public QGCUASParamManagerInterface { @@ -125,7 +125,7 @@ protected: // Parameter data model UASInterface* mav; ///< The MAV this manager is controlling UASParameterDataModel paramDataModel;///< Shared data model of parameters - UASParameterCommsMgr* paramCommsMgr; ///< Shared comms mgr for parameters + UASParameterCommsMgr paramCommsMgr; ///< Shared comms mgr for parameters }; diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 599840f3a0b33bd5449789cd830a86539c4ec901..f4e25b4bff351171cc47d61c54340a1dff32c4c5 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -1418,7 +1418,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) unknownPackets.append(message.msgid); emit unknownPacketReceived(uasId, message.compid, message.msgid); - qWarning() << "Unknown message from system:" << uasId << "message:" << message.msgid; + qDebug() << "Unknown message from system:" << uasId << "message:" << message.msgid; } } break; @@ -1787,7 +1787,7 @@ void UAS::sendMessage(mavlink_message_t message) { if (!LinkManager::instance()) { - qWarning() << "LINKMANAGER NOT AVAILABLE!"; + qDebug() << "LINKMANAGER NOT AVAILABLE!"; return; } @@ -2931,6 +2931,8 @@ bool UAS::emergencyKILL() */ void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObject * configuration) { + Q_UNUSED(configuration); + QGCFlightGearLink* link = dynamic_cast(simulation); if (!link || !simulation) { // Delete wrong sim @@ -2944,7 +2946,8 @@ void UAS::enableHilFlightGear(bool enable, QString options, bool sensorHil, QObj link = dynamic_cast(simulation); link->setStartupArguments(options); link->sensorHilEnabled(sensorHil); - QObject::connect(configuration, SIGNAL(barometerOffsetChanged(float)), link, SLOT(setBarometerOffset(float))); + // FIXME: this signal is not on the base hil configuration widget, only on the FG widget + //QObject::connect(configuration, SIGNAL(barometerOffsetChanged(float)), link, SLOT(setBarometerOffset(float))); if (enable) { startHil(); diff --git a/src/uas/UASParameterCommsMgr.cc b/src/uas/UASParameterCommsMgr.cc index e52b9a83c763c924b567e8077b6bcfd73c4bf5c8..627a01f4f99d436ee43e4597f8c927ea2aae0138 100644 --- a/src/uas/UASParameterCommsMgr.cc +++ b/src/uas/UASParameterCommsMgr.cc @@ -19,8 +19,9 @@ UASParameterCommsMgr::UASParameterCommsMgr(QObject *parent) : silenceTimeout(1000), transmissionListMode(false) { - - + // We signal to ourselves to start/stop timer on our own thread + connect(this, SIGNAL(_startSilenceTimer(void)), this, SLOT(_startSilenceTimerOnThisThread(void))); + connect(this, SIGNAL(_stopSilenceTimer(void)), this, SLOT(_stopSilenceTimerOnThisThread(void))); } UASParameterCommsMgr* UASParameterCommsMgr::initWithUAS(UASInterface* uas) @@ -254,7 +255,7 @@ void UASParameterCommsMgr::silenceTimerExpired() qDebug() << "maxSilenceTimeout exceeded: " << totalElapsed; int missingReads, missingWrites; clearRetransmissionLists(missingReads,missingWrites); - silenceTimer.stop(); + emit _stopSilenceTimer(); // Stop timer on our thread; lastReceiveTime = 0; lastSilenceTimerReset = curTime; setParameterStatusMsg(tr("TIMEOUT: Abandoning %1 reads %2 writes after %3 seconds").arg(missingReads).arg(missingWrites).arg(totalElapsed/1000)); @@ -370,13 +371,14 @@ void UASParameterCommsMgr::updateSilenceTimer() if (0 == lastReceiveTime) { lastReceiveTime = lastSilenceTimerReset; } - silenceTimer.start(silenceTimeout); + // We signal this to ourselves so timer is started on the right thread + emit _startSilenceTimer(); } else { //all parameters have been received, broadcast to UI emit parameterListUpToDate(); resetAfterListReceive(); - silenceTimer.stop(); + emit _stopSilenceTimer(); // Stop timer on our thread; lastReceiveTime = 0; } @@ -547,3 +549,12 @@ UASParameterCommsMgr::~UASParameterCommsMgr() } +void UASParameterCommsMgr::_startSilenceTimerOnThisThread(void) +{ + silenceTimer.start(silenceTimeout); +} + +void UASParameterCommsMgr::_stopSilenceTimerOnThisThread(void) +{ + silenceTimer.stop(); +} diff --git a/src/uas/UASParameterCommsMgr.h b/src/uas/UASParameterCommsMgr.h index ef313761547352399e0fb23dce851994df8a25f4..20a24bb12ba8733cee67cb174192fad66e52e599 100644 --- a/src/uas/UASParameterCommsMgr.h +++ b/src/uas/UASParameterCommsMgr.h @@ -68,6 +68,11 @@ signals: /** @brief We updated the parameter status message */ void parameterStatusMsgUpdated(QString msg, int level); + + + /// @brief We signal this to ourselves in order to get timer started/stopped on our own thread. + void _startSilenceTimer(void); + void _stopSilenceTimer(void); public slots: /** @brief Iterate through all components, through all pending parameters and send them to UAS */ @@ -113,7 +118,10 @@ protected: bool transmissionListMode; ///< Currently requesting list QMap* > writesWaiting; ///< All writes that have not yet been ack'd, by component ID - +private slots: + /// @brief We signal this to ourselves in order to get timer started/stopped on our own thread. + void _startSilenceTimerOnThisThread(void); + void _stopSilenceTimerOnThisThread(void); }; diff --git a/src/uas/UASParameterDataModel.cc b/src/uas/UASParameterDataModel.cc index a1997f52e19a6cdf1848e67f01b2d258dd1a618b..2cf7b5bb338718e56f7288fa99546e76f5495a68 100644 --- a/src/uas/UASParameterDataModel.cc +++ b/src/uas/UASParameterDataModel.cc @@ -268,7 +268,7 @@ void UASParameterDataModel::readUpdateParamsFromStream( QTextStream& stream) if (!userWarned && (uasId != lineMavId)) { //TODO warn the user somehow ?? Appears these are saved currently with mav ID 0 but mav ID is often nonzero? QString msg = tr("The parameters in the stream have been saved from system %1, but the currently selected system has the ID %2.").arg(lineMavId).arg(uasId); - qWarning() << msg ; + qDebug() << msg ; //MainWindow::instance()->showCriticalMessage( // tr("Parameter loading warning"), // tr("The parameters from the file %1 have been saved from system %2, but the currently selected system has the ID %3. If this is unintentional, please click on to revert to the parameters that are currently onboard").arg(fileName).arg(wpParams.at(0).toInt()).arg(mav->getUASID())); diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc index 406dedcad8c6f3339b006e5da71631b2f6833c71..5c57745dd890a9b60ad8672d3f7c99c73568c896 100644 --- a/src/uas/UASWaypointManager.cc +++ b/src/uas/UASWaypointManager.cc @@ -61,6 +61,10 @@ UASWaypointManager::UASWaypointManager(UAS* _uas) { uasid = 0; } + + // We signal to ourselves here so that tiemrs are started and stopped on correct thread + connect(this, SIGNAL(_startProtocolTimer(void)), this, SLOT(_startProtocolTimerOnThisThread(void))); + connect(this, SIGNAL(_stopProtocolTimer(void)), this, SLOT(_stopProtocolTimerOnThisThread(void))); } UASWaypointManager::~UASWaypointManager() @@ -133,7 +137,7 @@ void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double l void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, quint16 count) { if (current_state == WP_GETLIST && systemId == current_partner_systemid) { - protocol_timer.start(PROTOCOL_TIMEOUT_MS); + emit _startProtocolTimer(); // Start timer on correct thread current_retries = PROTOCOL_MAX_RETRIES; //Clear the old edit-list before receiving the new one @@ -152,7 +156,7 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui current_state = WP_GETLIST_GETWPS; sendWaypointRequest(current_wp_id); } else { - protocol_timer.stop(); + emit _stopProtocolTimer(); // Stop the time on our thread QTime time = QTime::currentTime(); emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString())); current_state = WP_IDLE; @@ -171,7 +175,7 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_mission_item_t *wp) { if (systemId == current_partner_systemid && current_state == WP_GETLIST_GETWPS && wp->seq == current_wp_id) { - protocol_timer.start(PROTOCOL_TIMEOUT_MS); + emit _startProtocolTimer(); // Start timer on our thread current_retries = PROTOCOL_MAX_RETRIES; if(wp->seq == current_wp_id) { @@ -202,7 +206,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_ current_partner_systemid = 0; current_partner_compid = 0; - protocol_timer.stop(); + emit _stopProtocolTimer(); // Stop timer on our thread emit readGlobalWPFromUAS(false); QTime time = QTime::currentTime(); emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString())); @@ -230,7 +234,7 @@ void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavli if (compId == current_partner_compid || compId == MAV_COMP_ID_ALL) { if((current_state == WP_SENDLIST || current_state == WP_SENDLIST_SENDWPS) && (current_wp_id == waypoint_buffer.count()-1 && wpa->type == 0)) { //all waypoints sent and ack received - protocol_timer.stop(); + emit _stopProtocolTimer(); // Stop timer on our thread current_state = WP_IDLE; readWaypoints(false); //Update "Onboard Waypoints"-tab immediately after the waypoint list has been sent. QTime time = QTime::currentTime(); @@ -269,10 +273,10 @@ void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavli emit updateStatusString(tr("ERROR: Unspecified error")); break; } - protocol_timer.stop(); + emit _stopProtocolTimer(); // Stop timer on our thread current_state = WP_IDLE; } else if(current_state == WP_CLEARLIST) { - protocol_timer.stop(); + emit _stopProtocolTimer(); // Stop timer on our thread current_state = WP_IDLE; QTime time = QTime::currentTime(); emit updateStatusString(tr("Done. (updated at %1)").arg(time.toString())); @@ -283,7 +287,7 @@ void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavli void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, mavlink_mission_request_t *wpr) { if (systemId == current_partner_systemid && ((current_state == WP_SENDLIST && wpr->seq == 0) || (current_state == WP_SENDLIST_SENDWPS && (wpr->seq == current_wp_id || wpr->seq == current_wp_id + 1)))) { - protocol_timer.start(PROTOCOL_TIMEOUT_MS); + emit _startProtocolTimer(); // Start timer on our thread current_retries = PROTOCOL_MAX_RETRIES; if (wpr->seq < waypoint_buffer.count()) { @@ -314,7 +318,7 @@ void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, m if (systemId == uasid) { // FIXME Petri if (current_state == WP_SETCURRENT) { - protocol_timer.stop(); + emit _stopProtocolTimer(); // Stop timer on our thread current_state = WP_IDLE; // update the local main storage @@ -362,7 +366,7 @@ int UASWaypointManager::setCurrentWaypoint(quint16 seq) if(current_state == WP_IDLE) { //send change to UAS - important to note: if the transmission fails, we have inconsistencies - protocol_timer.start(PROTOCOL_TIMEOUT_MS); + emit _startProtocolTimer(); // Start timer on our thread current_retries = PROTOCOL_MAX_RETRIES; current_state = WP_SETCURRENT; @@ -594,7 +598,7 @@ void UASWaypointManager::clearWaypointList() { if (current_state == WP_IDLE) { - protocol_timer.start(PROTOCOL_TIMEOUT_MS); + emit _startProtocolTimer(); // Start timer on our thread current_retries = PROTOCOL_MAX_RETRIES; current_state = WP_CLEARLIST; @@ -847,7 +851,10 @@ void UASWaypointManager::readWaypoints(bool readToEdit) emit waypointEditableListChanged(); } */ - protocol_timer.start(PROTOCOL_TIMEOUT_MS); + + // We are signalling ourselves here so that the timer gets started on the right thread + emit _startProtocolTimer(); + current_retries = PROTOCOL_MAX_RETRIES; current_state = WP_GETLIST; @@ -899,7 +906,7 @@ void UASWaypointManager::writeWaypoints() if (current_state == WP_IDLE) { // Send clear all if count == 0 if (waypointsEditable.count() > 0) { - protocol_timer.start(PROTOCOL_TIMEOUT_MS); + emit _startProtocolTimer(); // Start timer on our thread current_retries = PROTOCOL_MAX_RETRIES; current_count = waypointsEditable.count(); @@ -1128,3 +1135,14 @@ float UASWaypointManager::getHomeAltitudeOffsetDefault() { return defaultAltitudeHomeOffset; } + + +void UASWaypointManager::_startProtocolTimerOnThisThread(void) +{ + protocol_timer.start(PROTOCOL_TIMEOUT_MS); +} + +void UASWaypointManager::_stopProtocolTimerOnThisThread(void) +{ + protocol_timer.stop(); +} diff --git a/src/uas/UASWaypointManager.h b/src/uas/UASWaypointManager.h index 5c4f8e2cd61864ab85dd8cbcc5b89bafda0e6358..15b8b6326bd91b2e62bdd94e8b72b8230e16911d 100644 --- a/src/uas/UASWaypointManager.h +++ b/src/uas/UASWaypointManager.h @@ -160,6 +160,13 @@ signals: void loadWPFile(); ///< emits signal that a file wp has been load void readGlobalWPFromUAS(bool value); ///< emits signal when finish to read Global WP from UAS + + void _startProtocolTimer(void); ///< emits signal to start protocol timer + void _stopProtocolTimer(void); ///< emits signal to stop protocol timer + +private slots: + void _startProtocolTimerOnThisThread(void); ///< Starts the protocol timer + void _stopProtocolTimerOnThisThread(void); ///< Starts the protocol timer private: UAS* uas; ///< Reference to the corresponding UAS diff --git a/src/ui/QGCPX4VehicleConfig.cc b/src/ui/QGCPX4VehicleConfig.cc index b63b0c5248189ed1870703a0032613f4bc92ebc6..3ee0c175b9d9380bc46a559a57fbe57aada6dc07 100644 --- a/src/ui/QGCPX4VehicleConfig.cc +++ b/src/ui/QGCPX4VehicleConfig.cc @@ -204,12 +204,12 @@ void QGCPX4VehicleConfig::loadQgcConfig(bool primary) if (!autopilotdir.exists("general")) { //TODO: Throw some kind of error here. There is no general configuration directory - qWarning() << "Invalid general dir. no general configuration will be loaded."; + qDebug() << "Invalid general dir. no general configuration will be loaded."; } if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower())) { //TODO: Throw an error here too, no autopilot specific configuration - qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded."; + qDebug() << "Invalid vehicle dir, no vehicle specific configuration will be loaded."; } // Generate widgets for the General tab. @@ -380,23 +380,10 @@ void QGCPX4VehicleConfig::loadConfig() QGCToolWidget* tool; QDir autopilotdir(qApp->applicationDirPath() + "/files/" + mav->getAutopilotTypeName().toLower()); - QDir generaldir = QDir(autopilotdir.absolutePath() + "/general/widgets"); - QDir vehicledir = QDir(autopilotdir.absolutePath() + "/" + mav->getSystemTypeName().toLower() + "/widgets"); - if (!autopilotdir.exists("general")) - { - //TODO: Throw some kind of error here. There is no general configuration directory - qWarning() << "Invalid general dir. no general configuration will be loaded."; - } - if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower())) - { - //TODO: Throw an error here too, no autopilot specific configuration - qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded."; - } qDebug() << autopilotdir.absolutePath(); - qDebug() << generaldir.absolutePath(); - qDebug() << vehicledir.absolutePath(); + QFile xmlfile(autopilotdir.absolutePath() + "/arduplane.pdef.xml"); - if (xmlfile.exists() && !xmlfile.open(QIODevice::ReadOnly)) + if (!xmlfile.open(QIODevice::ReadOnly)) { loadQgcConfig(false); doneLoadingConfig = true; diff --git a/src/ui/QGCVehicleConfig.cc b/src/ui/QGCVehicleConfig.cc index 06121d1d5a43d09bfd60e9bbe27bbc5dbce86739..49881752a5779f2ad5e825fc0dcc553a6caa39dc 100644 --- a/src/ui/QGCVehicleConfig.cc +++ b/src/ui/QGCVehicleConfig.cc @@ -251,12 +251,12 @@ void QGCVehicleConfig::loadQgcConfig(bool primary) if (!autopilotdir.exists("general")) { //TODO: Throw some kind of error here. There is no general configuration directory - qWarning() << "Invalid general dir. no general configuration will be loaded."; + qDebug() << "Invalid general dir. no general configuration will be loaded."; } if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower())) { //TODO: Throw an error here too, no autopilot specific configuration - qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded."; + qDebug() << "Invalid vehicle dir, no vehicle specific configuration will be loaded."; } // Generate widgets for the General tab. @@ -475,12 +475,12 @@ void QGCVehicleConfig::loadConfig() if (!autopilotdir.exists("general")) { //TODO: Throw some kind of error here. There is no general configuration directory - qWarning() << "Invalid general dir. no general configuration will be loaded."; + qDebug() << "Invalid general dir. no general configuration will be loaded."; } if (!autopilotdir.exists(mav->getAutopilotTypeName().toLower())) { //TODO: Throw an error here too, no autopilot specific configuration - qWarning() << "Invalid vehicle dir, no vehicle specific configuration will be loaded."; + qDebug() << "Invalid vehicle dir, no vehicle specific configuration will be loaded."; } qDebug() << autopilotdir.absolutePath(); qDebug() << generaldir.absolutePath(); diff --git a/src/ui/designer/QGCParamSlider.cc b/src/ui/designer/QGCParamSlider.cc index 9750fe4cad37cc62572998d45d36c1514c999e4f..502166bfcbb1f312cc9f015ae363e84d419c7d72 100644 --- a/src/ui/designer/QGCParamSlider.cc +++ b/src/ui/designer/QGCParamSlider.cc @@ -269,7 +269,7 @@ void QGCParamSlider::setParamPending() uas->getParamManager()->sendPendingParameters(true, true); } else { - qWarning() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING"; + qDebug() << __FILE__ << __LINE__ << "NO UAS SET, DOING NOTHING"; } } diff --git a/src/ui/map3D/Pixhawk3DWidget.cc b/src/ui/map3D/Pixhawk3DWidget.cc index 543834c900dbb40d88ef58b38a6d17e357915b32..474b445be1e5440c2ae70e7048474664fc57e37b 100644 --- a/src/ui/map3D/Pixhawk3DWidget.cc +++ b/src/ui/map3D/Pixhawk3DWidget.cc @@ -66,7 +66,7 @@ Pixhawk3DWidget::Pixhawk3DWidget(QWidget* parent) , mViewParamWidget(new ViewParamWidget(mGlobalViewParams, mSystemViewParamMap, this, parent)) { connect(m3DWidget, SIGNAL(sizeChanged(int,int)), this, SLOT(sizeChanged(int,int))); - connect(m3DWidget, SIGNAL(update()), this, SLOT(update())); + connect(m3DWidget, SIGNAL(updateWidget()), this, SLOT(updateWidget())); m3DWidget->setCameraParams(2.0f, 30.0f, 0.01f, 10000.0f); m3DWidget->init(15.0f); @@ -1078,7 +1078,7 @@ Pixhawk3DWidget::sizeChanged(int width, int height) } void -Pixhawk3DWidget::update(void) +Pixhawk3DWidget::updateWidget(void) { MAV_FRAME frame = mGlobalViewParams->frame(); diff --git a/src/ui/map3D/Pixhawk3DWidget.h b/src/ui/map3D/Pixhawk3DWidget.h index 3dbc64992fd41c1e4d8d22cbcd2841f47626eb3f..913875f7c1847dab2bb7e6f7380620c4e7b42282 100644 --- a/src/ui/map3D/Pixhawk3DWidget.h +++ b/src/ui/map3D/Pixhawk3DWidget.h @@ -97,7 +97,7 @@ private slots: void rotateTerrain(void); void sizeChanged(int width, int height); - void update(void); + void updateWidget(void); protected: void addModels(QVector< osg::ref_ptr >& models, diff --git a/src/ui/map3D/Q3DWidget.h b/src/ui/map3D/Q3DWidget.h index 037de8aa9b01916fe5bb3cdd10510602d25e3c43..245559e11bf880628572fb6ff729a72933cc4b8d 100644 --- a/src/ui/map3D/Q3DWidget.h +++ b/src/ui/map3D/Q3DWidget.h @@ -176,7 +176,7 @@ protected slots: signals: void sizeChanged(int width, int height); - void update(void); + void updateWidget(void); protected: /** diff --git a/src/ui/px4_configuration/QGCPX4SensorCalibration.cc b/src/ui/px4_configuration/QGCPX4SensorCalibration.cc index a17174f39540cb46913101c3f28002ab4d0d141b..770f01c5de64d8f9295839ff5936d4882e8bb0d9 100644 --- a/src/ui/px4_configuration/QGCPX4SensorCalibration.cc +++ b/src/ui/px4_configuration/QGCPX4SensorCalibration.cc @@ -280,22 +280,26 @@ void QGCPX4SensorCalibration::setGpsOrientation(int index) void QGCPX4SensorCalibration::setAutopilotImage(const QString &path) { - autopilotIcon.load(path); + if (autopilotIcon.load(path)) { + int w = ui->autopilotLabel->width(); + int h = ui->autopilotLabel->height(); - int w = ui->autopilotLabel->width(); - int h = ui->autopilotLabel->height(); - - ui->autopilotLabel->setPixmap(autopilotIcon.scaled(w, h, Qt::KeepAspectRatio, Qt::SmoothTransformation)); + ui->autopilotLabel->setPixmap(autopilotIcon.scaled(w, h, Qt::KeepAspectRatio, Qt::SmoothTransformation)); + } else { + qDebug() << "AutoPilot Icon image did not load" << path; + } } void QGCPX4SensorCalibration::setGpsImage(const QString &path) { - gpsIcon.load(path); + if (gpsIcon.load(path)) { + int w = ui->gpsLabel->width(); + int h = ui->gpsLabel->height(); - int w = ui->gpsLabel->width(); - int h = ui->gpsLabel->height(); - - ui->gpsLabel->setPixmap(gpsIcon.scaled(w, h, Qt::KeepAspectRatio, Qt::SmoothTransformation)); + ui->gpsLabel->setPixmap(gpsIcon.scaled(w, h, Qt::KeepAspectRatio, Qt::SmoothTransformation)); + } else { + qDebug() << "GPS Icon image did not load" << path; + } } void QGCPX4SensorCalibration::updateIcons()