Browse Source

Merged with v10release. Some more GUI improvements.

QGC4.4
pixhawk 13 years ago
parent
commit
6187d71c84
  1. 11
      doc/Doxyfile
  2. 2
      src/QGC.cc
  3. 2
      src/QGC.h
  4. 8
      src/comm/MAVLinkSimulationMAV.cc
  5. 31
      src/input/JoystickInput.cc
  6. 3
      src/input/JoystickInput.h
  7. 2
      src/libs/utils/utils_external.pri
  8. 13
      src/uas/UAS.cc
  9. 2
      src/uas/UAS.h
  10. 4
      src/uas/UASWaypointManager.cc
  11. 5
      src/ui/HSIDisplay.cc
  12. 3
      src/ui/QGCMAVLinkInspector.cc
  13. 4
      src/ui/QGCMAVLinkInspector.h
  14. 2
      src/ui/QGCRGBDView.cc
  15. 4
      src/ui/WaypointEditableView.cc
  16. 44
      src/ui/WaypointEditableView.ui
  17. 31
      src/ui/WaypointViewOnlyView.ui
  18. 2
      src/ui/map/QGCMapWidget.cc
  19. 16
      src/ui/uas/UASControlWidget.cc
  20. 1
      src/ui/uas/UASListWidget.cc

11
doc/Doxyfile

@ -515,7 +515,7 @@ LAYOUT_FILE = @@ -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 @@ -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 @@ -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 = @@ -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

2
src/QGC.cc

@ -64,7 +64,7 @@ float limitAngleToPMPIf(float angle) @@ -64,7 +64,7 @@ float limitAngleToPMPIf(float angle)
else
{
// Approximate
angle = fmodf(angle, M_PI);
angle = fmodf(angle, (float) M_PI);
}
return angle;

2
src/QGC.h

@ -47,7 +47,7 @@ inline bool isnan(T value) @@ -47,7 +47,7 @@ inline bool isnan(T value)
template<typename T>
inline bool isinf(T value)
{
return std::numeric_limits<T>::has_infinity && (value == std::numeric_limits<T>::infinity() || (-1*value) == std::numeric_limits<T>::infinity());
return (value == std::numeric_limits<T>::infinity() || (-1*value) == std::numeric_limits<T>::infinity()) && std::numeric_limits<T>::has_infinity;
}
#else
#include <cmath>

8
src/comm/MAVLinkSimulationMAV.cc

@ -221,10 +221,10 @@ void MAVLinkSimulationMAV::mainloop() @@ -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

31
src/input/JoystickInput.cc

