Commit 6015f664 authored by Bryan Godbolt's avatar Bryan Godbolt

merged upstream

parents d018be5d 3ce833b4
...@@ -8,7 +8,7 @@ obj ...@@ -8,7 +8,7 @@ obj
bin/*.exe bin/*.exe
bin/*.txt bin/*.txt
bin/mac bin/mac
*pro.user *pro.user*
qrc_*.cpp qrc_*.cpp
*.Debug *.Debug
*.Release *.Release
......
...@@ -69,6 +69,7 @@ macx { ...@@ -69,6 +69,7 @@ macx {
-framework SDL \ -framework SDL \
-framework CoreFoundation \ -framework CoreFoundation \
-framework ApplicationServices \ -framework ApplicationServices \
# -framework GLUT \
-lm -lm
ICON = $$BASEDIR/images/icons/macx.icns ICON = $$BASEDIR/images/icons/macx.icns
...@@ -107,8 +108,48 @@ linux-g++ { ...@@ -107,8 +108,48 @@ linux-g++ {
LIBS += \ LIBS += \
-L/usr/lib \ -L/usr/lib \
-lm \ -lm \
-lflite_cmu_us_kal16 \
-lflite_usenglish \
-lflite_cmulex \
-lflite \
-lSDL \
-lSDLmain
#-lflite_cmu_us_rms \ #-lflite_cmu_us_rms \
#-lflite_cmu_us_slt \ #-lflite_cmu_us_slt \
}
linux-g++-64 {
CONFIG += debug
debug {
DESTDIR = $$BASEDIR
}
release {
DESTDIR = $$BASEDIR
}
INCLUDEPATH += /usr/include \
/usr/include/qt4/phonon
# $$BASEDIR/lib/flite/include \
# $$BASEDIR/lib/flite/lang
HARDWARE_PLATFORM = $$system(uname -a)
contains( HARDWARE_PLATFORM, x86_64 ) {
# 64-bit Linux
#LIBS += \
#-L$$BASEDIR/lib/flite/linux64
message(Building for GNU/Linux 64bit/x64)
} else {
# 32-bit Linux
#LIBS += \
#-L$$BASEDIR/lib/flite/linux32
message(Building for GNU/Linux 32bit/i386)
}
LIBS += \
-L/usr/lib \
-lm \
-lflite_cmu_us_kal16 \ -lflite_cmu_us_kal16 \
-lflite_usenglish \ -lflite_usenglish \
-lflite_cmulex \ -lflite_cmulex \
......
...@@ -18,10 +18,9 @@ TARGET = qgroundcontrol ...@@ -18,10 +18,9 @@ TARGET = qgroundcontrol
BASEDIR = . BASEDIR = .
BUILDDIR = build BUILDDIR = build
LANGUAGE = C++ LANGUAGE = C++
CONFIG += debug_and_release \ # console CONFIG += debug_and_release \
OBJECTS_DIR \ console
= \ OBJECTS_DIR = $$BUILDDIR/obj
$$BUILDDIR/obj
MOC_DIR = $$BUILDDIR/moc MOC_DIR = $$BUILDDIR/moc
UI_HEADERS_DIR = src/ui/generated UI_HEADERS_DIR = src/ui/generated
...@@ -56,7 +55,7 @@ FORMS += src/ui/MainWindow.ui \ ...@@ -56,7 +55,7 @@ FORMS += src/ui/MainWindow.ui \
src/ui/UASControl.ui \ src/ui/UASControl.ui \
src/ui/UASList.ui \ src/ui/UASList.ui \
src/ui/UASInfo.ui \ src/ui/UASInfo.ui \
src/ui/LineChart.ui \ src/ui/Linechart.ui \
src/ui/UASView.ui \ src/ui/UASView.ui \
src/ui/ParameterInterface.ui \ src/ui/ParameterInterface.ui \
src/ui/WaypointList.ui \ src/ui/WaypointList.ui \
...@@ -90,7 +89,8 @@ INCLUDEPATH += src \ ...@@ -90,7 +89,8 @@ INCLUDEPATH += src \
src/lib/qmapcontrol \ src/lib/qmapcontrol \
src/ui/mavlink \ src/ui/mavlink \
src/ui/param \ src/ui/param \
src/ui/watchdog src/ui/watchdog \
src/ui/map3D
HEADERS += src/MG.h \ HEADERS += src/MG.h \
src/Core.h \ src/Core.h \
src/uas/UASInterface.h \ src/uas/UASInterface.h \
...@@ -158,7 +158,6 @@ HEADERS += src/MG.h \ ...@@ -158,7 +158,6 @@ HEADERS += src/MG.h \
src/ui/linechart/IncrementalPlot.h \ src/ui/linechart/IncrementalPlot.h \
src/ui/map/Waypoint2DIcon.h \ src/ui/map/Waypoint2DIcon.h \
src/ui/map/MAV2DIcon.h \ src/ui/map/MAV2DIcon.h \
src/ui/map/QGC2DIcon.h \
src/ui/QGCRemoteControlView.h \ src/ui/QGCRemoteControlView.h \
src/WaypointGlobal.h \ src/WaypointGlobal.h \
src/ui/WaypointGlobalView.h \ src/ui/WaypointGlobalView.h \
...@@ -167,7 +166,11 @@ HEADERS += src/MG.h \ ...@@ -167,7 +166,11 @@ HEADERS += src/MG.h \
src/ui/RadioCalibration/AirfoilServoCalibrator.h \ src/ui/RadioCalibration/AirfoilServoCalibrator.h \
src/ui/RadioCalibration/SwitchCalibrator.h \ src/ui/RadioCalibration/SwitchCalibrator.h \
src/ui/RadioCalibration/CurveCalibrator.h \ src/ui/RadioCalibration/CurveCalibrator.h \
src/ui/RadioCalibration/AbstractCalibrator.h src/ui/RadioCalibration/AbstractCalibrator.h \
src/ui/map3D/Q3DWidget.h \
src/ui/map3D/CheetahModel.h \
src/ui/map3D/CheetahGL.h \
src/ui/map3D/QMap3DWidget.h
SOURCES += src/main.cc \ SOURCES += src/main.cc \
src/Core.cc \ src/Core.cc \
src/uas/UASManager.cc \ src/uas/UASManager.cc \
...@@ -230,7 +233,6 @@ SOURCES += src/main.cc \ ...@@ -230,7 +233,6 @@ SOURCES += src/main.cc \
src/ui/linechart/IncrementalPlot.cc \ src/ui/linechart/IncrementalPlot.cc \
src/ui/map/Waypoint2DIcon.cc \ src/ui/map/Waypoint2DIcon.cc \
src/ui/map/MAV2DIcon.cc \ src/ui/map/MAV2DIcon.cc \
src/ui/map/QGC2DIcon.cc \
src/ui/QGCRemoteControlView.cc \ src/ui/QGCRemoteControlView.cc \
src/WaypointGlobal.cpp \ src/WaypointGlobal.cpp \
src/ui/WaypointGlobalView.cpp \ src/ui/WaypointGlobalView.cpp \
...@@ -239,7 +241,11 @@ SOURCES += src/main.cc \ ...@@ -239,7 +241,11 @@ SOURCES += src/main.cc \
src/ui/RadioCalibration/SwitchCalibrator.cc \ src/ui/RadioCalibration/SwitchCalibrator.cc \
src/ui/RadioCalibration/CurveCalibrator.cc \ src/ui/RadioCalibration/CurveCalibrator.cc \
src/ui/RadioCalibration/AbstractCalibrator.cc \ src/ui/RadioCalibration/AbstractCalibrator.cc \
src/ui/RadioCalibration/RadioCalibrationData.cc src/ui/RadioCalibration/RadioCalibrationData.cc \
src/ui/map3D/Q3DWidget.cc \
src/ui/map3D/CheetahModel.cc \
src/ui/map3D/CheetahGL.cc \
src/ui/map3D/QMap3DWidget.cc
RESOURCES = mavground.qrc RESOURCES = mavground.qrc
# Include RT-LAB Library # Include RT-LAB Library
......
...@@ -123,8 +123,8 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv) ...@@ -123,8 +123,8 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
msgBox.setIcon(QMessageBox::Critical); msgBox.setIcon(QMessageBox::Critical);
msgBox.setText("Could not connect UDP port. Is an instance of " + qAppName() + "already running?"); msgBox.setText("Could not connect UDP port. Is an instance of " + qAppName() + "already running?");
msgBox.setInformativeText("You will not be able to receive data via UDP. Please check that you're running the right executable and then re-start " + qAppName() + ". Do you want to close the application?"); msgBox.setInformativeText("You will not be able to receive data via UDP. Please check that you're running the right executable and then re-start " + qAppName() + ". Do you want to close the application?");
msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::Cancel); msgBox.setStandardButtons(QMessageBox::Yes | QMessageBox::No);
msgBox.setDefaultButton(QMessageBox::Cancel); msgBox.setDefaultButton(QMessageBox::No);
int ret = msgBox.exec(); int ret = msgBox.exec();
// Close the message box shortly after the click to prevent accidental clicks // Close the message box shortly after the click to prevent accidental clicks
......
...@@ -405,14 +405,14 @@ void MAVLinkSimulationLink::mainloop() ...@@ -405,14 +405,14 @@ void MAVLinkSimulationLink::mainloop()
streampointer += bufferlength; streampointer += bufferlength;
// GPS RAW // GPS RAW
mavlink_msg_gps_raw_pack(systemId, componentId, &ret, 0, 3, 47.376417+x*0.001f, 8.548103+y*0.001f, z, 0, 0, 2.5f, 0.1f); mavlink_msg_gps_raw_pack(systemId, componentId, &ret, 0, 3, 47.376417+(x*0.001), 8.548103+(y*0.001), z, 0, 0, 2.5f, 0.1f);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret); bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream //add data into datastream
memcpy(stream+streampointer,buffer, bufferlength); memcpy(stream+streampointer,buffer, bufferlength);
streampointer += bufferlength; streampointer += bufferlength;
// GLOBAL POSITION // GLOBAL POSITION
mavlink_msg_global_position_pack(systemId, componentId, &ret, 0, 3, 47.376417+x*0.001f, 8.548103+y*0.001f, z, 0, 0); mavlink_msg_global_position_pack(systemId, componentId, &ret, 0, 3, 47.376417+(x*0.001), 8.548103+(y*0.001), z, 0, 0);
bufferlength = mavlink_msg_to_send_buffer(buffer, &ret); bufferlength = mavlink_msg_to_send_buffer(buffer, &ret);
//add data into datastream //add data into datastream
memcpy(stream+streampointer,buffer, bufferlength); memcpy(stream+streampointer,buffer, bufferlength);
......
...@@ -57,7 +57,7 @@ class SerialLink : public SerialLinkInterface { ...@@ -57,7 +57,7 @@ class SerialLink : public SerialLinkInterface {
//Q_INTERFACES(SerialLinkInterface:LinkInterface) //Q_INTERFACES(SerialLinkInterface:LinkInterface)
public: public:
SerialLink(QString portname=NULL, BaudRateType baudrate=BAUD57600, FlowType flow=FLOW_OFF, ParityType parity=PAR_NONE, DataBitsType dataBits=DATA_8, StopBitsType stopBits=STOP_1); SerialLink(QString portname = "", BaudRateType baudrate=BAUD57600, FlowType flow=FLOW_OFF, ParityType parity=PAR_NONE, DataBitsType dataBits=DATA_8, StopBitsType stopBits=STOP_1);
~SerialLink(); ~SerialLink();
static const int poll_interval = SERIAL_POLL_INTERVAL; ///< Polling interval, defined in configuration.h static const int poll_interval = SERIAL_POLL_INTERVAL; ///< Polling interval, defined in configuration.h
......
...@@ -73,6 +73,12 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), ...@@ -73,6 +73,12 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
sendDropRate(0), sendDropRate(0),
lowBattAlarm(false), lowBattAlarm(false),
positionLock(false), positionLock(false),
localX(0),
localY(0),
localZ(0),
roll(0),
pitch(0),
yaw(0),
statusTimeout(new QTimer(this)) statusTimeout(new QTimer(this))
{ {
color = UASInterface::getNextColor(); color = UASInterface::getNextColor();
...@@ -281,6 +287,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -281,6 +287,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_attitude_t attitude; mavlink_attitude_t attitude;
mavlink_msg_attitude_decode(&message, &attitude); mavlink_msg_attitude_decode(&message, &attitude);
quint64 time = getUnixTime(attitude.usec); quint64 time = getUnixTime(attitude.usec);
roll = attitude.roll;
pitch = attitude.pitch;
yaw = attitude.yaw;
emit valueChanged(uasId, "roll IMU", mavlink_msg_attitude_get_roll(&message), time); emit valueChanged(uasId, "roll IMU", mavlink_msg_attitude_get_roll(&message), time);
emit valueChanged(uasId, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time); emit valueChanged(uasId, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time);
emit valueChanged(uasId, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time); emit valueChanged(uasId, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time);
...@@ -300,6 +309,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -300,6 +309,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_local_position_t pos; mavlink_local_position_t pos;
mavlink_msg_local_position_decode(&message, &pos); mavlink_msg_local_position_decode(&message, &pos);
quint64 time = getUnixTime(pos.usec); quint64 time = getUnixTime(pos.usec);
localX = pos.x;
localY = pos.y;
localZ = pos.z;
emit valueChanged(uasId, "x", pos.x, time); emit valueChanged(uasId, "x", pos.x, time);
emit valueChanged(uasId, "y", pos.y, time); emit valueChanged(uasId, "y", pos.y, time);
emit valueChanged(uasId, "z", pos.z, time); emit valueChanged(uasId, "z", pos.z, time);
...@@ -353,28 +365,34 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -353,28 +365,34 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// only accept values in a realistic range // only accept values in a realistic range
// quint64 time = getUnixTime(pos.usec); // quint64 time = getUnixTime(pos.usec);
quint64 time = MG::TIME::getGroundTimeNow(); quint64 time = MG::TIME::getGroundTimeNow();
emit valueChanged(uasId, "lat", pos.lat, time); emit valueChanged(uasId, "lat", pos.lat, time);
emit valueChanged(uasId, "lon", pos.lon, time); emit valueChanged(uasId, "lon", pos.lon, time);
// Check for NaN
int alt = pos.alt; if (pos.fix_type > 0)
if (alt != alt)
{
alt = 0;
emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
}
emit valueChanged(uasId, "alt", pos.alt, time);
// Smaller than threshold and not NaN
if (pos.v < 1000000 && pos.v == pos.v)
{
emit valueChanged(uasId, "speed", pos.v, time);
//qDebug() << "GOT GPS RAW";
emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
}
else
{ {
emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v)); emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
// Check for NaN
int alt = pos.alt;
if (alt != alt)
{
alt = 0;
emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE");
}
emit valueChanged(uasId, "alt", pos.alt, time);
// Smaller than threshold and not NaN
if (pos.v < 1000000 && pos.v == pos.v)
{
emit valueChanged(uasId, "speed", pos.v, time);
//qDebug() << "GOT GPS RAW";
emit speedChanged(this, (double)pos.v, 0.0, 0.0, time);
}
else
{
emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v));
}
} }
emit globalPositionChanged(this, pos.lon, pos.lat, alt, time);
} }
break; break;
case MAVLINK_MSG_ID_GPS_STATUS: case MAVLINK_MSG_ID_GPS_STATUS:
...@@ -1159,8 +1177,8 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double ...@@ -1159,8 +1177,8 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double
manualYawAngle = yaw * yawScaling; manualYawAngle = yaw * yawScaling;
manualThrust = thrust * thrustScaling; manualThrust = thrust * thrustScaling;
if(mode == (int)MAV_MODE_MANUAL) // if(mode == (int)MAV_MODE_MANUAL)
{ // {
#ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES #ifdef MAVLINK_ENABLED_PIXHAWK_MESSAGES
mavlink_message_t message; mavlink_message_t message;
mavlink_msg_manual_control_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual); mavlink_msg_manual_control_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &message, this->uasId, (float)manualRollAngle, (float)manualPitchAngle, (float)manualYawAngle, (float)manualThrust, controlRollManual, controlPitchManual, controlYawManual, controlThrustManual);
...@@ -1169,7 +1187,7 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double ...@@ -1169,7 +1187,7 @@ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double
emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow()); emit attitudeThrustSetPointChanged(this, roll, pitch, yaw, thrust, MG::TIME::getGroundTimeNow());
#endif #endif
} // }
} }
int UAS::getSystemType() int UAS::getSystemType()
...@@ -1363,6 +1381,16 @@ void UAS::shutdown() ...@@ -1363,6 +1381,16 @@ void UAS::shutdown()
} }
} }
void UAS::setTargetPosition(float x, float y, float z, float yaw)
{
mavlink_message_t msg;
mavlink_msg_position_target_pack(MG::SYSTEM::ID, MG::SYSTEM::COMPID, &msg, x, y, z, yaw);
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
}
/** /**
* @return The name of this system as string in human-readable form * @return The name of this system as string in human-readable form
*/ */
......
...@@ -79,6 +79,15 @@ public: ...@@ -79,6 +79,15 @@ public:
/** @brief Get the links associated with this robot */ /** @brief Get the links associated with this robot */
QList<LinkInterface*>* getLinks(); QList<LinkInterface*>* getLinks();
double getLocalX() const { return localX; };
double getLocalY() const { return localY; };
double getLocalZ() const { return localZ; };
double getRoll() const { return roll; };
double getPitch() const { return pitch; };
double getYaw() const { return yaw; };
friend class UASWaypointManager; friend class UASWaypointManager;
protected: protected:
int uasId; ///< Unique system ID int uasId; ///< Unique system ID
...@@ -127,6 +136,12 @@ protected: ...@@ -127,6 +136,12 @@ protected:
float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS float sendDropRate; ///< Percentage of packets that were not received from the MAV by the GCS
bool lowBattAlarm; ///< Switch if battery is low bool lowBattAlarm; ///< Switch if battery is low
bool positionLock; ///< Status if position information is available or not bool positionLock; ///< Status if position information is available or not
double localX;
double localY;
double localZ;
double roll;
double pitch;
double yaw;
QTimer* statusTimeout; ///< Timer for various status timeouts QTimer* statusTimeout; ///< Timer for various status timeouts
/** @brief Set the current battery type */ /** @brief Set the current battery type */
...@@ -164,6 +179,9 @@ public slots: ...@@ -164,6 +179,9 @@ public slots:
/** @brief Shut the system cleanly down. Will shut down any onboard computers **/ /** @brief Shut the system cleanly down. Will shut down any onboard computers **/
void shutdown(); void shutdown();
/** @brief Set the target position for the robot to navigate to. */
void setTargetPosition(float x, float y, float z, float yaw);
void startLowBattAlarm(); void startLowBattAlarm();
void stopLowBattAlarm(); void stopLowBattAlarm();
......
...@@ -66,6 +66,14 @@ public: ...@@ -66,6 +66,14 @@ public:
/** @brief Get the status flag for the communication **/ /** @brief Get the status flag for the communication **/
virtual int getCommunicationStatus() const = 0; virtual int getCommunicationStatus() const = 0;
virtual double getLocalX() const = 0;
virtual double getLocalY() const = 0;
virtual double getLocalZ() const = 0;
virtual double getRoll() const = 0;
virtual double getPitch() const = 0;
virtual double getYaw() const = 0;
/** @brief Get reference to the waypoint manager **/ /** @brief Get reference to the waypoint manager **/
virtual UASWaypointManager &getWaypointManager(void) = 0; virtual UASWaypointManager &getWaypointManager(void) = 0;
...@@ -171,6 +179,13 @@ public slots: ...@@ -171,6 +179,13 @@ public slots:
* Works only if already landed and will cleanly shut down all onboard computers. * Works only if already landed and will cleanly shut down all onboard computers.
*/ */
virtual void shutdown() = 0; virtual void shutdown() = 0;
/** @brief Set the target position for the robot to navigate to.
* @param x x-coordinate of the target position
* @param y y-coordinate of the target position
* @param z z-coordinate of the target position
* @param yaw heading of the target position
*/
virtual void setTargetPosition(float x, float y, float z, float yaw) = 0;
/** @brief Request the list of stored waypoints from the robot */ /** @brief Request the list of stored waypoints from the robot */
//virtual void requestWaypoints() = 0; //virtual void requestWaypoints() = 0;
/** @brief Clear all existing waypoints on the robot */ /** @brief Clear all existing waypoints on the robot */
......
...@@ -100,7 +100,7 @@ HSIDisplay::HSIDisplay(QWidget *parent) : ...@@ -100,7 +100,7 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
topMargin(3.0f) topMargin(3.0f)
{ {
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
refreshTimer->setInterval(60); refreshTimer->setInterval(120);
// this->setScene(new QGraphicsScene(-metricWidth/2.0f, -metricWidth/2.0f, metricWidth, metricWidth, this)); // this->setScene(new QGraphicsScene(-metricWidth/2.0f, -metricWidth/2.0f, metricWidth, metricWidth, this));
......
...@@ -448,7 +448,7 @@ void HUD::paintText(QString text, QColor color, float fontSize, float refX, floa ...@@ -448,7 +448,7 @@ void HUD::paintText(QString text, QColor color, float fontSize, float refX, floa
QFont font("Bitstream Vera Sans"); QFont font("Bitstream Vera Sans");
// Enforce minimum font size of 5 pixels // Enforce minimum font size of 5 pixels
int fSize = qMax(1, (int)(fontSize*scalingFactor*1.26f)); int fSize = qMax(5, (int)(fontSize*scalingFactor*1.26f));
font.setPixelSize(fSize); font.setPixelSize(fSize);
QFontMetrics metrics = QFontMetrics(font); QFontMetrics metrics = QFontMetrics(font);
......
...@@ -45,6 +45,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -45,6 +45,7 @@ This file is part of the QGROUNDCONTROL project
#include "MainWindow.h" #include "MainWindow.h"
#include "JoystickWidget.h" #include "JoystickWidget.h"
#include "GAudioOutput.h" #include "GAudioOutput.h"
#include "QMap3DWidget.h"
// FIXME Move // FIXME Move
#include "PxQuadMAV.h" #include "PxQuadMAV.h"
...@@ -131,7 +132,7 @@ void MainWindow::buildWidgets() ...@@ -131,7 +132,7 @@ void MainWindow::buildWidgets()
mapWidget = new MapWidget(this); mapWidget = new MapWidget(this);
protocolWidget = new XMLCommProtocolWidget(this); protocolWidget = new XMLCommProtocolWidget(this);
dataplotWidget = new QGCDataPlot2D(this); dataplotWidget = new QGCDataPlot2D(this);
map3DWidget = new QWidget(this); // FIXME Lionel, insert visualizer here map3DWidget = new QMap3DWidget(this);
// Dock widgets // Dock widgets
controlDockWidget = new QDockWidget(tr("Control"), this); controlDockWidget = new QDockWidget(tr("Control"), this);
...@@ -216,6 +217,7 @@ void MainWindow::arrangeCenterStack() ...@@ -216,6 +217,7 @@ void MainWindow::arrangeCenterStack()
if (linechartWidget) centerStack->addWidget(linechartWidget); if (linechartWidget) centerStack->addWidget(linechartWidget);
if (protocolWidget) centerStack->addWidget(protocolWidget); if (protocolWidget) centerStack->addWidget(protocolWidget);
if (mapWidget) centerStack->addWidget(mapWidget); if (mapWidget) centerStack->addWidget(mapWidget);
if (map3DWidget) centerStack->addWidget(map3DWidget);
if (hudWidget) centerStack->addWidget(hudWidget); if (hudWidget) centerStack->addWidget(hudWidget);
if (dataplotWidget) centerStack->addWidget(dataplotWidget); if (dataplotWidget) centerStack->addWidget(dataplotWidget);
...@@ -655,14 +657,14 @@ void MainWindow::loadPixhawkView() ...@@ -655,14 +657,14 @@ void MainWindow::loadPixhawkView()
clearView(); clearView();
// Engineer view, used in EMAV2009 // Engineer view, used in EMAV2009
// LINE CHART // 3D map
if (linechartWidget) if (map3DWidget)
{ {
QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget()); QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
if (centerStack) if (centerStack)
{ {
linechartWidget->setActive(true); //map3DWidget->setActive(true);
centerStack->setCurrentWidget(linechartWidget); centerStack->setCurrentWidget(map3DWidget);
} }
} }
...@@ -673,6 +675,18 @@ void MainWindow::loadPixhawkView() ...@@ -673,6 +675,18 @@ void MainWindow::loadPixhawkView()
controlDockWidget->show(); controlDockWidget->show();
} }
// HORIZONTAL SITUATION INDICATOR
if (hsiDockWidget)
{
HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
if (hsi)
{
hsi->start();
addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget);
hsiDockWidget->show();
}
}
// UAS LIST // UAS LIST
if (listDockWidget) if (listDockWidget)
{ {
...@@ -694,18 +708,6 @@ void MainWindow::loadPixhawkView() ...@@ -694,18 +708,6 @@ void MainWindow::loadPixhawkView()
waypointsDockWidget->show(); waypointsDockWidget->show();
} }
// HORIZONTAL SITUATION INDICATOR
if (hsiDockWidget)
{
HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
if (hsi)
{
hsi->start();
addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget);
hsiDockWidget->show();
}
}
// DEBUG CONSOLE // DEBUG CONSOLE
if (debugConsoleDockWidget) if (debugConsoleDockWidget)
{ {
...@@ -713,13 +715,6 @@ void MainWindow::loadPixhawkView() ...@@ -713,13 +715,6 @@ void MainWindow::loadPixhawkView()
debugConsoleDockWidget->show(); debugConsoleDockWidget->show();
} }
// RADIO CONTROL VIEW
if (rcViewDockWidget)
{
addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget);
rcViewDockWidget->show();
}
// ONBOARD PARAMETERS // ONBOARD PARAMETERS
if (parametersDockWidget) if (parametersDockWidget)
{ {
......
...@@ -63,6 +63,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -63,6 +63,7 @@ This file is part of the QGROUNDCONTROL project
#include "HSIDisplay.h" #include "HSIDisplay.h"
#include "QGCDataPlot2D.h" #include "QGCDataPlot2D.h"
#include "QGCRemoteControlView.h" #include "QGCRemoteControlView.h"
#include "QMap3DWidget.h"
#include "LogCompressor.h" #include "LogCompressor.h"
...@@ -160,7 +161,7 @@ protected: ...@@ -160,7 +161,7 @@ protected:
QPointer<MapWidget> mapWidget; QPointer<MapWidget> mapWidget;
QPointer<XMLCommProtocolWidget> protocolWidget; QPointer<XMLCommProtocolWidget> protocolWidget;
QPointer<QGCDataPlot2D> dataplotWidget; QPointer<QGCDataPlot2D> dataplotWidget;
QPointer<QWidget> map3DWidget; QPointer<QMap3DWidget> map3DWidget;
// Dock widgets // Dock widgets
QPointer<QDockWidget> controlDockWidget; QPointer<QDockWidget> controlDockWidget;
QPointer<QDockWidget> infoDockWidget; QPointer<QDockWidget> infoDockWidget;
......
...@@ -38,7 +38,7 @@ ...@@ -38,7 +38,7 @@
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>1000</width> <width>1000</width>
<height>23</height> <height>25</height>
</rect> </rect>
</property> </property>
<widget class="QMenu" name="menuMGround"> <widget class="QMenu" name="menuMGround">
...@@ -113,7 +113,7 @@ ...@@ -113,7 +113,7 @@
<widget class="QStatusBar" name="statusBar"/> <widget class="QStatusBar" name="statusBar"/>
<action name="actionExit"> <action name="actionExit">
<property name="icon"> <property name="icon">
<iconset> <iconset resource="../../mavground.qrc">
<normaloff>:/images/actions/system-log-out.svg</normaloff>:/images/actions/system-log-out.svg</iconset> <normaloff>:/images/actions/system-log-out.svg</normaloff>:/images/actions/system-log-out.svg</iconset>
</property> </property>
<property name="text"> <property name="text">
...@@ -123,22 +123,9 @@ ...@@ -123,22 +123,9 @@
<string>Ctrl+Q</string> <string>Ctrl+Q</string>
</property> </property>
</action> </action>
<action name="actionSettings">
<property name="icon">
<iconset>
<normaloff>:/images/categories/preferences-system.svg</normaloff>
<normalon>:/images/categories/preferences-system.svg</normalon>:/images/categories/preferences-system.svg</iconset>
</property>
<property name="text">
<string>Settings</string>
</property>
<property name="shortcut">
<string>Ctrl+P</string>
</property>
</action>
<action name="actionLiftoff"> <action name="actionLiftoff">