Commit c49b32bd authored by tecnosapiens's avatar tecnosapiens

add widget to SlugsDataSensorView.ui

parent 71a63d00
......@@ -36,7 +36,7 @@ This file is part of the QGROUNDCONTROL project
#include "UDPLink.h"
#include "LinkManager.h"
#include "MG.h"
#include <netinet/in.h>
//#include <netinet/in.h>
UDPLink::UDPLink(QHostAddress host, quint16 port)
{
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#include "SlugsMAV.h"
#include <QDebug>
......@@ -29,8 +6,6 @@ SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) :
UAS(mavlink, id)//,
// Place other initializers here
{
}
/**
......@@ -55,7 +30,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
break;
}
#ifdef MAVLINK_ENABLED_SLUGS
#ifdef MAVLINK_ENABLED_SLUGS_MESSAGES_QGC
case MAVLINK_MSG_ID_CPU_LOAD:
{
......@@ -67,7 +42,11 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, tr("ControlDSC Load"), cpu_load.ctrlLoad, time);
emit valueChanged(uasId, tr("Battery Volt"), cpu_load.batVolt, time);
emit newCpuLoad (uasId, &cpu_load);
emit slugsCPULoad(uasId,
cpu_load.sensLoad,
cpu_load.ctrlLoad,
cpu_load.batVolt,
time);
break;
}
......@@ -80,6 +59,12 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, tr("Static Pressure"),air_data.staticPressure, time);
emit valueChanged(uasId, tr("Temp"),air_data.temperature,time);
emit slugsAirData(uasId,
air_data.dynamicPressure,
air_data.staticPressure,
air_data.temperature,
time);
break;
}
case MAVLINK_MSG_ID_SENSOR_BIAS:
......@@ -94,6 +79,16 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId,tr("Gy Bias"),sensor_bias.gyBias,time);
emit valueChanged(uasId,tr("Gz Bias"),sensor_bias.gzBias,time);
emit slugsSensorBias(uasId,
sensor_bias.axBias,
sensor_bias.ayBias,
sensor_bias.azBias,
sensor_bias.gxBias,
sensor_bias.gyBias,
sensor_bias.gzBias,
time);
break;
}
case MAVLINK_MSG_ID_DIAGNOSTIC:
......@@ -108,6 +103,14 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId,tr("Diag S2"),diagnostic.diagSh2,time);
emit valueChanged(uasId,tr("Diag S3"),diagnostic.diagSh3,time);
emit slugsDiagnostic(uasId,
diagnostic.diagFl1,
diagnostic.diagFl2,
diagnostic.diagFl3,
diagnostic.diagSh1,
diagnostic.diagSh2,
diagnostic.diagSh3);
break;
}
case MAVLINK_MSG_ID_PILOT_CONSOLE:
......@@ -121,6 +124,15 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId,"dr",pilot.dr,time);
emit valueChanged(uasId,"de",pilot.de,time);
emit slugsPilotConsolePWM(uasId,
pilot.dt,
pilot.dla,
pilot.dra,
pilot.dr,
pilot.de,
time);
break;
}
case MAVLINK_MSG_ID_PWM_COMMANDS:
......@@ -139,6 +151,19 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId,"da1_c",pwm.aux1,time);
emit valueChanged(uasId,"da2_c",pwm.aux2,time);
emit slugsPWM(uasId,
pwm.dt_c,
pwm.dla_c,
pwm.dra_c,
pwm.dr_c,
pwm.dle_c,
pwm.dre_c,
pwm.dlf_c,
pwm.drf_c,
pwm.aux1,
pwm.aux2,
time);
break;
}
......
......@@ -383,6 +383,62 @@ signals:
* @param fix 0: No IR/Ultrasound sensor, N > 0: Found N active sensors
*/
void irUltraSoundLocalizationChanged(UASInterface* uas, int fix);
// ESPECIAL SLUGS MESSAGE
void slugsCPULoad(UASInterface* uas,
uint8_t sensLoad,
uint8_t ctrlLoad,
uint8_t batVolt,
quint64 time);
void slugsAirData(UASInterface* uas,
float dinamicPressure,
float staticPresure,
uint16_t temperature,
quint64 time);
void slugsSensorBias(UASInterface* uas,
double axBias,
double ayBias,
double azBias,
double gxBias,
double gyBias,
double gzBias,
quint64 time);
void slugsDiagnostic(UASInterface* uas,
double diagFl1,
double diagFl2,
double diagFl3,
int16_t diagSh1,
int16_t diagSh2,
int16_t diagSh3,
quint64 time);
void slugsPilotConsolePWM(UASInterface* uas,
uint16_t dt,
uint16_t dla,
uint16_t dra,
uint16_t dr,
uint16_t de,
quint64 time);
void slugsPWM(UASInterface* uas,
uint16_t dt_c,
uint16_t dla_c,
uint16_t dra_c,
uint16_t dr_c,
uint16_t dle_c,
uint16_t dre_c,
uint16_t dlf_c,
uint16_t drf_c,
uint16_t da1_c,
uint16_t da2_c,
quint64 time);
};
Q_DECLARE_INTERFACE(UASInterface, "org.qgroundcontrol/1.0");
......
......@@ -181,6 +181,7 @@ void MainWindow::buildWidgets()
slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
slugsDataWidget->setWidget( new SlugsDataSensorView(this));
}
/**
......@@ -540,7 +541,17 @@ void MainWindow::UASCreated(UASInterface* uas)
PxQuadMAV* mav = dynamic_cast<PxQuadMAV*>(uas);
if (mav) loadPixhawkView();
SlugsMAV* mav2 = dynamic_cast<SlugsMAV*>(uas);
if (mav2) loadSlugsView();
if (mav2)
{
SlugsDataSensorView* slugDataView = dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget());
if(slugDataView)
{
slugDataView->addUAS(uas);
}
loadSlugsView();
}
}
}
......
......@@ -47,12 +47,11 @@ void SlugsDataSensorView::loadParameters()
Axb = 0;
Ayb = 0;
Azb = 0;
TimeActualAcel = 0;
//Gyro
Gxb = 0;
Gyb = 0;
Gzb = 0;
TimeActualGyro = 0;
TimeActualBias = 0;
}
......@@ -68,7 +67,7 @@ void SlugsDataSensorView::addUAS(UASInterface* uas)
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugLocalPositionChange(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugSpeedLocalPositionChanged(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugAttitudeChanged(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(sensorBiasAcelerometerChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugsSensorBiasAcelerometerChanged(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(slugsSensorBias(UASInterface*,double,double,double,double,double,double,quint64)), this, SLOT(slugsSensorBiasAcelerometerChanged(UASInterface*,double,double,double,quint64)));
// Set this UAS as active if it is the first one
if(activeUAS == 0)
......@@ -81,35 +80,48 @@ void SlugsDataSensorView::addUAS(UASInterface* uas)
void SlugsDataSensorView::setActiveUAS(UASInterface* uas)
{
activeUAS = uas;
}
void SlugsDataSensorView::refresh()
{
if(activeUAS)
{
//refresh UI position data
ui->ed_x->setPlainText(QString::number(Xpos, 'f', 4));
ui->ed_y->setPlainText(QString::number(Ypos, 'f', 4));
ui->ed_z->setPlainText(QString::number(Zpos, 'f', 4));
//refresh UI speed position data
ui->ed_vx->setPlainText(QString::number(VXpos,'f',4));
ui->ed_vy->setPlainText(QString::number(VYpos,'f',4));
ui->ed_vz->setPlainText(QString::number(VZpos,'f',4));
//refresh UI attitude data
ui->m_SlugAttitudeRoll_plainTextEdit->setPlainText(QString::number(roll,'f',4));
ui->m_SlugAttitudePitch_plainTextEdit->setPlainText(QString::number(pitch,'f',4));
ui->m_SlugAttitudeYaw_plainTextEdit->setPlainText(QString::number(yaw,'f',4));
//refresh UI position data
ui->ed_x->setPlainText(QString::number(Xpos, 'f', 4));
ui->ed_y->setPlainText(QString::number(Ypos, 'f', 4));
ui->ed_z->setPlainText(QString::number(Zpos, 'f', 4));
//refresh UI speed position data
ui->ed_vx->setPlainText(QString::number(VXpos,'f',4));
ui->ed_vy->setPlainText(QString::number(VYpos,'f',4));
ui->ed_vz->setPlainText(QString::number(VZpos,'f',4));
//refresh UI attitude data
ui->m_SlugAttitudeRoll_plainTextEdit->setPlainText(QString::number(roll,'f',4));
ui->m_SlugAttitudePitch_plainTextEdit->setPlainText(QString::number(pitch,'f',4));
ui->m_SlugAttitudeYaw_plainTextEdit->setPlainText(QString::number(yaw,'f',4));
//refresh UI sensor bias acelerometer data
ui->m_SlugsAxBiases_textEdit->setText(QString::number(Axb, 'f', 4));
ui->m_SlugsAyBiases_textEdit->setText(QString::number(Ayb, 'f', 4));
ui->m_SlugsAzBiases_textEdit->setText(QString::number(Azb, 'f', 4));
ui->m_SlugsGxBiases_textEdit->setText(QString::number(Gxb, 'f', 4));
ui->m_SlugsGyBiases_textEdit->setText(QString::number(Gyb, 'f', 4));
ui->m_SlugsGzBiases_textEdit->setText(QString::number(Gzb, 'f', 4));
//refresh UI sensor bias acelerometer data
ui->m_SlugsAxBiases_textEdit->setText(QString::number(Axb, 'f', 4));
ui->m_SlugsAyBiases_textEdit->setText(QString::number(Ayb, 'f', 4));
ui->m_SlugsAzBiases_textEdit->setText(QString::number(Azb, 'f', 4));
}
}
void SlugsDataSensorView::slugLocalPositionChanged(UASInterface * uasTemp, double x, double y, double z, quint64 time)
void SlugsDataSensorView::slugLocalPositionChanged(UASInterface * uasTemp,
double x,
double y,
double z,
quint64 time)
{
Q_UNUSED( uasTemp);
......@@ -120,7 +132,11 @@ void SlugsDataSensorView::slugLocalPositionChanged(UASInterface * uasTemp, doubl
}
void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface *uasTemp, double vx, double vy, double vz, quint64 time)
void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface *uasTemp,
double vx,
double vy,
double vz,
quint64 time)
{
Q_UNUSED( uasTemp);
......@@ -130,7 +146,11 @@ void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface *uasTemp, d
TimeActualSpeed = time;
}
void SlugsDataSensorView::slugAttitudeChanged(UASInterface *uasTemp, double slugroll, double slugpitch, double slugyaw, quint64 time)
void SlugsDataSensorView::slugAttitudeChanged(UASInterface *uasTemp,
double slugroll,
double slugpitch,
double slugyaw,
quint64 time)
{
Q_UNUSED( uasTemp);
......@@ -140,14 +160,24 @@ void SlugsDataSensorView::slugAttitudeChanged(UASInterface *uasTemp, double slug
TimeActualAttitude = time;
}
void SlugsDataSensorView::slugsSensorBiasAcelerometerChanged(UASInterface *uasTemp, double axb, double ayb, double azb, quint64 time)
void SlugsDataSensorView::slugsSensorBiasChanged(UASInterface *uasTemp,
double axb,
double ayb,
double azb,
double gxb,
double gyb,
double gzb,
quint64 time)
{
Q_UNUSED( uasTemp);
Axb = axb;
Ayb = ayb;
Azb = azb;
TimeActualAcel = time;
Gxb = gxb;
Gyb = gyb;
Gzb = gzb;
TimeActualBias = time;
}
......
......@@ -75,10 +75,35 @@ public slots:
void refresh();
void slugLocalPositionChanged(UASInterface* uasTemp,double x,double y,double z,quint64 time);
void slugSpeedLocalPositionChanged(UASInterface* uasTemp,double vx,double vy,double vz,quint64 time);
void slugAttitudeChanged(UASInterface* uasTemp,double slugroll,double slugpitch,double slugyaw, quint64 time);
void slugsSensorBiasAcelerometerChanged(UASInterface* uasTemp, double axb, double ayb, double azb, quint64 time);
void slugLocalPositionChanged(UASInterface* uasTemp,
double x,
double y,
double z,
quint64 time);
void slugSpeedLocalPositionChanged(UASInterface* uasTemp,
double vx,
double vy,
double vz,
quint64 time);
void slugAttitudeChanged(UASInterface* uasTemp,
double slugroll,
double slugpitch,
double slugyaw,
quint64 time);
void slugsSensorBiasChanged(UASInterface* uasTemp,
double axb,
double ayb,
double azb,
double gxb,
double gyb,
double gzb,
quint64 time);
protected:
QTimer* updateTimer;
......@@ -106,12 +131,14 @@ protected:
double Axb;
double Ayb;
double Azb;
quint64 TimeActualAcel;
//Gyro
double Gxb;
double Gyb;
double Gzb;
quint64 TimeActualGyro;
quint64 TimeActualBias;
//
......
This diff is collapsed.
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