diff --git a/doc/Doxyfile b/doc/Doxyfile index 28d0c331eedafb0378f760f7995c60d68a969f81..0d28fe85ac9a56c216cec104b6f0aac988ff7b97 100644 --- a/doc/Doxyfile +++ b/doc/Doxyfile @@ -515,7 +515,7 @@ LAYOUT_FILE = # The QUIET tag can be used to turn on/off the messages that are generated # by doxygen. Possible values are YES and NO. If left blank NO is used. -QUIET = YES +QUIET = NO # The WARNINGS tag can be used to turn on/off the warning messages that are # generated by doxygen. Possible values are YES and NO. If left blank @@ -599,7 +599,8 @@ RECURSIVE = YES # subdirectory from a directory tree whose root is specified with the INPUT tag. EXCLUDE = ../src/lib/ \ - lib/ + lib/ \ + ../src/libs/ # The EXCLUDE_SYMLINKS tag can be used select whether or not files or # directories that are symbolic links (a Unix filesystem feature) are excluded @@ -985,7 +986,7 @@ SEARCHENGINE = YES # If the GENERATE_LATEX tag is set to YES (the default) Doxygen will # generate Latex output. -GENERATE_LATEX = YES +GENERATE_LATEX = NO # The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. # If a relative path is entered the value of OUTPUT_DIRECTORY will be @@ -1033,13 +1034,13 @@ LATEX_HEADER = # contain links (just like the HTML output) instead of page references # This makes the output suitable for online browsing using a pdf viewer. -PDF_HYPERLINKS = YES +PDF_HYPERLINKS = NO # If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of # plain latex in the generated Makefile. Set this option to YES to get a # higher quality PDF documentation. -USE_PDFLATEX = YES +USE_PDFLATEX = NO # If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\batchmode. # command to the generated LaTeX files. This will instruct LaTeX to keep diff --git a/src/QGC.cc b/src/QGC.cc index 179d54f5905c1c1c06006a2a68f31fc01bba2f90..c30209f83b0ceb8ea992d4d465dd9f385838f53c 100644 --- a/src/QGC.cc +++ b/src/QGC.cc @@ -64,7 +64,7 @@ float limitAngleToPMPIf(float angle) else { // Approximate - angle = fmodf(angle, M_PI); + angle = fmodf(angle, (float) M_PI); } return angle; diff --git a/src/QGC.h b/src/QGC.h index 9a1b442d176de3bc7818d086c4cc2f8fa705880f..7f17bd143cb4ef2a6641e6120d56f3aec214252e 100644 --- a/src/QGC.h +++ b/src/QGC.h @@ -47,7 +47,7 @@ inline bool isnan(T value) template inline bool isinf(T value) { - return std::numeric_limits::has_infinity && (value == std::numeric_limits::infinity() || (-1*value) == std::numeric_limits::infinity()); + return (value == std::numeric_limits::infinity() || (-1*value) == std::numeric_limits::infinity()) && std::numeric_limits::has_infinity; } #else #include diff --git a/src/comm/MAVLinkSimulationMAV.cc b/src/comm/MAVLinkSimulationMAV.cc index 519924400295bc10ae00d3200cb5aaeec0beca83..948fcecbd4cdf5cc7889159e41c223b2cfc8fafe 100644 --- a/src/comm/MAVLinkSimulationMAV.cc +++ b/src/comm/MAVLinkSimulationMAV.cc @@ -221,10 +221,10 @@ void MAVLinkSimulationMAV::mainloop() if (sys_mode & MAV_MODE_FLAG_DECODE_POSITION_HIL) { mavlink_hil_controls_t hil; - hil.roll_ailerons = 0.0; - hil.pitch_elevator = 0.05; - hil.yaw_rudder = 0.05; - hil.throttle = 0.6; + hil.roll_ailerons = 0.0f; + hil.pitch_elevator = 0.05f; + hil.yaw_rudder = 0.05f; + hil.throttle = 0.6f; // Encode the data (adding header and checksums, etc.) mavlink_msg_hil_controls_encode(systemid, MAV_COMP_ID_IMU, &ret, &hil); // And send it diff --git a/src/input/JoystickInput.cc b/src/input/JoystickInput.cc index 805f9a5d6534c3ffd4ee0575ca45ce20d0f84f17..01d6e4fab00ff7e72fec3b06639de5f3bb761a1f 100644 --- a/src/input/JoystickInput.cc +++ b/src/input/JoystickInput.cc @@ -37,6 +37,7 @@ This file is part of the PIXHAWK project #include "UAS.h" #include "UASManager.h" #include "QGC.h" +#include /** * The coordinate frame of the joystick axis is the aeronautical frame like shown on this image: @@ -49,10 +50,10 @@ JoystickInput::JoystickInput() : uas(NULL), uasButtonList(QList()), done(false), - thrustAxis(3), - xAxis(1), - yAxis(0), - yawAxis(2), + thrustAxis(2), + xAxis(0), + yAxis(1), + yawAxis(3), joystickName(tr("Unitinialized")) { for (int i = 0; i < 10; i++) { @@ -66,6 +67,17 @@ JoystickInput::JoystickInput() : //start(); } +JoystickInput::~JoystickInput() +{ + { + QMutexLocker locker(&this->m_doneMutex); + done = true; + } + this->wait(); + this->deleteLater(); +} + + void JoystickInput::setActiveUAS(UASInterface* uas) { // Only connect / disconnect is the UAS is of a controllable UAS class @@ -134,7 +146,16 @@ void JoystickInput::run() init(); - while(!done) { + forever + { + { + QMutexLocker locker(&this->m_doneMutex); + if(done) + { + done = false; + break; + } + } while(SDL_PollEvent(&event)) { SDL_JoystickUpdate(); diff --git a/src/input/JoystickInput.h b/src/input/JoystickInput.h index ad08c123a7ecda059e1ef583019d739b8f160989..f8b369e49cd3ffaba0d53d6ec5c9dfae8f5a6f42 100644 --- a/src/input/JoystickInput.h +++ b/src/input/JoystickInput.h @@ -35,6 +35,7 @@ This file is part of the PIXHAWK project #include #include +#include #include #include "UASInterface.h" @@ -48,6 +49,7 @@ class JoystickInput : public QThread public: JoystickInput(); + ~JoystickInput(); void run(); const QString& getName(); @@ -63,6 +65,7 @@ protected: UASInterface* uas; QList uasButtonList; bool done; + QMutex m_doneMutex; // Axis 3 is thrust (CALIBRATION!) int thrustAxis; diff --git a/src/libs/utils/utils_external.pri b/src/libs/utils/utils_external.pri index 621e0ca9d20e9e68145b3b46a53af80c589f2fb4..dd78de62f1b4f6f534e42e1a96424426bfd72205 100644 --- a/src/libs/utils/utils_external.pri +++ b/src/libs/utils/utils_external.pri @@ -77,7 +77,7 @@ macx { SOURCES += consoleprocess_unix.cpp } -linux-g++ { +linux-g++|linux-g++-64 { SOURCES += consoleprocess_unix.cpp } diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index c0c6e690c0ea13873953f47a941a49871e89d520..7c8aa430c37feb121c48b19bc687dac1de4be34d 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -767,6 +767,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) imagePayload = p.payload; imageQuality = p.jpg_quality; imageType = p.type; + imageWidth = p.width; + imageHeight = p.height; imageStart = QGC::groundTimeMilliseconds(); } break; @@ -1392,16 +1394,13 @@ QImage UAS::getImage() // RAW greyscale if (imageType == MAVLINK_DATA_STREAM_IMG_RAW8U) { - // TODO FIXME Fabian - // RAW hardcoded to 22x22 - int imgWidth = 22; - int imgHeight = 22; - int imgColors = 255; + // TODO FIXME + int imgColors = 255;//imageSize/(imageWidth*imageHeight); //const int headerSize = 15; // Construct PGM header QString header("P5\n%1 %2\n%3\n"); - header = header.arg(imgWidth).arg(imgHeight).arg(imgColors); + header = header.arg(imageWidth).arg(imageHeight).arg(imgColors); QByteArray tmpImage(header.toStdString().c_str(), header.toStdString().size()); tmpImage.append(imageRecBuffer); @@ -1451,7 +1450,7 @@ void UAS::requestImage() if (imagePacketsArrived == 0) { mavlink_message_t msg; - mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 50); + mavlink_msg_data_transmission_handshake_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, DATA_TYPE_JPEG_IMAGE, 0, 0, 0, 0, 0, 50); sendMessage(msg); } #endif diff --git a/src/uas/UAS.h b/src/uas/UAS.h index 1e89ed1d4082d6c3c76409a3282f706e7ab28af9..093122db15a3754f54f54ab965c46111cb69a40f 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -214,6 +214,8 @@ protected: //COMMENTS FOR TEST UNIT int imagePayload; ///< Payload size per transmitted packet (bytes). Standard is 254, and decreases when image resolution increases. int imageQuality; ///< Quality of the transmitted image (percentage) int imageType; ///< Type of the transmitted image (BMP, PNG, JPEG, RAW 8 bit, RAW 32 bit) + int imageWidth; ///< Width of the image stream + int imageHeight; ///< Width of the image stream QByteArray imageRecBuffer; ///< Buffer for the incoming bytestream QImage image; ///< Image data of last completely transmitted image quint64 imageStart; diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc index f4c308a6d07ee8272e458b64711b64c9496ea910..5e87809341a22e6c5e38bf20303904e7c07c2a97 100644 --- a/src/uas/UASWaypointManager.cc +++ b/src/uas/UASWaypointManager.cc @@ -114,6 +114,9 @@ void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double l { Q_UNUSED(mav); Q_UNUSED(time); + Q_UNUSED(alt); + Q_UNUSED(lon); + Q_UNUSED(lat); if (waypointsEditable.count() > 0 && currentWaypointEditable && (currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL || currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT)) { // TODO FIXME Calculate distance @@ -240,6 +243,7 @@ void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, m void UASWaypointManager::handleWaypointReached(quint8 systemId, quint8 compId, mavlink_mission_item_reached_t *wpr) { + Q_UNUSED(compId); if (!uas) return; if (systemId == uasid) { emit updateStatusString(QString("Reached waypoint %1").arg(wpr->seq)); diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc index 296e25d3e08e16c7335a5fc65bf7f1bfd0d1f3f2..0e260bf1af20886478237cad56b3ae7cfa1641a4 100644 --- a/src/ui/HSIDisplay.cc +++ b/src/ui/HSIDisplay.cc @@ -486,6 +486,11 @@ void HSIDisplay::updatePositionZControllerEnabled(bool enabled) void HSIDisplay::updateObjectPosition(unsigned int time, int id, int type, const QString& name, int quality, float bearing, float distance) { + Q_UNUSED(quality); + Q_UNUSED(name); + Q_UNUSED(type); + Q_UNUSED(id); + Q_UNUSED(time); // FIXME add multi-object support QPainter painter(this); QColor color(Qt::yellow); diff --git a/src/ui/QGCMAVLinkInspector.cc b/src/ui/QGCMAVLinkInspector.cc index 691f8bcceb8ca92dbbbfb64ba3e3b5bfb46317a3..d4c353c3b01d0bbd542d44fd12fc7906d4f76166 100644 --- a/src/ui/QGCMAVLinkInspector.cc +++ b/src/ui/QGCMAVLinkInspector.cc @@ -6,6 +6,9 @@ #include +const float QGCMAVLinkInspector::updateHzLowpass = 0.2f; +const unsigned int QGCMAVLinkInspector::updateInterval = 1000U; + QGCMAVLinkInspector::QGCMAVLinkInspector(MAVLinkProtocol* protocol, QWidget *parent) : QWidget(parent), ui(new Ui::QGCMAVLinkInspector) diff --git a/src/ui/QGCMAVLinkInspector.h b/src/ui/QGCMAVLinkInspector.h index f4751dd659a300fdc3c026bdf6c18cd0b947ab2f..4623b2436d273f2f059c4163fe2b85c1e3ac16ee 100644 --- a/src/ui/QGCMAVLinkInspector.h +++ b/src/ui/QGCMAVLinkInspector.h @@ -37,8 +37,8 @@ protected: // Update one message field void updateField(int msgid, int fieldid, QTreeWidgetItem* item); - static const unsigned int updateInterval = 1000; - static const float updateHzLowpass = 0.2f; + static const unsigned int updateInterval; + static const float updateHzLowpass; private: Ui::QGCMAVLinkInspector *ui; diff --git a/src/ui/QGCRGBDView.cc b/src/ui/QGCRGBDView.cc index de45d8065374e7e9ffc0267024b9cfb490a49405..ded4a4edac8b2a3808e8d99f0d8e364d36232f8b 100644 --- a/src/ui/QGCRGBDView.cc +++ b/src/ui/QGCRGBDView.cc @@ -265,5 +265,7 @@ void QGCRGBDView::updateData(UASInterface *uas) } glImage = QGLWidget::convertToGLFormat(fill); +#else + Q_UNUSED(uas); #endif } diff --git a/src/ui/WaypointEditableView.cc b/src/ui/WaypointEditableView.cc index ce4731792041e8b011364355132a39abd7ab9fa6..73fdfb0d7fbfc0bb300c28cd589439ff56e8642f 100644 --- a/src/ui/WaypointEditableView.cc +++ b/src/ui/WaypointEditableView.cc @@ -310,9 +310,7 @@ void WaypointEditableView::changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE mode) } void WaypointEditableView::updateFrameView(int frame) -{ - std::cerr << "update frame view: "<< frame << std::endl; - //int custom_index = m_ui->comboBox_action->findData(MAV_CMD_ENUM_END); +{ switch(frame) { case MAV_FRAME_GLOBAL: case MAV_FRAME_GLOBAL_RELATIVE_ALT: diff --git a/src/ui/WaypointEditableView.ui b/src/ui/WaypointEditableView.ui index 13e1093377487b6ae8d7b3d0fc7df7f690a335f0..5ba5bb569893624c285890fe2cf068fb09779e36 100644 --- a/src/ui/WaypointEditableView.ui +++ b/src/ui/WaypointEditableView.ui @@ -105,6 +105,18 @@ QPushButton:pressed { + + + 0 + 0 + + + + + 25 + 0 + + Qt::TabFocus @@ -127,9 +139,15 @@ QPushButton:pressed { + + + 0 + 0 + + - 15 + 25 0 @@ -471,6 +489,12 @@ QPushButton:pressed { + + + 0 + 0 + + Uncertainty radius in meters where to accept this waypoint as reached @@ -488,6 +512,12 @@ where to accept this waypoint as reached + + + 0 + 0 + + Rotaty wing and ground vehicles only: Time to stay at this position before advancing @@ -505,6 +535,12 @@ Time to stay at this position before advancing + + + 0 + 0 + + Number of turns to loiter @@ -581,6 +617,12 @@ Time to stay at this position before advancing + + + 0 + 0 + + Automatically continue after this waypoint diff --git a/src/ui/WaypointViewOnlyView.ui b/src/ui/WaypointViewOnlyView.ui index 93c0726cff2eae91b7a8329a27b7f9e425189f66..76ef552aa2a153d0f909fe85852b54a20f409197 100644 --- a/src/ui/WaypointViewOnlyView.ui +++ b/src/ui/WaypointViewOnlyView.ui @@ -75,7 +75,7 @@ margin-top: 1ex; /* leave space at the top for the title */ false - + 2 @@ -85,11 +85,17 @@ margin-top: 1ex; /* leave space at the top for the title */ - + 0 0 + + + 25 + 0 + + Currently executed waypoint @@ -103,9 +109,27 @@ margin-top: 1ex; /* leave space at the top for the title */ + + + 0 + 0 + + + + + 25 + 0 + + + + 1 + ID + + Qt::AlignCenter + @@ -160,6 +184,9 @@ margin-top: 1ex; /* leave space at the top for the title */ Frame + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + diff --git a/src/ui/map/QGCMapWidget.cc b/src/ui/map/QGCMapWidget.cc index ed1b371c1f3093e301274e64d7cce05ba22021f4..2c5a7aa3e7e3034170388080c187bebc11b79f97 100644 --- a/src/ui/map/QGCMapWidget.cc +++ b/src/ui/map/QGCMapWidget.cc @@ -10,7 +10,7 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) : mapcontrol::OPMapWidget(parent), currWPManager(NULL), firingWaypointChange(NULL), - maxUpdateInterval(2.1), // 2 seconds + maxUpdateInterval(2.1f), // 2 seconds followUAVEnabled(false), trailType(mapcontrol::UAVTrailType::ByTimeElapsed), trailInterval(2.0f), diff --git a/src/ui/uas/UASControlWidget.cc b/src/ui/uas/UASControlWidget.cc index 5c13e52225e190ed1cb9f15ff2cf1200cb66e445..06161d291ed938099d5b4b84a445f9228e021a96 100644 --- a/src/ui/uas/UASControlWidget.cc +++ b/src/ui/uas/UASControlWidget.cc @@ -44,6 +44,7 @@ This file is part of the PIXHAWK project UASControlWidget::UASControlWidget(QWidget *parent) : QWidget(parent), uas(0), + uasMode(0), engineOn(false) { ui.setupUi(this); @@ -59,6 +60,8 @@ UASControlWidget::UASControlWidget(QWidget *parent) : QWidget(parent), connect(ui.modeComboBox, SIGNAL(activated(int)), this, SLOT(setMode(int))); connect(ui.setModeButton, SIGNAL(clicked()), this, SLOT(transmitMode())); + uasMode = ui.modeComboBox->itemData(ui.modeComboBox->currentIndex()).toInt(); + ui.modeComboBox->setCurrentIndex(0); ui.gridLayout->setAlignment(Qt::AlignTop); @@ -67,7 +70,8 @@ UASControlWidget::UASControlWidget(QWidget *parent) : QWidget(parent), void UASControlWidget::setUAS(UASInterface* uas) { - if (this->uas != 0) { + if (this->uas != 0) + { UASInterface* oldUAS = UASManager::instance()->getUASForId(this->uas); disconnect(ui.controlButton, SIGNAL(clicked()), oldUAS, SLOT(armSystem())); disconnect(ui.liftoffButton, SIGNAL(clicked()), oldUAS, SLOT(launch())); @@ -101,9 +105,12 @@ UASControlWidget::~UASControlWidget() void UASControlWidget::updateStatemachine() { - if (engineOn) { + if (engineOn) + { ui.controlButton->setText(tr("DISARM SYSTEM")); - } else { + } + else + { ui.controlButton->setText(tr("ARM SYSTEM")); } } @@ -139,7 +146,8 @@ void UASControlWidget::updateMode(int uas,QString mode,QString description) void UASControlWidget::updateState(int state) { - switch (state) { + switch (state) + { case (int)MAV_STATE_ACTIVE: engineOn = true; ui.controlButton->setText(tr("DISARM SYSTEM")); diff --git a/src/ui/uas/UASListWidget.cc b/src/ui/uas/UASListWidget.cc index faa136d3b0db284afd126956af5b3adb1257ef19..33bac7a584256d421e518c739cdde638db1d80f1 100644 --- a/src/ui/uas/UASListWidget.cc +++ b/src/ui/uas/UASListWidget.cc @@ -114,6 +114,7 @@ void UASListWidget::activeUAS(UASInterface* uas) void UASListWidget::removeUAS(UASInterface* uas) { + Q_UNUSED(uas); // uasViews.remove(uas); // listLayout->removeWidget(uasViews.value(uas)); // uasViews.value(uas)->deleteLater();