Browse Source

Cleanups in GCS

QGC4.4
lm 15 years ago
parent
commit
d49b7022c8
  1. 26
      src/comm/MAVLinkProtocol.cc
  2. 10
      src/comm/MAVLinkProtocol.h
  3. 5
      src/uas/UAS.cc
  4. 41
      src/ui/HSIDisplay.cc
  5. 2
      src/ui/HSIDisplay.h
  6. 3
      src/ui/MAVLinkSettingsWidget.cc
  7. 2
      src/ui/MainWindow.cc
  8. 6
      src/ui/ObjectDetectionView.cc

26
src/comm/MAVLinkProtocol.cc

@ -35,6 +35,7 @@ This file is part of the PIXHAWK project @@ -35,6 +35,7 @@ This file is part of the PIXHAWK project
#include <QDebug>
#include <QTime>
#include <QApplication>
#include "MG.h"
#include "MAVLinkProtocol.h"
@ -56,7 +57,9 @@ This file is part of the PIXHAWK project @@ -56,7 +57,9 @@ This file is part of the PIXHAWK project
MAVLinkProtocol::MAVLinkProtocol() :
heartbeatTimer(new QTimer(this)),
heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
m_heartbeatsEnabled(false)
m_heartbeatsEnabled(false),
m_loggingEnabled(false),
m_logfile(NULL)
{
start(QThread::LowPriority);
// Start heartbeat timer, emitting a heartbeat at the configured rate
@ -83,6 +86,7 @@ MAVLinkProtocol::~MAVLinkProtocol() @@ -83,6 +86,7 @@ MAVLinkProtocol::~MAVLinkProtocol()
void MAVLinkProtocol::run()
{
}
/**
@ -316,11 +320,31 @@ void MAVLinkProtocol::enableHeartbeats(bool enabled) @@ -316,11 +320,31 @@ void MAVLinkProtocol::enableHeartbeats(bool enabled)
emit heartbeatChanged(enabled);
}
void MAVLinkProtocol::enableLogging(bool enabled)
{
if (enabled && !m_loggingEnabled)
{
m_logfile = new QFile(QCoreApplication::applicationDirPath()+"mavlink.log");
}
else
{
m_logfile->close();
delete m_logfile;
m_logfile = NULL;
}
m_loggingEnabled = enabled;
}
bool MAVLinkProtocol::heartbeatsEnabled(void)
{
return m_heartbeatsEnabled;
}
bool MAVLinkProtocol::loggingEnabled(void)
{
return m_loggingEnabled;
}
/**
* The default rate is 1 Hertz.
*

10
src/comm/MAVLinkProtocol.h

@ -37,6 +37,7 @@ This file is part of the PIXHAWK project @@ -37,6 +37,7 @@ This file is part of the PIXHAWK project
#include <QMutex>
#include <QString>
#include <QTimer>
#include <QFile>
#include <QMap>
#include <QByteArray>
#include "ProtocolInterface.h"
@ -65,6 +66,8 @@ public: @@ -65,6 +66,8 @@ public:
int getHeartbeatRate();
/** @brief Get heartbeat state */
bool heartbeatsEnabled(void);
/** @brief Get logging state */
bool loggingEnabled(void);
public slots:
/** @brief Receive bytes from a communication interface */
@ -79,6 +82,9 @@ public slots: @@ -79,6 +82,9 @@ public slots:
/** @brief Enable / disable the heartbeat emission */
void enableHeartbeats(bool enabled);
/** @brief Enable/disable binary packet logging */
void enableLogging(bool enabled);
/** @brief Send an extra heartbeat to all connected units */
void sendHeartbeat();
@ -86,6 +92,8 @@ protected: @@ -86,6 +92,8 @@ protected:
QTimer* heartbeatTimer; ///< Timer to emit heartbeats
int heartbeatRate; ///< Heartbeat rate, controls the timer interval
bool m_heartbeatsEnabled; ///< Enabled/disable heartbeat emission
bool m_loggingEnabled; ///< Enable/disable packet logging
QFile* m_logfile; ///< Logfile
QMutex receiveMutex; ///< Mutex to protect receiveBytes function
int lastIndex[256][256];
int totalReceiveCounter;
@ -98,6 +106,8 @@ signals: @@ -98,6 +106,8 @@ signals:
void messageReceived(LinkInterface* link, mavlink_message_t message);
/** @brief Emitted if heartbeat emission mode is changed */
void heartbeatChanged(bool heartbeats);
/** @brief Emitted if logging is started / stopped */
void loggingChanged(bool enabled);
};
#endif // MAVLINKPROTOCOL_H_

