Commit 3d5d9f06 authored by pixhawk's avatar pixhawk

Merge branch 'v10release' of git://github.com/pixhawk/qgroundcontrol into v10release

parents 2198cffd 94f9e534
...@@ -42,8 +42,8 @@ macx { ...@@ -42,8 +42,8 @@ macx {
# COMPILER_VERSION = $$system(gcc -v) # COMPILER_VERSION = $$system(gcc -v)
#message(Using compiler $$COMPILER_VERSION) #message(Using compiler $$COMPILER_VERSION)
CONFIG += x86 cocoa phonon CONFIG += x86_64 cocoa phonon
CONFIG -= x86_64 CONFIG -= x86
#HARDWARE_PLATFORM = $$system(uname -a) #HARDWARE_PLATFORM = $$system(uname -a)
#contains( $$HARDWARE_PLATFORM, "9.6.0" ) || contains( $$HARDWARE_PLATFORM, "9.7.0" ) || contains( $$HARDWARE_PLATFORM, "9.8.0" ) || contains( $$HARDWARE_PLATFORM, "9.9.0" ) { #contains( $$HARDWARE_PLATFORM, "9.6.0" ) || contains( $$HARDWARE_PLATFORM, "9.7.0" ) || contains( $$HARDWARE_PLATFORM, "9.8.0" ) || contains( $$HARDWARE_PLATFORM, "9.9.0" ) {
...@@ -65,11 +65,10 @@ macx { ...@@ -65,11 +65,10 @@ macx {
# debug { # debug {
#QMAKE_CXXFLAGS += -finstrument-functions #QMAKE_CXXFLAGS += -finstrument-functions
#LIBS += -lSaturn #LIBS += -lSaturn
CONFIG += console
# } # }
#} #}
QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.5 QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.6
#DESTDIR = $$BASEDIR/bin/mac #DESTDIR = $$BASEDIR/bin/mac
INCLUDEPATH += -framework SDL INCLUDEPATH += -framework SDL
...@@ -103,7 +102,7 @@ macx { ...@@ -103,7 +102,7 @@ macx {
DEFINES += QGC_OSG_ENABLED DEFINES += QGC_OSG_ENABLED
# Include OpenSceneGraph libraries # Include OpenSceneGraph libraries
INCLUDEPATH += -framework GLUT \ INCLUDEPATH += -framework GLUT \
-framework Carbon \ -framework Cocoa \
-framework OpenThreads \ -framework OpenThreads \
-framework osg \ -framework osg \
-framework osgViewer \ -framework osgViewer \
...@@ -113,7 +112,7 @@ macx { ...@@ -113,7 +112,7 @@ macx {
-framework osgWidget -framework osgWidget
LIBS += -framework GLUT \ LIBS += -framework GLUT \
-framework Carbon \ -framework Cocoa \
-framework OpenThreads \ -framework OpenThreads \
-framework osg \ -framework osg \
-framework osgViewer \ -framework osgViewer \
...@@ -123,37 +122,13 @@ macx { ...@@ -123,37 +122,13 @@ macx {
-framework osgWidget -framework osgWidget
} }
exists(/usr/include/osgEarth) { exists(/opt/local/include/libfreenect)|exists(/usr/local/include/libfreenect) {
message("Building support for osgEarth")
DEPENDENCIES_PRESENT += osgearth
# Include osgEarth libraries
INCLUDEPATH += -framework GDAL \
$$IN_PWD/lib/mac32-gcc/include \
-framework GEOS \
-framework SQLite3 \
-framework osgFX \
-framework osgTerrain
LIBS += -framework GDAL \
-framework GEOS \
-framework SQLite3 \
-framework osgFX \
-framework osgTerrain
DEFINES += QGC_OSGEARTH_ENABLED
}
exists(/opt/local/include/libfreenect) {
message("Building support for libfreenect") message("Building support for libfreenect")
DEPENDENCIES_PRESENT += libfreenect DEPENDENCIES_PRESENT += libfreenect
# Include libfreenect libraries # Include libfreenect libraries
LIBS += -lfreenect LIBS += -lfreenect
DEFINES += QGC_LIBFREENECT_ENABLED DEFINES += QGC_LIBFREENECT_ENABLED
} }
# osg/osgEarth dynamic casts might fail without this compiler option.
# see http://osgearth.org/wiki/FAQ for details.
#QMAKE_CXXFLAGS += -Wl,-E
} }
# GNU/Linux # GNU/Linux
......
...@@ -303,12 +303,12 @@ void MAVLinkSimulationMAV::mainloop() ...@@ -303,12 +303,12 @@ void MAVLinkSimulationMAV::mainloop()
timer25Hz--; timer25Hz--;
} }
static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS]; //static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS];
static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS; static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS;
static unsigned error_count; //static unsigned error_count;
static const mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO; mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO;
static void print_one_field(const mavlink_message_t *msg, const mavlink_field_info_t *f, int idx) static void print_one_field(const mavlink_message_t *msg, const mavlink_field_info_t *f, int idx)
{ {
......
...@@ -33,7 +33,18 @@ ...@@ -33,7 +33,18 @@
namespace mapcontrol namespace mapcontrol
{ {
OPMapWidget::OPMapWidget(QWidget *parent, Configuration *config):QGraphicsView(parent),configuration(config),UAV(0),GPS(0),Home(0),followmouse(true),compass(0),showuav(false),showhome(false),showDiag(false),diagGraphItem(0),diagTimer(0) OPMapWidget::OPMapWidget(QWidget *parent, Configuration *config) : QGraphicsView(parent),
configuration(config),
UAV(0),
GPS(0),
Home(0),
followmouse(true),
compass(0),
showuav(false),
showhome(false),
diagTimer(0),
showDiag(false),
diagGraphItem(0)
{ {
setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred); setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred);
core=new internals::Core; core=new internals::Core;
...@@ -277,6 +288,7 @@ namespace mapcontrol ...@@ -277,6 +288,7 @@ namespace mapcontrol
} }
void OPMapWidget::WPCreate(int id, WayPointItem* item) void OPMapWidget::WPCreate(int id, WayPointItem* item)
{ {
Q_UNUSED(id);
static internals::PointLatLng lastPos; static internals::PointLatLng lastPos;
ConnectWP(item); ConnectWP(item);
......
...@@ -29,14 +29,14 @@ namespace mapcontrol ...@@ -29,14 +29,14 @@ namespace mapcontrol
{ {
WayPointItem::WayPointItem(const internals::PointLatLng &coord,double const& altitude, MapGraphicItem *map) : WayPointItem::WayPointItem(const internals::PointLatLng &coord,double const& altitude, MapGraphicItem *map) :
map(map), map(map),
autoreachedEnabled(true),
coord(coord), coord(coord),
reached(false), reached(false),
description(""), description(""),
shownumber(true), shownumber(true),
isDragging(false), isDragging(false),
altitude(altitude), altitude(altitude),
heading(0), heading(0)
autoreachedEnabled(true)
{ {
text=0; text=0;
numberI=0; numberI=0;
...@@ -53,13 +53,13 @@ namespace mapcontrol ...@@ -53,13 +53,13 @@ namespace mapcontrol
RefreshPos(); RefreshPos();
} }
WayPointItem::WayPointItem(const internals::PointLatLng &coord,double const& altitude, const QString &description, MapGraphicItem *map) : WayPointItem::WayPointItem(const internals::PointLatLng &coord,double const& altitude, const QString &description, MapGraphicItem *map) :
map(map),
coord(coord), coord(coord),
reached(false), reached(false),
description(description), description(description),
shownumber(true), shownumber(true),
isDragging(false), isDragging(false),
altitude(altitude), altitude(altitude),
map(map),
heading(0) heading(0)
{ {
text=0; text=0;
......
...@@ -63,7 +63,7 @@ bool XmlConfig::readXmlFile(QIODevice &device, QSettings::SettingsMap &map) ...@@ -63,7 +63,7 @@ bool XmlConfig::readXmlFile(QIODevice &device, QSettings::SettingsMap &map)
.arg(errorLine) .arg(errorLine)
.arg(errorColumn) .arg(errorColumn)
.arg(errorStr); .arg(errorStr);
qFatal(err.toLatin1().data()); qFatal("%s", err.toLatin1().data());
return false; return false;
} }
root = domDoc.documentElement(); root = domDoc.documentElement();
......
...@@ -1459,6 +1459,7 @@ void UAS::writeParametersToStorage() ...@@ -1459,6 +1459,7 @@ void UAS::writeParametersToStorage()
{ {
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0); mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, 0, MAV_CMD_PREFLIGHT_STORAGE, 1, 1, -1, -1, -1, 0, 0, 0);
qDebug() << "SENT COMMAND" << MAV_CMD_PREFLIGHT_STORAGE;
sendMessage(msg); sendMessage(msg);
} }
...@@ -1492,7 +1493,6 @@ void UAS::enableAllDataTransmission(int rate) ...@@ -1492,7 +1493,6 @@ void UAS::enableAllDataTransmission(int rate)
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg);
} }
void UAS::enableRawSensorDataTransmission(int rate) void UAS::enableRawSensorDataTransmission(int rate)
...@@ -1514,7 +1514,6 @@ void UAS::enableRawSensorDataTransmission(int rate) ...@@ -1514,7 +1514,6 @@ void UAS::enableRawSensorDataTransmission(int rate)
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg);
} }
void UAS::enableExtendedSystemStatusTransmission(int rate) void UAS::enableExtendedSystemStatusTransmission(int rate)
...@@ -1536,7 +1535,6 @@ void UAS::enableExtendedSystemStatusTransmission(int rate) ...@@ -1536,7 +1535,6 @@ void UAS::enableExtendedSystemStatusTransmission(int rate)
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg);
} }
void UAS::enableRCChannelDataTransmission(int rate) void UAS::enableRCChannelDataTransmission(int rate)
...@@ -1562,7 +1560,6 @@ void UAS::enableRCChannelDataTransmission(int rate) ...@@ -1562,7 +1560,6 @@ void UAS::enableRCChannelDataTransmission(int rate)
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg);
#endif #endif
} }
...@@ -1585,7 +1582,6 @@ void UAS::enableRawControllerDataTransmission(int rate) ...@@ -1585,7 +1582,6 @@ void UAS::enableRawControllerDataTransmission(int rate)
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg);
} }
//void UAS::enableRawSensorFusionTransmission(int rate) //void UAS::enableRawSensorFusionTransmission(int rate)
...@@ -1629,7 +1625,6 @@ void UAS::enablePositionTransmission(int rate) ...@@ -1629,7 +1625,6 @@ void UAS::enablePositionTransmission(int rate)
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream); mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception // Send message twice to increase chance of reception
sendMessage(msg); sendMessage(msg);
sendMessage(msg);
} }
void UAS::enableExtra1Transmission(int rate) void UAS::enableExtra1Transmission(int rate)
...@@ -2122,7 +2117,7 @@ void UAS::shutdown() ...@@ -2122,7 +2117,7 @@ void UAS::shutdown()
{ {
// If the active UAS is set, execute command // If the active UAS is set, execute command
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 0, 2, 0, 0, 0, 0, 0, 0); mavlink_msg_command_long_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, uasId, MAV_COMP_ID_ALL, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1, 0, 2, 0, 0, 0, 0, 0);
sendMessage(msg); sendMessage(msg);
result = true; result = true;
} }
...@@ -2165,33 +2160,34 @@ QString UAS::getShortModeTextFor(int id) ...@@ -2165,33 +2160,34 @@ QString UAS::getShortModeTextFor(int id)
qDebug() << "MODE:" << modeid; qDebug() << "MODE:" << modeid;
// BASE MODE DECODING // BASE MODE DECODING
if (modeid & MAV_MODE_FLAG_DECODE_POSITION_AUTO) if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO)
{ {
mode = "AUTO"; mode += "AUTO";
} }
else if (modeid & MAV_MODE_FLAG_DECODE_POSITION_GUIDED) if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_GUIDED)
{ {
mode = "GUIDED"; mode += "GUIDED";
} }
else if (modeid & MAV_MODE_FLAG_DECODE_POSITION_STABILIZE) if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_STABILIZE)
{ {
mode = "STABILIZED"; mode += "STABILIZED";
} }
else if (modeid & MAV_MODE_FLAG_DECODE_POSITION_TEST) if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_TEST)
{ {
mode = "TEST"; mode += "TEST";
} }
else if (modeid & MAV_MODE_FLAG_DECODE_POSITION_MANUAL) if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_MANUAL)
{ {
mode = "MANUAL"; mode += "MANUAL";
} }
else
if (modeid == 0)
{ {
mode = "PREFLIGHT"; mode = "PREFLIGHT";
} }
// ARMED STATE DECODING // ARMED STATE DECODING
if (modeid & MAV_MODE_FLAG_DECODE_POSITION_SAFETY) if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
{ {
mode.prepend("A|"); mode.prepend("A|");
} }
...@@ -2201,7 +2197,7 @@ QString UAS::getShortModeTextFor(int id) ...@@ -2201,7 +2197,7 @@ QString UAS::getShortModeTextFor(int id)
} }
// HARDWARE IN THE LOOP DECODING // HARDWARE IN THE LOOP DECODING
if (modeid & MAV_MODE_FLAG_DECODE_POSITION_HIL) if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_HIL)
{ {
mode.prepend("HIL:"); mode.prepend("HIL:");
} }
......
...@@ -45,8 +45,8 @@ UASWaypointManager::UASWaypointManager(UAS* _uas) ...@@ -45,8 +45,8 @@ UASWaypointManager::UASWaypointManager(UAS* _uas)
current_state(WP_IDLE), current_state(WP_IDLE),
current_partner_systemid(0), current_partner_systemid(0),
current_partner_compid(0), current_partner_compid(0),
protocol_timer(this), currentWaypointEditable(NULL),
currentWaypointEditable(NULL) protocol_timer(this)
{ {
if (uas) if (uas)
{ {
...@@ -112,7 +112,14 @@ void UASWaypointManager::handleLocalPositionChanged(UASInterface* mav, double x, ...@@ -112,7 +112,14 @@ void UASWaypointManager::handleLocalPositionChanged(UASInterface* mav, double x,
void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double alt, quint64 time) void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double lat, double lon, double alt, quint64 time)
{ {
Q_UNUSED(mav);
Q_UNUSED(time);
if (waypointsEditable.count() > 0 && currentWaypointEditable && (currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL || currentWaypointEditable->getFrame() == MAV_FRAME_GLOBAL_RELATIVE_ALT))
{
// TODO FIXME Calculate distance
double dist = 0;
emit waypointDistanceChanged(dist);
}
} }
void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, quint16 count) void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, quint16 count)
...@@ -240,6 +247,7 @@ void UASWaypointManager::handleWaypointReached(quint8 systemId, quint8 compId, m ...@@ -240,6 +247,7 @@ void UASWaypointManager::handleWaypointReached(quint8 systemId, quint8 compId, m
void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_mission_current_t *wpc) void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, mavlink_mission_current_t *wpc)
{ {
Q_UNUSED(compId);
if (!uas) return; if (!uas) return;
if (systemId == uasid) { if (systemId == uasid) {
// FIXME Petri // FIXME Petri
......
...@@ -100,11 +100,12 @@ HSIDisplay::HSIDisplay(QWidget *parent) : ...@@ -100,11 +100,12 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
mavInitialized(false), mavInitialized(false),
bottomMargin(10.0f), bottomMargin(10.0f),
topMargin(12.0f), topMargin(12.0f),
userSetPointSet(false),
dragStarted(false), dragStarted(false),
leftDragStarted(false), leftDragStarted(false),
mouseHasMoved(false), mouseHasMoved(false),
actionPending(false) actionPending(false),
userSetPointSet(false),
userXYSetPointSet(false)
{ {
refreshTimer->setInterval(updateInterval); refreshTimer->setInterval(updateInterval);
......
...@@ -88,11 +88,11 @@ MainWindow* MainWindow::instance(QSplashScreen* screen) ...@@ -88,11 +88,11 @@ MainWindow* MainWindow::instance(QSplashScreen* screen)
MainWindow::MainWindow(QWidget *parent): MainWindow::MainWindow(QWidget *parent):
QMainWindow(parent), QMainWindow(parent),
currentView(VIEW_UNCONNECTED), currentView(VIEW_UNCONNECTED),
currentStyle(QGC_MAINWINDOW_STYLE_INDOOR),
aboutToCloseFlag(false), aboutToCloseFlag(false),
changingViewsFlag(false), changingViewsFlag(false),
styleFileName(QCoreApplication::applicationDirPath() + "/style-indoor.css"), styleFileName(QCoreApplication::applicationDirPath() + "/style-indoor.css"),
autoReconnect(false), autoReconnect(false),
currentStyle(QGC_MAINWINDOW_STYLE_INDOOR),
centerStackActionGroup(this), centerStackActionGroup(this),
lowPowerMode(false) lowPowerMode(false)
{ {
......
...@@ -279,6 +279,7 @@ protected: ...@@ -279,6 +279,7 @@ protected:
/** @brief Keeps track of the current view */ /** @brief Keeps track of the current view */
VIEW_SECTIONS currentView; VIEW_SECTIONS currentView;
QGC_MAINWINDOW_STYLE currentStyle;
bool aboutToCloseFlag; bool aboutToCloseFlag;
bool changingViewsFlag; bool changingViewsFlag;
...@@ -371,7 +372,6 @@ protected: ...@@ -371,7 +372,6 @@ protected:
QTimer* videoTimer; QTimer* videoTimer;
QString styleFileName; QString styleFileName;
bool autoReconnect; bool autoReconnect;
QGC_MAINWINDOW_STYLE currentStyle;
Qt::WindowStates windowStateVal; Qt::WindowStates windowStateVal;
bool lowPowerMode; ///< If enabled, QGC reduces the update rates of all widgets bool lowPowerMode; ///< If enabled, QGC reduces the update rates of all widgets
QGCFlightGearLink* fgLink; QGCFlightGearLink* fgLink;
......
...@@ -707,15 +707,15 @@ void QGCParamWidget::saveParameters() ...@@ -707,15 +707,15 @@ void QGCParamWidget::saveParameters()
{ {
case QVariant::Int: case QVariant::Int:
paramValue = paramValue.arg(j.value().toInt()); paramValue = paramValue.arg(j.value().toInt());
paramType.arg(MAVLINK_TYPE_INT32_T); paramType = paramType.arg(MAVLINK_TYPE_INT32_T);
break; break;
case QVariant::UInt: case QVariant::UInt:
paramValue = paramValue.arg(j.value().toUInt()); paramValue = paramValue.arg(j.value().toUInt());
paramType.arg(MAVLINK_TYPE_UINT32_T); paramType = paramType.arg(MAVLINK_TYPE_UINT32_T);
break; break;
case QMetaType::Float: case QMetaType::Float:
paramValue = paramValue.arg(j.value().toDouble(), 25, 'g', 12); paramValue = paramValue.arg(j.value().toDouble(), 25, 'g', 12);
paramType.arg(MAVLINK_TYPE_FLOAT); paramType = paramType.arg(MAVLINK_TYPE_FLOAT);
break; break;
default: default:
qCritical() << "ABORTED PARAM WRITE TO FILE, NO VALID QVARIANT TYPE" << j.value(); qCritical() << "ABORTED PARAM WRITE TO FILE, NO VALID QVARIANT TYPE" << j.value();
......
...@@ -50,12 +50,12 @@ UASControlWidget::UASControlWidget(QWidget *parent) : QWidget(parent), ...@@ -50,12 +50,12 @@ UASControlWidget::UASControlWidget(QWidget *parent) : QWidget(parent),
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setUAS(UASInterface*))); connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setUAS(UASInterface*)));
ui.modeComboBox->clear(); ui.modeComboBox->clear();
ui.modeComboBox->insertItem(MAV_MODE_PREFLIGHT, UAS::getShortModeTextFor(MAV_MODE_PREFLIGHT)); ui.modeComboBox->insertItem(0, UAS::getShortModeTextFor(MAV_MODE_PREFLIGHT), MAV_MODE_PREFLIGHT);
ui.modeComboBox->insertItem(MAV_MODE_STABILIZE_ARMED, UAS::getShortModeTextFor(MAV_MODE_STABILIZE_ARMED)); ui.modeComboBox->insertItem(1, UAS::getShortModeTextFor((MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED)), (MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED));
ui.modeComboBox->insertItem(MAV_MODE_MANUAL_ARMED, UAS::getShortModeTextFor(MAV_MODE_MANUAL_ARMED)); ui.modeComboBox->insertItem(2, UAS::getShortModeTextFor(MAV_MODE_FLAG_MANUAL_INPUT_ENABLED), MAV_MODE_FLAG_MANUAL_INPUT_ENABLED);
ui.modeComboBox->insertItem(MAV_MODE_GUIDED_DISARMED, UAS::getShortModeTextFor(MAV_MODE_GUIDED_ARMED)); ui.modeComboBox->insertItem(3, UAS::getShortModeTextFor((MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED)), (MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED));
ui.modeComboBox->insertItem(MAV_MODE_AUTO_ARMED, UAS::getShortModeTextFor(MAV_MODE_AUTO_ARMED)); ui.modeComboBox->insertItem(4, UAS::getShortModeTextFor((MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED)), (MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED | MAV_MODE_FLAG_AUTO_ENABLED));
ui.modeComboBox->insertItem(MAV_MODE_TEST_ARMED, UAS::getShortModeTextFor(MAV_MODE_TEST_ARMED)); ui.modeComboBox->insertItem(5, UAS::getShortModeTextFor((MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_TEST_ENABLED)), (MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_TEST_ENABLED));
connect(ui.modeComboBox, SIGNAL(activated(int)), this, SLOT(setMode(int))); connect(ui.modeComboBox, SIGNAL(activated(int)), this, SLOT(setMode(int)));
connect(ui.setModeButton, SIGNAL(clicked()), this, SLOT(transmitMode())); connect(ui.setModeButton, SIGNAL(clicked()), this, SLOT(transmitMode()));
...@@ -157,7 +157,7 @@ void UASControlWidget::updateState(int state) ...@@ -157,7 +157,7 @@ void UASControlWidget::updateState(int state)
void UASControlWidget::setMode(int mode) void UASControlWidget::setMode(int mode)
{ {
// Adapt context button mode // Adapt context button mode
uasMode = mode; uasMode = ui.modeComboBox->itemData(mode).toInt();
ui.modeComboBox->blockSignals(true); ui.modeComboBox->blockSignals(true);
ui.modeComboBox->setCurrentIndex(mode); ui.modeComboBox->setCurrentIndex(mode);
ui.modeComboBox->blockSignals(false); ui.modeComboBox->blockSignals(false);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment