Commit 52230a20 authored by lm's avatar lm

Fixed debug console, fixed nav mode, fixed WP interface

parent 9c6775fb
......@@ -993,8 +993,9 @@ bool MAVLinkSimulationLink::connect()
start(LowPriority);
MAVLinkSimulationMAV* mav1 = new MAVLinkSimulationMAV(this, 1, 47.376, 8.548);
//MAVLinkSimulationMAV* mav2 = new MAVLinkSimulationMAV(this, 2);
Q_UNUSED(mav1);
//MAVLinkSimulationMAV* mav2 = new MAVLinkSimulationMAV(this, 2);
//
//Q_UNUSED(mav2);
// timer->start(rate);
return true;
......
......@@ -323,6 +323,7 @@ void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg)
{
case MAV_ACTION_TAKEOFF:
flying = true;
nav_mode = MAV_NAV_LIFTOFF;
ack.result = 1;
break;
default:
......@@ -345,6 +346,7 @@ void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg)
mavlink_msg_local_position_setpoint_set_decode(&msg, &sp);
if (sp.target_system == this->systemid)
{
nav_mode = MAV_NAV_WAYPOINT;
previousSPX = nextSPX;
previousSPY = nextSPY;
previousSPZ = nextSPZ;
......
......@@ -143,7 +143,7 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit errCountChanged(uasId, "IMU", "SPI0", status.spi0_err_count);
emit errCountChanged(uasId, "IMU", "SPI1", status.spi1_err_count);
emit errCountChanged(uasId, "IMU", "UART", status.uart_total_err_count);
emit valueChanged(uasId, "Load", "%", ((float)status.load)/1000.0f, MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "Load", "%", ((float)status.load)/10.0f, getUnixTime());
}
break;
default:
......
......@@ -45,8 +45,9 @@ warnLevelPercent(20.0f),
currentVoltage(12.0f),
lpVoltage(12.0f),
batteryRemainingEstimateEnabled(false),
mode(MAV_MODE_UNINIT),
status(MAV_STATE_UNINIT),
mode(-1),
status(-1),
navMode(-1),
onboardTimeOffset(0),
controlRollManual(true),
controlPitchManual(true),
......@@ -252,20 +253,26 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if (state.status != this->status)
{
statechanged = true;
this->status = (int)state.status;
this->status = state.status;
getStatusForCode((int)state.status, uasState, stateDescription);
emit statusChanged(this, uasState, stateDescription);
emit statusChanged(this->status);
stateAudio = " changed status to " + uasState;
}
if (navMode != state.nav_mode)
{
emit navModeChanged(uasId, state.nav_mode, getNavModeText(state.nav_mode));
navMode = state.nav_mode;
}
emit loadChanged(this,state.load/10.0f);
emit valueChanged(uasId, "Load", "%", ((float)state.load)/10.0f, getUnixTime());
if (this->mode != static_cast<unsigned int>(state.mode))
if (this->mode != static_cast<int>(state.mode))
{
modechanged = true;
this->mode = static_cast<unsigned int>(state.mode);
this->mode = static_cast<int>(state.mode);
QString mode;
switch (state.mode)
......@@ -537,7 +544,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "altitude", "m", altitude, time);
double totalSpeed = sqrt(speedX*speedX + speedY*speedY + speedZ*speedZ);
emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time);
emit globalPositionChanged(this, longitude, latitude, altitude, time);
emit globalPositionChanged(this, latitude, longitude, altitude, time);
emit speedChanged(this, speedX, speedY, speedZ, time);
// Set internal state
if (!positionLock)
......@@ -566,7 +573,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "altitude", "m", altitude, time);
double totalSpeed = sqrt(speedX*speedX + speedY*speedY + speedZ*speedZ);
emit valueChanged(uasId, "gps speed", "m/s", totalSpeed, time);
emit globalPositionChanged(this, longitude, latitude, altitude, time);
emit globalPositionChanged(this, latitude, longitude, altitude, time);
emit speedChanged(this, speedX, speedY, speedZ, time);
// Set internal state
if (!positionLock)
......@@ -596,7 +603,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
if (pos.fix_type > 0)
{
emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
emit globalPositionChanged(this, pos.lat, pos.lon, pos.alt, time);
emit valueChanged(uasId, "gps speed", "m/s", pos.v, time);
// Check for NaN
......@@ -790,7 +797,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_waypoint_reached_t wpr;
mavlink_msg_waypoint_reached_decode(&message, &wpr);
waypointManager.handleWaypointReached(message.sysid, message.compid, &wpr);
GAudioOutput::instance()->say(QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq));
QString text = QString("System %1 reached waypoint %2").arg(getUASName()).arg(wpr.seq);
GAudioOutput::instance()->say(text);
emit textMessageReceived(message.sysid, message.compid, 0, text);
}
break;
......@@ -1167,45 +1176,81 @@ float UAS::filterVoltage(float value) const
return lpVoltage * 0.7f + value * 0.3f;
}
QString UAS::getNavModeText(int mode)
{
switch (mode)
{
case MAV_NAV_GROUNDED:
return QString("GROUNDED");
break;
case MAV_NAV_HOLD:
return QString("HOLD");
break;
case MAV_NAV_LANDING:
return QString("LANDING");
break;
case MAV_NAV_LIFTOFF:
return QString("LIFTOFF");
break;
case MAV_NAV_LOITER:
return QString("LOITER");
break;
case MAV_NAV_LOST:
return QString("LOST");
break;
case MAV_NAV_RETURNING:
return QString("RETURNING");
break;
case MAV_NAV_VECTOR:
return QString("VECTOR");
break;
case MAV_NAV_WAYPOINT:
return QString("WAYPOINT");
break;
default:
return QString("UNKNOWN");
}
}
void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDescription)
{
switch (statusCode)
{
case MAV_STATE_UNINIT:
uasState = tr("UNINIT");
stateDescription = tr("Waiting..");
stateDescription = tr("Unitialized, booting up.");
break;
case MAV_STATE_BOOT:
uasState = tr("BOOT");
stateDescription = tr("Booting..");
stateDescription = tr("Booting system, please wait.");
break;
case MAV_STATE_CALIBRATING:
uasState = tr("CALIBRATING");
stateDescription = tr("Calibrating..");
stateDescription = tr("Calibrating sensors, please wait.");
break;
case MAV_STATE_ACTIVE:
uasState = tr("ACTIVE");
stateDescription = tr("Normal");
stateDescription = tr("Active, normal operation.");
break;
case MAV_STATE_STANDBY:
uasState = tr("STANDBY");
stateDescription = tr("Standby, OK");
stateDescription = tr("Standby mode, ready for liftoff.");
break;
case MAV_STATE_CRITICAL:
uasState = tr("CRITICAL");
stateDescription = tr("FAILURE: Continue");
stateDescription = tr("FAILURE: Continuing operation.");
break;
case MAV_STATE_EMERGENCY:
uasState = tr("EMERGENCY");
stateDescription = tr("EMERGENCY: Land!");
stateDescription = tr("EMERGENCY: Land Immediately!");
break;
case MAV_STATE_POWEROFF:
uasState = tr("SHUTDOWN");
stateDescription = tr("Powering off");
stateDescription = tr("Powering off system.");
break;
default:
uasState = tr("UNKNOWN");
stateDescription = tr("Unknown state");
stateDescription = tr("Unknown system state");
break;
}
}
......
......@@ -130,8 +130,9 @@ protected: //COMMENTS FOR TEST UNIT
bool batteryRemainingEstimateEnabled; ///< If the estimate is enabled, QGC will try to estimate the remaining battery life
float chargeLevel; ///< Charge level of battery, in percent
int timeRemaining; ///< Remaining time calculated based on previous and current
unsigned int mode; ///< The current mode of the MAV
int mode; ///< The current mode of the MAV
int status; ///< The current status of the MAV
int navMode; ///< The current navigation mode of the MAV
quint64 onboardTimeOffset;
bool controlRollManual; ///< status flag, true if roll is controlled manually
......@@ -173,6 +174,8 @@ public:
float getChargeLevel();
/** @brief Get the human-readable status message for this code */
void getStatusForCode(int statusCode, QString& uasState, QString& stateDescription);
/** @brief Get the human-readable navigation mode translation for this mode */
QString getNavModeText(int mode);
/** @brief Check if vehicle is in autonomous mode */
bool isAuto();
......
......@@ -306,7 +306,11 @@ signals:
void poiFound(UASInterface* uas, int type, int colorIndex, QString message, float x, float y, float z);
void poiConnectionFound(UASInterface* uas, int type, int colorIndex, QString message, float x1, float y1, float z1, float x2, float y2, float z2);
/** @brief A text message from the system has been received */
void textMessageReceived(int uasid, int componentid, int severity, QString text);
void navModeChanged(int uasid, int mode, const QString& text);
/**
* @brief Update the error count of a device
*
......
......@@ -236,6 +236,7 @@ void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, m
{
if (systemId == uas.getUASID() && compId == MAV_COMP_ID_WAYPOINTPLANNER)
{
// FIXME Petri
if (current_state == WP_SETCURRENT)
{
protocol_timer.stop();
......@@ -257,10 +258,11 @@ void UASWaypointManager::handleWaypointCurrent(quint8 systemId, quint8 compId, m
}
}
emit updateStatusString(QString("New current waypoint %1").arg(wpc->seq));
//emit update to UI widgets
emit currentWaypointChanged(wpc->seq);
qDebug() << "Updated waypoints list";
}
emit updateStatusString(QString("New current waypoint %1").arg(wpc->seq));
//emit update to UI widgets
emit currentWaypointChanged(wpc->seq);
qDebug() << "new current waypoint" << wpc->seq;
}
}
......
......@@ -67,7 +67,7 @@ DebugConsole::DebugConsole(QWidget *parent) :
// Hide sent text field - it is only useful after send has been hit
m_ui->sentText->setVisible(false);
// Hide auto-send checkbox
m_ui->specialCheckBox->setVisible(false);
//m_ui->specialCheckBox->setVisible(false);
// Make text area not editable
m_ui->receiveText->setReadOnly(true);
// Limit to 500 lines
......@@ -116,7 +116,7 @@ DebugConsole::DebugConsole(QWidget *parent) :
// Connect Checkbox
connect(m_ui->specialComboBox, SIGNAL(highlighted(QString)), this, SLOT(specialSymbolSelected(QString)));
// Set add button invisible if auto add checkbox is checked
connect(m_ui->specialCheckBox, SIGNAL(clicked(bool)), m_ui->addSymbolButton, SLOT(setHidden(bool)));
//connect(m_ui->specialCheckBox, SIGNAL(clicked(bool)), m_ui->addSymbolButton, SLOT(setHidden(bool)));
// Allow to send via return
connect(m_ui->sendText, SIGNAL(returnPressed()), this, SLOT(sendBytes()));
......@@ -129,6 +129,12 @@ DebugConsole::DebugConsole(QWidget *parent) :
}
}
void DebugConsole::hideEvent(QHideEvent* event)
{
Q_UNUSED(event);
storeSettings();
}
DebugConsole::~DebugConsole()
{
storeSettings();
......@@ -148,12 +154,12 @@ void DebugConsole::loadSettings()
setAutoHold(settings.value("AUTO_HOLD_ENABLED", autoHold).toBool());
settings.endGroup();
// Update visibility settings
if (m_ui->specialCheckBox->isChecked())
{
m_ui->specialCheckBox->setVisible(true);
m_ui->addSymbolButton->setVisible(false);
}
// // Update visibility settings
// if (m_ui->specialCheckBox->isChecked())
// {
// m_ui->specialCheckBox->setVisible(true);
// m_ui->addSymbolButton->setVisible(false);
// }
}
void DebugConsole::storeSettings()
......@@ -247,9 +253,6 @@ void DebugConsole::setAutoHold(bool hold)
}
// Set new state
autoHold = hold;
// FIXME REMOVE THIS HERE
storeSettings();
}
/**
......@@ -522,7 +525,7 @@ QString DebugConsole::bytesToSymbolNames(const QByteArray& b)
void DebugConsole::specialSymbolSelected(const QString& text)
{
Q_UNUSED(text);
m_ui->specialCheckBox->setVisible(true);
//m_ui->specialCheckBox->setVisible(true);
}
void DebugConsole::appendSpecialSymbol(const QString& text)
......@@ -705,8 +708,6 @@ void DebugConsole::hexModeEnabled(bool mode)
m_ui->sentText->clear();
commandHistory.clear();
}
// FIXME REMOVE THIS HERE
storeSettings();
}
/**
......@@ -723,8 +724,6 @@ void DebugConsole::MAVLINKfilterEnabled(bool filter)
m_ui->mavlinkCheckBox->setChecked(filter);
}
}
// FIXME REMOVE THIS HERE
storeSettings();
}
/**
* @param hold Freeze the input and thus any scrolling
......
......@@ -101,6 +101,7 @@ public slots:
protected:
void changeEvent(QEvent *e);
void hideEvent(QHideEvent* event);
/** @brief Convert a symbol name to the byte representation */
QByteArray symbolNameToBytes(const QString& symbol);
/** @brief Convert a symbol byte to the name */
......
......@@ -323,7 +323,7 @@ void HSIDisplay::renderOverlay()
{
// Position
QString str;
str.sprintf("%05.2f lat %06.2f lon %06.2f alt", lat, lon, alt);
str.sprintf("lat: %05.2f lon: %06.2f alt: %06.2f", lat, lon, alt);
paintText(tr("GPS"), QGC::colorCyan, 2.6f, 2, vheight- 5.0f, &painter);
paintText(str, Qt::white, 2.6f, 10, vheight - 5.0f, &painter);
}
......
......@@ -1309,7 +1309,7 @@ void HUD::drawChangeRateStrip(float xRef, float yRef, float height, float minRat
// Text
QString label;
label.sprintf("< %06.2f", value);
label.sprintf("< %+06.2f", value);
paintText(label, defaultColor, 3.0f, xRef+width/2.0f, yRef+height-((scaledValue - minRate)/(maxRate-minRate))*height - 1.6f, painter);
}
......
......@@ -865,8 +865,8 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
qmapcontrol::Point* p;
QPointF coordinate;
coordinate.setX(lat);
coordinate.setY(lon);
coordinate.setX(lon);
coordinate.setY(lat);
if (!uasIcons.contains(uas->getUASID()))
{
......@@ -901,7 +901,7 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
// if (p)
// {
p = uasIcons.value(uas->getUASID());
p->setCoordinate(QPointF(lat, lon));
p->setCoordinate(QPointF(lon, lat));
//p->setYaw(uas->getYaw());
// }
// Extend trail
......@@ -922,7 +922,7 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
// Sets the view to the interesting area
if (followgps->isChecked())
{
updatePosition(0, lat, lon);
updatePosition(0, lon, lat);
}
else
{
......
......@@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>260</width>
<height>111</height>
<width>360</width>
<height>119</height>
</rect>
</property>
<property name="sizePolicy">
......@@ -56,10 +56,11 @@ QLabel#modeLabel {
QLabel#stateLabel {
font: 12px;
color: #3C7B9E;
}
QLabel#gpsLabel {
font: 8px;
QLabel#navLabel {
font: 12px;
}
QLabel#positionLabel {
......@@ -255,7 +256,7 @@ QMenu::separator {
<property name="title">
<string/>
</property>
<layout class="QGridLayout" name="gridLayout" columnstretch="10,10,1,10,10,10,100,100">
<layout class="QGridLayout" name="gridLayout" columnstretch="1,1,10,10,10,10,80">
<property name="horizontalSpacing">
<number>4</number>
</property>
......@@ -306,23 +307,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="0" column="2" rowspan="8">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::MinimumExpanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>4</width>
<height>88</height>
</size>
</property>
</spacer>
</item>
<item row="0" column="3" colspan="3">
<item row="0" column="2" colspan="3">
<widget class="QLabel" name="nameLabel">
<property name="maximumSize">
<size>
......@@ -349,7 +334,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="0" column="6" colspan="2">
<item row="0" column="5" colspan="2">
<widget class="QLabel" name="modeLabel">
<property name="maximumSize">
<size>
......@@ -366,11 +351,11 @@ QMenu::separator {
</font>
</property>
<property name="text">
<string/>
<string>MODE</string>
</property>
</widget>
</item>
<item row="1" column="3" rowspan="3">
<item row="1" column="2" rowspan="3">
<widget class="QLabel" name="timeRemainingLabel">
<property name="font">
<font>
......@@ -391,7 +376,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="1" column="4" rowspan="3" colspan="2">
<item row="1" column="3" rowspan="3" colspan="2">
<widget class="QLabel" name="timeElapsedLabel">
<property name="font">
<font>
......@@ -412,7 +397,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="3" column="6" rowspan="2" colspan="2">
<item row="3" column="5" rowspan="2" colspan="2">
<widget class="QProgressBar" name="thrustBar">
<property name="font">
<font>
......@@ -430,7 +415,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="4" column="3">
<item row="4" column="2">
<widget class="QLabel" name="groundDistanceLabel">
<property name="font">
<font>
......@@ -451,7 +436,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="4" column="4" colspan="2">
<item row="4" column="3" colspan="2">
<widget class="QLabel" name="speedLabel">
<property name="font">
<font>
......@@ -536,22 +521,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="5" column="3" rowspan="2" colspan="2">
<widget class="QLabel" name="stateLabel">
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>50</weight>
<italic>false</italic>
<bold>false</bold>
</font>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="7" column="3" colspan="2">
<item row="7" column="2">
<widget class="QLabel" name="waypointLabel">
<property name="font">
<font>
......@@ -575,7 +545,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="2" column="6" colspan="2">
<item row="2" column="5" colspan="2">
<widget class="QLabel" name="positionLabel">
<property name="minimumSize">
<size>
......@@ -608,25 +578,7 @@ QMenu::separator {
</property>
</widget>
</item>
<item row="5" column="6" colspan="2">
<widget class="QLabel" name="statusTextLabel">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>12</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
</font>
</property>
<property name="text">
<string/>
</property>
</widget>
</item>
<item row="6" column="5" rowspan="2" colspan="3">
<item row="7" column="3" colspan="4">
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>4</number>
......@@ -791,6 +743,49 @@ QMenu::separator {
</item>
</layout>
</item>
<item row="5" column="2" rowspan="2" colspan="2">
<widget class="QLabel" name="navLabel">
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>50</weight>
<italic>false</italic>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>NAV</string>
</property>
</widget>
</item>
<item row="8" column="0" colspan="7">
<widget class="QLabel" name="statusTextLabel">
<property name="text">
<string>Waiting for first status update..</string>
</property>
</widget>
</item>
<item row="5" column="5">
<widget class="QLabel" name="stateLabel">
<property name="maximumSize">
<size>
<width>16777215</width>
<height>12</height>
</size>
</property>
<property name="font">
<font>
<pointsize>-1</pointsize>
<weight>50</weight>
<italic>false</italic>
<bold>false</bold>
</font>
</property>
<property name="text">
<string>STATE</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
......
......@@ -528,14 +528,9 @@ void WaypointView::updateValues()
void WaypointView::setCurrent(bool state)
{
if (state)
{
m_ui->selectedBox->setCheckState(Qt::Checked);
}
else
{
m_ui->selectedBox->setCheckState(Qt::Unchecked);
}
m_ui->selectedBox->blockSignals(true);
m_ui->selectedBox->setChecked(state);;
m_ui->selectedBox->blockSignals(false);
}
WaypointView::~WaypointView()
......
......@@ -211,7 +211,7 @@ void QGCGoogleEarthView::updateWaypointList(int uas)
}
}
void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec)
void QGCGoogleEarthView::updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec)
{
Q_UNUSED(usec);
javaScript(QString("addTrailPosition(%1, %2, %3, %4);").arg(uas->getUASID()).arg(lat, 0, 'f', 15).arg(lon, 0, 'f', 15).arg(alt, 0, 'f', 15));
......
......@@ -79,7 +79,7 @@ public slots:
/** @brief Set the currently selected UAS */
void setActiveUAS(UASInterface* uas);
/** @brief Update the global position */
void updateGlobalPosition(UASInterface* uas, double lon, double lat, double alt, quint64 usec);
void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec);
/** @brief Update a single waypoint */
void updateWaypoint(int uas, Waypoint* wp);
/** @brief Update the waypoint list */
......
......@@ -89,7 +89,9 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
connect(uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointUpdated(quint16)));
connect(uas, SIGNAL(systemTypeSet(UASInterface*,uint)), this, SLOT(setSystemType(UASInterface*,uint)));
connect(UASManager::instance(), SIGNAL(activeUASStatusChanged(UASInterface*,bool)), this, SLOT(updateActiveUAS(UASInterface*,bool)));
connect(uas, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(showStatusText(int, int, int, QString)));
connect(uas, SIGNAL(navModeChanged(int, int, QString)), this, SLOT(updateNavMode(int, int, QString)));
// Setup UAS selection
connect(m_ui->uasViewFrame, SIGNAL(clicked(bool)), this, SLOT(setUASasActive(bool)));
......@@ -151,6 +153,22 @@ void UASView::heartbeatTimeout()
timeout = true;
}
void UASView::updateNavMode(int uasid, int mode, const QString& text)
{
Q_UNUSED(uasid);
Q_UNUSED(mode);
m_ui->navLabel->setText(text);
}
void UASView::showStatusText(int uasid, int componentid, int severity, QString text)
{
Q_UNUSED(uasid);
Q_UNUSED(componentid);
Q_UNUSED(severity);
//m_ui->statusTextLabel->setText(text);
stateDesc = text;
}
/**
* Set the background color based on the MAV color. If the MAV is selected as the
* currently actively controlled system, the frame color is highlighted
......
......@@ -86,6 +86,10 @@ public slots:
void selectAirframe();
/** @brief Select the battery type */
void setBatterySpecs();
/** @brief Show a status text message */
void showStatusText(int uasid, int componentid, int severity, QString text);
/** @brief Update the navigation mode state */
void updateNavMode(int uasid, int mode, const QString& text);
protected:
void changeEvent(QEvent *e);
......
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