5
src/uas/UAS.cc

@ -338,7 +338,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) @@ -338,7 +338,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "lon", pos.lon, time);
emit valueChanged(uasId, "alt", pos.alt, time);
emit valueChanged(uasId, "speed", pos.v, time);
qDebug() << "GOT GPS RAW";
//qDebug() << "GOT GPS RAW";
emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time);
}
break;
@ -346,7 +346,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) @@ -346,7 +346,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
mavlink_gps_status_t pos;
mavlink_msg_gps_status_decode(&message, &pos);
for(int i = 0; i < pos.satellites_visible && i < sizeof(pos.satellite_used); i++)
//qDebug() << "GOT GPS STATUS FOR "<< pos.satellites_visible << "SATELLITES";
for(int i = 0; i < (int)pos.satellites_visible; i++)
{
emit gpsSatelliteStatusChanged(uasId, i, pos.satellite_azimuth[i], pos.satellite_direction[i], pos.satellite_snr[i], static_cast<bool>(pos.satellite_used[i]));
}

41
src/ui/HSIDisplay.cc

@ -42,7 +42,7 @@ HSIDisplay::HSIDisplay(QWidget *parent) : @@ -42,7 +42,7 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
HDDisplay(NULL, parent),
gpsSatellites()
{
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
}
void HSIDisplay::paintEvent(QPaintEvent * event)
@ -133,6 +133,8 @@ void HSIDisplay::setActiveUAS(UASInterface* uas) @@ -133,6 +133,8 @@ void HSIDisplay::setActiveUAS(UASInterface* uas)
//disconnect(uas, SIGNAL(valueChanged(UASInterface*,QString,double,quint64)), this, SLOT(updateValue(UASInterface*,QString,double,quint64)));
}
connect(uas, SIGNAL(gpsSatelliteStatusChanged(int,int,float,float,float,bool)), this, SLOT(updateSatellite(int,int,float,float,float,bool)));
// Now connect the new UAS
//if (this->uas != uas)
@ -146,7 +148,14 @@ void HSIDisplay::setActiveUAS(UASInterface* uas) @@ -146,7 +148,14 @@ void HSIDisplay::setActiveUAS(UASInterface* uas)
void HSIDisplay::updateSatellite(int uasid, int satid, float azimuth, float direction, float snr, bool used)
{
Q_UNUSED(uasid);
//qDebug() << "UPDATED SATELLITE";
// If slot is empty, insert object
if (gpsSatellites.size() <= satid)
{
gpsSatellites.resize(satid+1);
// gpsSatellites.insert(satid, new GPSSatellite(satid, azimuth, direction, snr, used));
}
if (gpsSatellites.at(satid) == NULL)
{
gpsSatellites.insert(satid, new GPSSatellite(satid, azimuth, direction, snr, used));
@ -160,11 +169,30 @@ void HSIDisplay::updateSatellite(int uasid, int satid, float azimuth, float dire @@ -160,11 +169,30 @@ void HSIDisplay::updateSatellite(int uasid, int satid, float azimuth, float dire
QColor HSIDisplay::getColorForSNR(float snr)
{
return QColor(200, 250, 200);
QColor color;
if (snr < 10)
{
color = QColor(250, 200, 200);
}
else if (snr > 20)
{
color = QColor(200, 250, 200);
}
else if (snr > 30)
{
color = QColor(100, 250, 100);
}
else
{
color = QColor(180, 180, 180);
}
return color;
}
void HSIDisplay::drawGPS()
{
float xCenter = vwidth/2.0f;
float yCenter = vwidth/2.0f;
QPainter painter(this);
painter.setRenderHint(QPainter::Antialiasing, true);
painter.setRenderHint(QPainter::HighQualityAntialiasing, true);
@ -172,7 +200,8 @@ void HSIDisplay::drawGPS() @@ -172,7 +200,8 @@ void HSIDisplay::drawGPS()
// Max satellite circle radius
const float margin = 0.2f; // 20% margin of total width on each side
float radius = (vwidth - vwidth * 2.0f * margin) / 2.0f;
float radius = (vwidth - vwidth * 2.0f * margin) / 4.0f;
radius = radius;
for (int i = 0; i < gpsSatellites.size(); i++)
{
@ -195,10 +224,10 @@ void HSIDisplay::drawGPS() @@ -195,10 +224,10 @@ void HSIDisplay::drawGPS()
painter.setPen(color);
painter.setBrush(brush);
float xPos = sin(sat->direction) * sat->azimuth * radius;
float yPos = cos(sat->direction) * sat->azimuth * radius;
float xPos = xCenter + sin(sat->direction/180.0f * M_PI) * (sat->azimuth/180.0f * M_PI) * radius;
float yPos = yCenter + cos(sat->direction/180.0f * M_PI) * (sat->azimuth/180.0f * M_PI) * radius;
drawCircle(xPos, yPos, vwidth/10.0f, 1.0f, color, &painter);
drawCircle(xPos, yPos, vwidth*0.02f, 1.0f, color, &painter);
}
}
}

2
src/ui/HSIDisplay.h

@ -49,6 +49,7 @@ public: @@ -49,6 +49,7 @@ public:
public slots:
void setActiveUAS(UASInterface* uas);
void updateSatellite(int uasid, int satid, float azimuth, float direction, float snr, bool used);
void paintEvent(QPaintEvent * event);
protected slots:
@ -59,7 +60,6 @@ protected slots: @@ -59,7 +60,6 @@ protected slots:
protected:
void updateSatellite(int uasid, int satid, float azimuth, float direction, float snr, bool used);
static QColor getColorForSNR(float snr);
/**

3
src/ui/MAVLinkSettingsWidget.cc

@ -11,9 +11,12 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget @@ -11,9 +11,12 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget
// Connect actions
connect(protocol, SIGNAL(heartbeatChanged(bool)), m_ui->heartbeatCheckBox, SLOT(setChecked(bool)));
connect(m_ui->heartbeatCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableHeartbeats(bool)));
connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->loggingCheckBox, SLOT(setChecked(bool)));
connect(m_ui->loggingCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableLogging(bool)));
// Initialize state
m_ui->heartbeatCheckBox->setChecked(protocol->heartbeatsEnabled());
m_ui->loggingCheckBox->setChecked(protocol->loggingEnabled());
}
MAVLinkSettingsWidget::~MAVLinkSettingsWidget()

2
src/ui/MainWindow.cc

@ -85,7 +85,7 @@ settings() @@ -85,7 +85,7 @@ settings()
waypoints->setVisible(false);
info = new UASInfoWidget(this);
info->setVisible(false);
detection = new ObjectDetectionView("test", this);
detection = new ObjectDetectionView("patterns", this);
detection->setVisible(false);
hud = new HUD(640, 480, this);
hud->setVisible(false);

6
src/ui/ObjectDetectionView.cc

@ -94,7 +94,6 @@ void ObjectDetectionView::newDetection(int uasId, QString patternPath, int x1, i @@ -94,7 +94,6 @@ void ObjectDetectionView::newDetection(int uasId, QString patternPath, int x1, i
{
//qDebug() << "REDETECTED";
/*
QList<QAction*> actions = m_ui->listWidget->actions();
// Find action and update it
foreach (QAction* act, actions)
@ -107,7 +106,9 @@ void ObjectDetectionView::newDetection(int uasId, QString patternPath, int x1, i @@ -107,7 +106,9 @@ void ObjectDetectionView::newDetection(int uasId, QString patternPath, int x1, i
act->setText(patternPath + separator + "(#" + QString::number(count) + ")" + separator + QString::number(confidence));
}
}
QPixmap image = QPixmap(patternFolder + "/" + patternPath);
QString filePath = MG::DIR::getSupportFilesDirectory() + "/" + patternFolder + "/" + patternPath.split("/").last();
qDebug() << "Loading:" << filePath;
QPixmap image = QPixmap(filePath);
image = image.scaledToWidth(m_ui->imageLabel->width());
m_ui->imageLabel->setPixmap(image);
QString patternName = patternPath.split("//").last(); // Remove preceding folder names
@ -115,7 +116,6 @@ void ObjectDetectionView::newDetection(int uasId, QString patternPath, int x1, i @@ -115,7 +116,6 @@ void ObjectDetectionView::newDetection(int uasId, QString patternPath, int x1, i
// Set name and label
m_ui->nameLabel->setText(patternName);
*/
}
else
{

Loading…
Cancel
Save