Commit 71369792 authored by lm's avatar lm

Fixes to Google Earth, guarded a PIXHAWK message with correct include guards

parent 6fcdce98
...@@ -36,6 +36,7 @@ var currViewRange = 50.0; ///<< The current viewing range from this position (in ...@@ -36,6 +36,7 @@ var currViewRange = 50.0; ///<< The current viewing range from this position (in
var currTilt = 40.0; ///<< The tilt angle (in degrees) var currTilt = 40.0; ///<< The tilt angle (in degrees)
var currFollowTilt = 40.0; var currFollowTilt = 40.0;
var currView = null; var currView = null;
var distanceMode = 0;
var viewMode = 0; var viewMode = 0;
var lastTilt = 0; var lastTilt = 0;
...@@ -94,6 +95,11 @@ function getDraggingAllowed() ...@@ -94,6 +95,11 @@ function getDraggingAllowed()
return draggingAllowed; return draggingAllowed;
} }
function setDistanceMode(mode)
{
distanceMode = mode;
}
function setDraggingAllowed(allowed) function setDraggingAllowed(allowed)
{ {
draggingAllowed = allowed; draggingAllowed = allowed;
......
...@@ -210,9 +210,9 @@ void Waypoint::setCurrent(bool current) ...@@ -210,9 +210,9 @@ void Waypoint::setCurrent(bool current)
void Waypoint::setAcceptanceRadius(double radius) void Waypoint::setAcceptanceRadius(double radius)
{ {
if (this->param1 != radius) if (this->param2 != radius)
{ {
this->param1 = radius; this->param2 = radius;
emit changed(this); emit changed(this);
} }
} }
...@@ -291,9 +291,9 @@ void Waypoint::setLoiterOrbit(double orbit) ...@@ -291,9 +291,9 @@ void Waypoint::setLoiterOrbit(double orbit)
void Waypoint::setHoldTime(int holdTime) void Waypoint::setHoldTime(int holdTime)
{ {
if (this->param2 != holdTime) if (this->param1 != holdTime)
{ {
this->param2 = holdTime; this->param1 = holdTime;
emit changed(this); emit changed(this);
} }
} }
......
...@@ -59,8 +59,8 @@ public: ...@@ -59,8 +59,8 @@ public:
bool getAutoContinue() const { return autocontinue; } bool getAutoContinue() const { return autocontinue; }
bool getCurrent() const { return current; } bool getCurrent() const { return current; }
double getLoiterOrbit() const { return orbit; } double getLoiterOrbit() const { return orbit; }
double getAcceptanceRadius() const { return param1; } double getAcceptanceRadius() const { return param2; }
double getHoldTime() const { return param2; } double getHoldTime() const { return param1; }
double getParam1() const { return param1; } double getParam1() const { return param1; }
double getParam2() const { return param2; } double getParam2() const { return param2; }
double getParam3() const { return orbit; } double getParam3() const { return orbit; }
......
...@@ -1001,9 +1001,8 @@ bool MAVLinkSimulationLink::connect() ...@@ -1001,9 +1001,8 @@ bool MAVLinkSimulationLink::connect()
start(LowPriority); start(LowPriority);
MAVLinkSimulationMAV* mav1 = new MAVLinkSimulationMAV(this, 1, 47.376, 8.548); MAVLinkSimulationMAV* mav1 = new MAVLinkSimulationMAV(this, 1, 47.376, 8.548);
Q_UNUSED(mav1); Q_UNUSED(mav1);
//MAVLinkSimulationMAV* mav2 = new MAVLinkSimulationMAV(this, 2); // MAVLinkSimulationMAV* mav2 = new MAVLinkSimulationMAV(this, 2, 47.375, 8.548, 1);
// // Q_UNUSED(mav2);
//Q_UNUSED(mav2);
// timer->start(rate); // timer->start(rate);
return true; return true;
} }
......
...@@ -4,7 +4,7 @@ ...@@ -4,7 +4,7 @@
#include "MAVLinkSimulationMAV.h" #include "MAVLinkSimulationMAV.h"
MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int systemid, double lat, double lon) : MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int systemid, double lat, double lon, int version) :
QObject(parent), QObject(parent),
link(parent), link(parent),
planner(parent, systemid), planner(parent, systemid),
...@@ -34,7 +34,8 @@ MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int sy ...@@ -34,7 +34,8 @@ MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int sy
sys_mode(MAV_MODE_READY), sys_mode(MAV_MODE_READY),
sys_state(MAV_STATE_STANDBY), sys_state(MAV_STATE_STANDBY),
nav_mode(MAV_NAV_GROUNDED), nav_mode(MAV_NAV_GROUNDED),
flying(false) flying(false),
mavlink_version(version)
{ {
// Please note: The waypoint planner is running // Please note: The waypoint planner is running
connect(&mainloopTimer, SIGNAL(timeout()), this, SLOT(mainloop())); connect(&mainloopTimer, SIGNAL(timeout()), this, SLOT(mainloop()));
...@@ -62,7 +63,7 @@ void MAVLinkSimulationMAV::mainloop() ...@@ -62,7 +63,7 @@ void MAVLinkSimulationMAV::mainloop()
if (timer1Hz <= 0) if (timer1Hz <= 0)
{ {
mavlink_message_t msg; mavlink_message_t msg;
mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK); mavlink_msg_heartbeat_pack_version_free(systemid, MAV_COMP_ID_IMU, &msg, MAV_FIXED_WING, MAV_AUTOPILOT_PIXHAWK, mavlink_version);
link->sendMAVLinkMessage(&msg); link->sendMAVLinkMessage(&msg);
planner.handleMessage(msg); planner.handleMessage(msg);
......
...@@ -11,7 +11,7 @@ class MAVLinkSimulationMAV : public QObject ...@@ -11,7 +11,7 @@ class MAVLinkSimulationMAV : public QObject
{ {
Q_OBJECT Q_OBJECT
public: public:
explicit MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int systemid, double lat=47.376389, double lon=8.548056); explicit MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int systemid, double lat=47.376389, double lon=8.548056, int version=MAVLINK_VERSION);
signals: signals:
...@@ -53,6 +53,19 @@ protected: ...@@ -53,6 +53,19 @@ protected:
uint8_t sys_state; uint8_t sys_state;
uint8_t nav_mode; uint8_t nav_mode;
bool flying; bool flying;
int mavlink_version;
static inline uint16_t mavlink_msg_heartbeat_pack_version_free(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint8_t type, uint8_t autopilot, uint8_t version)
{
uint16_t i = 0;
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
i += put_uint8_t_by_index(type, i, msg->payload); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
i += put_uint8_t_by_index(autopilot, i, msg->payload); // Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
i += put_uint8_t_by_index(version, i, msg->payload); // MAVLink version
return mavlink_finalize_message(msg, system_id, component_id, i);
}
}; };
......
...@@ -894,7 +894,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -894,7 +894,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit textMessageReceived(uasId, message.compid, severity, text); emit textMessageReceived(uasId, message.compid, severity, text);
} }
break; break;
#ifdef MAVLINK_ENABLED_PIXHAWK
case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE: case MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE:
{ {
qDebug() << "RECIEVED ACK TO GET IMAGE"; qDebug() << "RECIEVED ACK TO GET IMAGE";
...@@ -939,7 +939,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -939,7 +939,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
} }
} }
break; break;
#endif
case MAVLINK_MSG_ID_DEBUG_VECT: case MAVLINK_MSG_ID_DEBUG_VECT:
{ {
mavlink_debug_vect_t vect; mavlink_debug_vect_t vect;
...@@ -1363,6 +1363,7 @@ QImage UAS::getImage() ...@@ -1363,6 +1363,7 @@ QImage UAS::getImage()
void UAS::requestImage() void UAS::requestImage()
{ {
#ifdef MAVLINK_ENABLED_PIXHAWK
qDebug() << "trying to get an image from the uas..."; qDebug() << "trying to get an image from the uas...";
if (imagePacketsArrived == 0) if (imagePacketsArrived == 0)
...@@ -1371,7 +1372,7 @@ void UAS::requestImage() ...@@ -1371,7 +1372,7 @@ void UAS::requestImage()
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, 50);
sendMessage(msg); sendMessage(msg);
} }
else if (MG::TIME::getGroundTimeNow() - imageStart >= 1000) else if (QGC::groundTimeMilliseconds() - imageStart >= 1000)
{ {
// handshake happened more than 1 second ago, packets should have arrived by now // handshake happened more than 1 second ago, packets should have arrived by now
// maybe we missed some packets (dropped along the way) // maybe we missed some packets (dropped along the way)
...@@ -1380,6 +1381,7 @@ void UAS::requestImage() ...@@ -1380,6 +1381,7 @@ void UAS::requestImage()
// Restart statemachine // Restart statemachine
imagePacketsArrived = 0; imagePacketsArrived = 0;
} }
#endif
// default else, wait? // default else, wait?
} }
......
...@@ -33,9 +33,14 @@ MapWidget::MapWidget(QWidget *parent) : ...@@ -33,9 +33,14 @@ MapWidget::MapWidget(QWidget *parent) :
uasTrails(), uasTrails(),
mav(NULL), mav(NULL),
lastUpdate(0), lastUpdate(0),
initialized(false),
m_ui(new Ui::MapWidget) m_ui(new Ui::MapWidget)
{ {
m_ui->setupUi(this); m_ui->setupUi(this);
}
void MapWidget::init()
{
mc = new qmapcontrol::MapControl(this->size()); mc = new qmapcontrol::MapControl(this->size());
// VISUAL MAP STYLE // VISUAL MAP STYLE
...@@ -268,6 +273,9 @@ MapWidget::MapWidget(QWidget *parent) : ...@@ -268,6 +273,9 @@ MapWidget::MapWidget(QWidget *parent) :
drawCamBorder = false; drawCamBorder = false;
radioCamera = 10; radioCamera = 10;
// Done set state
initialized = true;
} }
void MapWidget::goTo() void MapWidget::goTo()
...@@ -1013,6 +1021,8 @@ void MapWidget::hideEvent(QHideEvent* event) ...@@ -1013,6 +1021,8 @@ void MapWidget::hideEvent(QHideEvent* event)
settings.setValue("LAST_ZOOM", mc->currentZoom()); settings.setValue("LAST_ZOOM", mc->currentZoom());
settings.endGroup(); settings.endGroup();
settings.sync(); settings.sync();
if (!initialized) init();
} }
......
...@@ -146,6 +146,10 @@ protected: ...@@ -146,6 +146,10 @@ protected:
//QMap<int, qmapcontrol::LineString*> waypointPaths; //QMap<int, qmapcontrol::LineString*> waypointPaths;
UASInterface* mav; UASInterface* mav;
quint64 lastUpdate; quint64 lastUpdate;
bool initialized;
/** @brief Initialize view */
void init();
protected slots: protected slots:
void captureMapClick (const QMouseEvent* event, const QPointF coordinate); void captureMapClick (const QMouseEvent* event, const QPointF coordinate);
......
...@@ -97,6 +97,7 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) : ...@@ -97,6 +97,7 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
connect(m_ui->acceptanceSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setAcceptanceRadius(double))); connect(m_ui->acceptanceSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setAcceptanceRadius(double)));
connect(m_ui->holdTimeSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setHoldTime(int))); connect(m_ui->holdTimeSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setHoldTime(int)));
connect(m_ui->turnsSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setTurns(int))); connect(m_ui->turnsSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setTurns(int)));
connect(m_ui->takeOffAngleSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam1(double)));
// Connect actions // Connect actions
connect(customCommand->commandSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setAction(int))); connect(customCommand->commandSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setAction(int)));
...@@ -246,8 +247,6 @@ void WaypointView::changedAction(int index) ...@@ -246,8 +247,6 @@ void WaypointView::changedAction(int index)
case MAV_CMD_NAV_LOITER_UNLIM: case MAV_CMD_NAV_LOITER_UNLIM:
case MAV_CMD_NAV_LOITER_TURNS: case MAV_CMD_NAV_LOITER_TURNS:
case MAV_CMD_NAV_LOITER_TIME: case MAV_CMD_NAV_LOITER_TIME:
case MAV_CMD_CONDITION_DELAY:
case MAV_CMD_DO_SET_MODE:
changeViewMode(QGC_WAYPOINTVIEW_MODE_NAV); changeViewMode(QGC_WAYPOINTVIEW_MODE_NAV);
// Update frame view // Update frame view
updateFrameView(m_ui->comboBox_frame->currentIndex()); updateFrameView(m_ui->comboBox_frame->currentIndex());
...@@ -434,9 +433,14 @@ void WaypointView::updateValues() ...@@ -434,9 +433,14 @@ void WaypointView::updateValues()
// Only update if changed // Only update if changed
if (m_ui->comboBox_action->currentIndex() != action_index) if (m_ui->comboBox_action->currentIndex() != action_index)
{ {
// TODO Action and frame should not be coupled // If action is unknown, set direct editing mode
if (wp->getFrame() != MAV_FRAME_MISSION) if (wp->getAction() < 0 || wp->getAction() > MAV_CMD_NAV_TAKEOFF)
{ {
changeViewMode(QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING);
}
else
{
// Action ID known, update
m_ui->comboBox_action->setCurrentIndex(action_index); m_ui->comboBox_action->setCurrentIndex(action_index);
updateActionView(action); updateActionView(action);
} }
...@@ -480,6 +484,14 @@ void WaypointView::updateValues() ...@@ -480,6 +484,14 @@ void WaypointView::updateValues()
{ {
m_ui->holdTimeSpinBox->setValue(wp->getHoldTime()); m_ui->holdTimeSpinBox->setValue(wp->getHoldTime());
} }
if (m_ui->turnsSpinBox->value() != wp->getTurns())
{
m_ui->turnsSpinBox->setValue(wp->getTurns());
}
if (m_ui->takeOffAngleSpinBox->value() != wp->getParam1())
{
m_ui->takeOffAngleSpinBox->setValue(wp->getParam1());
}
// UPDATE CUSTOM ACTION WIDGET // UPDATE CUSTOM ACTION WIDGET
......
...@@ -121,6 +121,11 @@ void QGCGoogleEarthView::reloadHTML() ...@@ -121,6 +121,11 @@ void QGCGoogleEarthView::reloadHTML()
show(); show();
} }
void QGCGoogleEarthView::enableEditMode(bool mode)
{
javaScript(QString("setDraggingAllowed(%1);").arg(mode));
}
/** /**
* @param range in meters (SI-units) * @param range in meters (SI-units)
*/ */
...@@ -129,6 +134,11 @@ void QGCGoogleEarthView::setViewRange(float range) ...@@ -129,6 +134,11 @@ void QGCGoogleEarthView::setViewRange(float range)
javaScript(QString("setViewRange(%1);").arg(range, 0, 'f', 5)); javaScript(QString("setViewRange(%1);").arg(range, 0, 'f', 5));
} }
void QGCGoogleEarthView::setDistanceMode(int mode)
{
javaScript(QString("setDistanceMode(%1);").arg(mode));
}
void QGCGoogleEarthView::toggleViewMode() void QGCGoogleEarthView::toggleViewMode()
{ {
switch (currentViewMode) switch (currentViewMode)
...@@ -469,26 +479,31 @@ void QGCGoogleEarthView::initializeGoogleEarth() ...@@ -469,26 +479,31 @@ void QGCGoogleEarthView::initializeGoogleEarth()
setActiveUAS(UASManager::instance()->getActiveUAS()); setActiveUAS(UASManager::instance()->getActiveUAS());
// Add any further MAV automatically // Add any further MAV automatically
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*))); connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*)), Qt::UniqueConnection);
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)), Qt::UniqueConnection);
// Connect UI signals/slots // Connect UI signals/slots
// Follow checkbox // Follow checkbox
ui->followAirplaneCheckbox->setChecked(followCamera); ui->followAirplaneCheckbox->setChecked(followCamera);
connect(ui->followAirplaneCheckbox, SIGNAL(toggled(bool)), this, SLOT(follow(bool))); connect(ui->followAirplaneCheckbox, SIGNAL(toggled(bool)), this, SLOT(follow(bool)), Qt::UniqueConnection);
// Trail checkbox // Trail checkbox
ui->trailCheckbox->setChecked(trailEnabled); ui->trailCheckbox->setChecked(trailEnabled);
connect(ui->trailCheckbox, SIGNAL(toggled(bool)), this, SLOT(showTrail(bool))); connect(ui->trailCheckbox, SIGNAL(toggled(bool)), this, SLOT(showTrail(bool)), Qt::UniqueConnection);
// Go home // Go home
connect(ui->goHomeButton, SIGNAL(clicked()), this, SLOT(goHome())); connect(ui->goHomeButton, SIGNAL(clicked()), this, SLOT(goHome()));
// Cam distance slider // Cam distance slider
connect(ui->camDistanceSlider, SIGNAL(valueChanged(int)), this, SLOT(setViewRangeScaledInt(int))); connect(ui->camDistanceSlider, SIGNAL(valueChanged(int)), this, SLOT(setViewRangeScaledInt(int)), Qt::UniqueConnection);
setViewRangeScaledInt(ui->camDistanceSlider->value()); setViewRangeScaledInt(ui->camDistanceSlider->value());
// Distance combo box
connect(ui->camDistanceComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(setDistanceMode(int)), Qt::UniqueConnection);
// Edit mode button
connect(ui->editButton, SIGNAL(clicked(bool)), this, SLOT(enableEditMode(bool)), Qt::UniqueConnection);
// Update waypoint list // Update waypoint list
if (mav) updateWaypointList(mav->getUASID()); if (mav) updateWaypointList(mav->getUASID());
...@@ -497,7 +512,8 @@ void QGCGoogleEarthView::initializeGoogleEarth() ...@@ -497,7 +512,8 @@ void QGCGoogleEarthView::initializeGoogleEarth()
// Set current view mode // Set current view mode
setViewMode(currentViewMode); setViewMode(currentViewMode);
setDistanceMode(ui->camDistanceComboBox->currentIndex());
enableEditMode(ui->editButton->isChecked());
follow(this->followCamera); follow(this->followCamera);
gEarthInitialized = true; gEarthInitialized = true;
......
...@@ -102,8 +102,12 @@ public slots: ...@@ -102,8 +102,12 @@ public slots:
void goHome(); void goHome();
/** @brief Set the home location */ /** @brief Set the home location */
void setHome(double lat, double lon, double alt); void setHome(double lat, double lon, double alt);
/** @brief Allow waypoint editing */
void enableEditMode(bool mode);
/** @brief Set camera view range to aircraft in meters */ /** @brief Set camera view range to aircraft in meters */
void setViewRange(float range); void setViewRange(float range);
/** @brief Set the distance mode - either to ground or to MAV */
void setDistanceMode(int mode);
/** @brief Set the view mode */ /** @brief Set the view mode */
void setViewMode(VIEW_MODE mode); void setViewMode(VIEW_MODE mode);
/** @brief Toggle through the different view modes */ /** @brief Toggle through the different view modes */
......
...@@ -13,7 +13,7 @@ ...@@ -13,7 +13,7 @@
<property name="windowTitle"> <property name="windowTitle">
<string>Form</string> <string>Form</string>
</property> </property>
<layout class="QGridLayout" name="gridLayout"> <layout class="QGridLayout" name="gridLayout" columnstretch="1,1,1,1,1,1,30,1,100,1,1,1,1,1,1">
<property name="horizontalSpacing"> <property name="horizontalSpacing">
<number>8</number> <number>8</number>
</property> </property>
...@@ -23,7 +23,7 @@ ...@@ -23,7 +23,7 @@
<property name="margin"> <property name="margin">
<number>2</number> <number>2</number>
</property> </property>
<item row="0" column="0" colspan="14"> <item row="0" column="0" colspan="15">
<layout class="QVBoxLayout" name="webViewLayout"/> <layout class="QVBoxLayout" name="webViewLayout"/>
</item> </item>
<item row="1" column="1"> <item row="1" column="1">
...@@ -58,7 +58,7 @@ ...@@ -58,7 +58,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="13"> <item row="1" column="14">
<spacer name="horizontalSpacer"> <spacer name="horizontalSpacer">
<property name="orientation"> <property name="orientation">
<enum>Qt::Horizontal</enum> <enum>Qt::Horizontal</enum>
...@@ -71,7 +71,7 @@ ...@@ -71,7 +71,7 @@
</property> </property>
</spacer> </spacer>
</item> </item>
<item row="1" column="9"> <item row="1" column="8">
<widget class="QSlider" name="camDistanceSlider"> <widget class="QSlider" name="camDistanceSlider">
<property name="toolTip"> <property name="toolTip">
<string>Distance of the chase camera to the MAV</string> <string>Distance of the chase camera to the MAV</string>
...@@ -96,22 +96,6 @@ ...@@ -96,22 +96,6 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="8">
<widget class="QLabel" name="camDistanceLabel">
<property name="toolTip">
<string>Distance of the chase camera to the MAV</string>
</property>
<property name="statusTip">
<string>Distance of the chase camera to the MAV</string>
</property>
<property name="whatsThis">
<string>Distance of the chase camera to the MAV</string>
</property>
<property name="text">
<string>Dist</string>
</property>
</widget>
</item>
<item row="1" column="4"> <item row="1" column="4">
<widget class="QCheckBox" name="waypointsCheckbox"> <widget class="QCheckBox" name="waypointsCheckbox">
<property name="toolTip"> <property name="toolTip">
...@@ -128,7 +112,7 @@ ...@@ -128,7 +112,7 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="10"> <item row="1" column="9">
<widget class="QCheckBox" name="followAirplaneCheckbox"> <widget class="QCheckBox" name="followAirplaneCheckbox">
<property name="toolTip"> <property name="toolTip">
<string>Chase the MAV</string> <string>Chase the MAV</string>
...@@ -145,7 +129,7 @@ ...@@ -145,7 +129,7 @@
</widget> </widget>
</item> </item>
<item row="1" column="6"> <item row="1" column="6">
<widget class="QComboBox" name="mavComboBox"> <widget class="QComboBox" name="camDistanceComboBox">
<property name="toolTip"> <property name="toolTip">
<string>Select the MAV to chase</string> <string>Select the MAV to chase</string>
</property> </property>
...@@ -155,9 +139,40 @@ ...@@ -155,9 +139,40 @@
<property name="whatsThis"> <property name="whatsThis">
<string>Select the MAV to chase</string> <string>Select the MAV to chase</string>
</property> </property>
<item>
<property name="text">
<string>Ground Distance</string>
</property>
</item>
<item>
<property name="text">
<string>MAV Distance</string>
</property>
</item>
</widget>
</item>
<item row="1" column="5">
<widget class="Line" name="line">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
</widget> </widget>
</item> </item>
<item row="1" column="7"> <item row="1" column="13">
<widget class="QPushButton" name="resetButton">
<property name="text">
<string>Reset</string>
</property>
</widget>
</item>
<item row="1" column="10">
<widget class="QPushButton" name="changeViewButton">
<property name="text">
<string>Overhead</string>
</property>
</widget>
</item>
<item row="1" column="12">
<widget class="QPushButton" name="clearTrailsButton"> <widget class="QPushButton" name="clearTrailsButton">
<property name="toolTip"> <property name="toolTip">
<string>Delete all waypoints</string> <string>Delete all waypoints</string>
...@@ -173,24 +188,26 @@ ...@@ -173,24 +188,26 @@
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="5"> <item row="1" column="11">
<widget class="Line" name="line"> <widget class="Line" name="line_2">
<property name="orientation"> <property name="orientation">
<enum>Qt::Vertical</enum> <enum>Qt::Vertical</enum>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="12"> <item row="1" column="2">
<widget class="QPushButton" name="resetButton"> <widget class="QPushButton" name="editButton">
<property name="text"> <property name="toolTip">
<string>Reset</string> <string>Enable waypoint and home location edit mode</string>
</property>
<property name="statusTip">
<string>Enable waypoint and home location edit mode</string>
</property> </property>
</widget>
</item>
<item row="1" column="11">
<widget class="QPushButton" name="changeViewButton">
<property name="text"> <property name="text">
<string>Overhead</string> <string>Edit</string>
</property>
<property name="checkable">
<bool>true</bool>
</property> </property>
</widget> </widget>
</item> </item>
......
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