Commit 04dbdee2 authored by LM's avatar LM

Substantially improved runtime speed, fixed a few more bugs

parent 36b4938c
......@@ -79,7 +79,8 @@ attitudeStamped(false),
lastAttitude(0),
simulation(new QGCFlightGearLink(this)),
isLocalPositionKnown(false),
isGlobalPositionKnown(false)
isGlobalPositionKnown(false),
systemIsArmed(false)
{
color = UASInterface::getNextColor();
setBatterySpecs(QString("9V,9.5V,12.6V"));
......@@ -87,6 +88,10 @@ isGlobalPositionKnown(false)
connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
statusTimeout->start(500);
readSettings();
// Initial signals
emit disarmed();
emit armingChanged(false);
}
UAS::~UAS()
......@@ -236,8 +241,21 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit systemTypeSet(this, type);
}
// FIXME update
//emit armingChanged(uasId, );
bool currentlyArmed = state.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
if (systemIsArmed != currentlyArmed)
{
systemIsArmed = currentlyArmed;
emit armingChanged(systemIsArmed);
if (systemIsArmed)
{
emit armed();
}
else
{
emit disarmed();
}
}
QString audiostring = "System " + getUASName();
QString stateAudio = "";
......@@ -618,7 +636,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
mavlink_mission_count_t wpc;
mavlink_msg_mission_count_decode(&message, &wpc);
if (wpc.target_system == mavlink->getSystemId() && wpc.target_component == mavlink->getComponentId())
if (wpc.target_system == mavlink->getSystemId())
{
waypointManager.handleWaypointCount(message.sysid, message.compid, wpc.count);
}
......@@ -634,7 +652,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_mission_item_t wp;
mavlink_msg_mission_item_decode(&message, &wp);
//qDebug() << "got waypoint (" << wp.seq << ") from ID " << message.sysid << " x=" << wp.x << " y=" << wp.y << " z=" << wp.z;
if(wp.target_system == mavlink->getSystemId() && wp.target_component == mavlink->getComponentId())
if(wp.target_system == mavlink->getSystemId())
{
waypointManager.handleWaypoint(message.sysid, message.compid, &wp);
}
......@@ -660,7 +678,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
mavlink_mission_request_t wpr;
mavlink_msg_mission_request_decode(&message, &wpr);
if(wpr.target_system == mavlink->getSystemId() && wpr.target_component == mavlink->getComponentId())
if(wpr.target_system == mavlink->getSystemId())
{
waypointManager.handleWaypointRequest(message.sysid, message.compid, &wpr);
}
......
......@@ -220,6 +220,7 @@ protected: //COMMENTS FOR TEST UNIT
QGCFlightGearLink* simulation; ///< Hardware in the loop simulation link
bool isLocalPositionKnown; ///< If the local position has been received for this MAV
bool isGlobalPositionKnown; ///< If the global position has been received for this MAV
bool systemIsArmed; ///< If the system is armed
public:
/** @brief Set the current battery type */
......@@ -234,6 +235,8 @@ public:
QString getNavModeText(int mode);
/** @brief Check if vehicle is in autonomous mode */
bool isAuto();
/** @brief Check if vehicle is armed */
bool isArmed() const { return systemIsArmed; }
UASWaypointManager* getWaypointManager() {
return &waypointManager;
......
......@@ -89,6 +89,8 @@ public:
virtual bool getSelected() const = 0;
virtual bool isArmed() const = 0;
/** @brief Set the airframe of this MAV */
virtual int getAirframe() const = 0;
......@@ -334,6 +336,13 @@ signals:
void navModeChanged(int uasid, int mode, const QString& text);
/** @brief System is now armed */
void armed();
/** @brief System is now disarmed */
void disarmed();
/** @brief Arming mode changed */
void armingChanged(bool armed);
/**
* @brief Update the error count of a device
*
......
......@@ -64,6 +64,9 @@ QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) :
connect(calibrate, SIGNAL(clicked()), calibrationWindow, SLOT(show()));
connect(UASManager::instance(), SIGNAL(activeUASSet(int)), this, SLOT(setUASId(int)));
connect(&updateTimer, SIGNAL(timeout()), this, SLOT(redraw()));
updateTimer.start(1500);
}
QGCRemoteControlView::~QGCRemoteControlView()
......@@ -74,6 +77,23 @@ QGCRemoteControlView::~QGCRemoteControlView()
void QGCRemoteControlView::setUASId(int id)
{
// Clear channel count
raw.clear();
raw.resize(0);
normalized.clear();
normalized.resize(0);
foreach (QLabel* label, rawLabels)
{
label->deleteLater();
}
foreach(QProgressBar* bar, progressBars)
{
bar->deleteLater();
}
if (uasId != -1) {
UASInterface* uas = UASManager::instance()->getUASForId(id);
if (uas) {
......@@ -110,14 +130,12 @@ void QGCRemoteControlView::setChannelRaw(int channelId, float raw)
this->raw.append(raw);
//this->normalized.append(0);
appendChannelWidget(channelId);
updated = true;
} else {
// This is an existing channel, aupdate it
if (this->raw[channelId] != raw) updated = true;
this->raw[channelId] = raw;
}
updated = true;
// FIXME Will be timer based in the future
redraw();
}
void QGCRemoteControlView::setChannelScaled(int channelId, float normalized)
......@@ -128,22 +146,20 @@ void QGCRemoteControlView::setChannelScaled(int channelId, float normalized)
this->normalized.append(normalized);
this->raw.append(0);
appendChannelWidget(channelId);
updated = true;
}
else
{
// This is an existing channel, update it
if (this->normalized[channelId] != normalized) updated = true;
this->normalized[channelId] = normalized;
}
// updated = true;
// // FIXME Will be timer based in the future
// redraw();
}
void QGCRemoteControlView::setRemoteRSSI(float rssiNormalized)
{
if (rssi != rssiNormalized) updated = true;
rssi = rssiNormalized;
updated = true;
}
void QGCRemoteControlView::appendChannelWidget(int channelId)
......@@ -169,7 +185,8 @@ void QGCRemoteControlView::appendChannelWidget(int channelId)
void QGCRemoteControlView::redraw()
{
if(isVisible() && updated) {
if(isVisible() && updated)
{
// Update raw values
//for(int i = 0; i < rawLabels.count(); i++)
//{
......@@ -177,7 +194,8 @@ void QGCRemoteControlView::redraw()
//}
// Update percent bars
for(int i = 0; i < progressBars.count(); i++) {
for(int i = 0; i < progressBars.count(); i++)
{
rawLabels.at(i)->setText(QString("%1 us").arg(raw.at(i), 4, 10, QChar('0')));
int vv = normalized.at(i)*100.0f;
//progressBars.at(i)->setValue(vv);
......
......@@ -76,6 +76,7 @@ protected:
QLabel* nameLabel;
QPushButton *calibrate;
RadioCalibrationWindow *calibrationWindow;
QTimer updateTimer;
private:
Ui::QGCRemoteControlView *ui;
......
......@@ -37,7 +37,8 @@ QGCToolBar::QGCToolBar(QWidget *parent) :
batteryPercent(0),
batteryVoltage(0),
wpId(0),
wpDistance(0)
wpDistance(0),
systemArmed(false)
{
setObjectName("QGC_TOOLBAR");
......@@ -212,6 +213,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
disconnect(mav, SIGNAL(systemTypeSet(UASInterface*,uint)), this, SLOT(setSystemType(UASInterface*,uint)));
disconnect(mav, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(receiveTextMessage(int,int,int,QString)));
disconnect(mav, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBatteryRemaining(UASInterface*,double,double,int)));
disconnect(mav, SIGNAL(armingChanged(bool)), this, SLOT(updateArmingState(bool)));
if (mav->getWaypointManager())
{
disconnect(mav->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(updateCurrentWaypoint(quint16)));
......@@ -227,6 +229,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
connect(active, SIGNAL(systemTypeSet(UASInterface*,uint)), this, SLOT(setSystemType(UASInterface*,uint)));
connect(active, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(receiveTextMessage(int,int,int,QString)));
connect(active, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBatteryRemaining(UASInterface*,double,double,int)));
connect(active, SIGNAL(armingChanged(bool)), this, SLOT(updateArmingState(bool)));
if (active->getWaypointManager())
{
connect(active->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(updateCurrentWaypoint(quint16)));
......@@ -235,6 +238,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
// Update all values once
systemName = mav->getUASName();
systemArmed = mav->isArmed();
toolBarNameLabel->setText(mav->getUASName());
toolBarNameLabel->setStyleSheet(QString("QLabel { font: bold 16px; color: %1; }").arg(mav->getColor().name()));
symbolButton->setStyleSheet(QString("QWidget { background-color: %1; color: #DDDDDF; background-clip: border; } QToolButton { font-weight: bold; font-size: 12px; border: 0px solid #999999; border-radius: 5px; min-width:22px; max-width: 22px; min-height: 22px; max-height: 22px; padding: 0px; margin: 0px 4px 0px 20px; background-color: none; }").arg(mav->getColor().name()));
......@@ -248,6 +252,12 @@ void QGCToolBar::createCustomWidgets()
}
void QGCToolBar::updateArmingState(bool armed)
{
systemArmed = armed;
changed = true;
}
void QGCToolBar::updateView()
{
if (!changed) return;
......@@ -259,6 +269,18 @@ void QGCToolBar::updateView()
toolBarModeLabel->setText(tr("%1").arg(mode));
toolBarNameLabel->setText(systemName);
toolBarMessageLabel->setText(lastSystemMessage);
if (systemArmed)
{
toolBarSafetyLabel->setStyleSheet(QString("QLabel { margin: 0px 2px; font: 14px; color: %1; background-color: %2; }").arg(QGC::colorRed.name()).arg(QGC::colorYellow.name()));
toolBarSafetyLabel->setText(tr("ARMED"));
}
else
{
toolBarSafetyLabel->setStyleSheet("QLabel { margin: 0px 2px; font: 14px; color: #14C814; }");
toolBarSafetyLabel->setText(tr("SAFE"));
}
changed = false;
}
......
......@@ -66,6 +66,8 @@ public slots:
void updateCurrentWaypoint(quint16 id);
/** @brief Update distance to current waypoint */
void updateWaypointDistance(double distance);
/** @brief Update arming state */
void updateArmingState(bool armed);
/** @brief Repaint widgets */
void updateView();
......@@ -96,6 +98,7 @@ protected:
QString systemName;
QString lastSystemMessage;
QTimer updateViewTimer;
bool systemArmed;
};
#endif // QGCTOOLBAR_H
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