@ -37,6 +37,7 @@ This file is part of the PIXHAWK project @@ -37,6 +37,7 @@ This file is part of the PIXHAWK project
#include "UAS.h"
#include "UASManager.h"
#include "QGC.h"
#include <QMutexLocker>
/**
* The coordinate frame of the joystick axis is the aeronautical frame like shown on this image:
@ -49,10 +50,10 @@ JoystickInput::JoystickInput() : @@ -49,10 +50,10 @@ JoystickInput::JoystickInput() :
uas(NULL),
uasButtonList(QList<int>()),
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() : @@ -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() @@ -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();

3
src/input/JoystickInput.h

@ -35,6 +35,7 @@ This file is part of the PIXHAWK project @@ -35,6 +35,7 @@ This file is part of the PIXHAWK project
#include <QThread>
#include <QList>
#include <qmutex.h>
#include <SDL/SDL.h>
#include "UASInterface.h"
@ -48,6 +49,7 @@ class JoystickInput : public QThread @@ -48,6 +49,7 @@ class JoystickInput : public QThread
public:
JoystickInput();
~JoystickInput();
void run();
const QString& getName();
@ -63,6 +65,7 @@ protected: @@ -63,6 +65,7 @@ protected:
UASInterface* uas;
QList<int> uasButtonList;
bool done;
QMutex m_doneMutex;
// Axis 3 is thrust (CALIBRATION!)
int thrustAxis;

2
src/libs/utils/utils_external.pri

@ -77,7 +77,7 @@ macx { @@ -77,7 +77,7 @@ macx {
SOURCES += consoleprocess_unix.cpp
}
linux-g++ {
linux-g++|linux-g++-64 {
SOURCES += consoleprocess_unix.cpp
}

13
src/uas/UAS.cc

@ -767,6 +767,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) @@ -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() @@ -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() @@ -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

2
src/uas/UAS.h

@ -214,6 +214,8 @@ protected: //COMMENTS FOR TEST UNIT @@ -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;

4
src/uas/UASWaypointManager.cc

@ -114,6 +114,9 @@ void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double l @@ -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 @@ -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));

5
src/ui/HSIDisplay.cc

@ -486,6 +486,11 @@ void HSIDisplay::updatePositionZControllerEnabled(bool enabled) @@ -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);

3
src/ui/QGCMAVLinkInspector.cc

@ -6,6 +6,9 @@ @@ -6,6 +6,9 @@
#include <QDebug>
const float QGCMAVLinkInspector::updateHzLowpass = 0.2f;
const unsigned int QGCMAVLinkInspector::updateInterval = 1000U;
QGCMAVLinkInspector::QGCMAVLinkInspector(MAVLinkProtocol* protocol, QWidget *parent) :
QWidget(parent),
ui(new Ui::QGCMAVLinkInspector)

4
src/ui/QGCMAVLinkInspector.h

@ -37,8 +37,8 @@ protected: @@ -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;

2
src/ui/QGCRGBDView.cc

@ -265,5 +265,7 @@ void QGCRGBDView::updateData(UASInterface *uas) @@ -265,5 +265,7 @@ void QGCRGBDView::updateData(UASInterface *uas)
}
glImage = QGLWidget::convertToGLFormat(fill);
#else
Q_UNUSED(uas);
#endif
}

4
src/ui/WaypointEditableView.cc

@ -310,9 +310,7 @@ void WaypointEditableView::changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE mode) @@ -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:

44
src/ui/WaypointEditableView.ui

@ -105,6 +105,18 @@ QPushButton:pressed { @@ -105,6 +105,18 @@ QPushButton:pressed {
</property>
<item>
<widget class="QCheckBox" name="selectedBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>25</width>
<height>0</height>
</size>
</property>
<property name="focusPolicy">
<enum>Qt::TabFocus</enum>
</property>
@ -127,9 +139,15 @@ QPushButton:pressed { @@ -127,9 +139,15 @@ QPushButton:pressed {
</item>
<item>
<widget class="QLabel" name="idLabel">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>15</width>
<width>25</width>
<height>0</height>
</size>
</property>
@ -471,6 +489,12 @@ QPushButton:pressed { @@ -471,6 +489,12 @@ QPushButton:pressed {
</item>
<item>
<widget class="QDoubleSpinBox" name="acceptanceSpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Uncertainty radius in meters
where to accept this waypoint as reached</string>
@ -488,6 +512,12 @@ where to accept this waypoint as reached</string> @@ -488,6 +512,12 @@ where to accept this waypoint as reached</string>
</item>
<item>
<widget class="QDoubleSpinBox" name="holdTimeSpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Rotaty wing and ground vehicles only:
Time to stay at this position before advancing</string>
@ -505,6 +535,12 @@ Time to stay at this position before advancing</string> @@ -505,6 +535,12 @@ Time to stay at this position before advancing</string>
</item>
<item>
<widget class="QSpinBox" name="turnsSpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Number of turns to loiter</string>
</property>
@ -581,6 +617,12 @@ Time to stay at this position before advancing</string> @@ -581,6 +617,12 @@ Time to stay at this position before advancing</string>
</item>
<item>
<widget class="QCheckBox" name="autoContinue">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Automatically continue after this waypoint</string>
</property>

31
src/ui/WaypointViewOnlyView.ui

@ -75,7 +75,7 @@ margin-top: 1ex; /* leave space at the top for the title */ @@ -75,7 +75,7 @@ margin-top: 1ex; /* leave space at the top for the title */
<property name="checkable">
<bool>false</bool>
</property>
<layout class="QHBoxLayout" name="horizontalLayout" stretch="3,2,100,10,5,1">
<layout class="QHBoxLayout" name="horizontalLayout" stretch="0,2,100,10,5,1">
<property name="spacing">
<number>2</number>
</property>
@ -85,11 +85,17 @@ margin-top: 1ex; /* leave space at the top for the title */ @@ -85,11 +85,17 @@ margin-top: 1ex; /* leave space at the top for the title */
<item>
<widget class="QCheckBox" name="current">
<property name="sizePolicy">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>25</width>
<height>0</height>
</size>
</property>
<property name="toolTip">
<string>Currently executed waypoint</string>
</property>
@ -103,9 +109,27 @@ margin-top: 1ex; /* leave space at the top for the title */ @@ -103,9 +109,27 @@ margin-top: 1ex; /* leave space at the top for the title */
</item>
<item>
<widget class="QLabel" name="idLabel">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>25</width>
<height>0</height>
</size>
</property>
<property name="lineWidth">
<number>1</number>
</property>
<property name="text">
<string>ID</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
<item>
@ -160,6 +184,9 @@ margin-top: 1ex; /* leave space at the top for the title */ @@ -160,6 +184,9 @@ margin-top: 1ex; /* leave space at the top for the title */
<property name="text">
<string>Frame</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>

2
src/ui/map/QGCMapWidget.cc

@ -10,7 +10,7 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) : @@ -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),

16
src/ui/uas/UASControlWidget.cc

@ -44,6 +44,7 @@ This file is part of the PIXHAWK project @@ -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), @@ -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), @@ -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() @@ -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) @@ -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"));

1
src/ui/uas/UASListWidget.cc

@ -114,6 +114,7 @@ void UASListWidget::activeUAS(UASInterface* uas) @@ -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();

Loading…
Cancel
Save