Browse Source

add messages to slugsView

QGC4.4
tecnosapiens 15 years ago
parent
commit
6a5655eb3b
  1. 1
      qgroundcontrol.pro
  2. 80
      src/uas/SlugsMAV.cc
  3. 3
      src/ui/SlugsDataSensorView.cc
  4. 16
      src/ui/SlugsDataSensorView.h

1
qgroundcontrol.pro

@ -32,6 +32,7 @@
# include ( "../qmapcontrol/QMapControl/QMapControl.pri" ) #{ # include ( "../qmapcontrol/QMapControl/QMapControl.pri" ) #{
# Include bundled version if necessary # Include bundled version if necessary
include(lib/QMapControl/QMapControl.pri) include(lib/QMapControl/QMapControl.pri)
# message("Including bundled QMapControl version as FALLBACK. This is fine on Linux and MacOS, but not the best choice in Windows") # message("Including bundled QMapControl version as FALLBACK. This is fine on Linux and MacOS, but not the best choice in Windows")

80
src/uas/SlugsMAV.cc

@ -30,7 +30,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
break; break;
} }
#ifdef MAVLINK_ENABLED_SLUGS_MESSAGES_QGC #ifdef MAVLINK_ENABLED_SLUGS
case MAVLINK_MSG_ID_CPU_LOAD: case MAVLINK_MSG_ID_CPU_LOAD:
{ {
@ -42,11 +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("ControlDSC Load"), cpu_load.ctrlLoad, time);
emit valueChanged(uasId, tr("Battery Volt"), cpu_load.batVolt, time); emit valueChanged(uasId, tr("Battery Volt"), cpu_load.batVolt, time);
emit slugsCPULoad(uasId, // emit slugsCPULoad(uasId,
cpu_load.sensLoad, // cpu_load.sensLoad,
cpu_load.ctrlLoad, // cpu_load.ctrlLoad,
cpu_load.batVolt, // cpu_load.batVolt,
time); // 0);
break; break;
} }
@ -59,11 +59,11 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, tr("Static Pressure"),air_data.staticPressure, time); emit valueChanged(uasId, tr("Static Pressure"),air_data.staticPressure, time);
emit valueChanged(uasId, tr("Temp"),air_data.temperature,time); emit valueChanged(uasId, tr("Temp"),air_data.temperature,time);
emit slugsAirData(uasId, // emit slugsAirData(uasId,
air_data.dynamicPressure, // air_data.dynamicPressure,
air_data.staticPressure, // air_data.staticPressure,
air_data.temperature, // air_data.temperature,
time); // time);
break; break;
} }
@ -79,14 +79,15 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId,tr("Gy Bias"),sensor_bias.gyBias,time); emit valueChanged(uasId,tr("Gy Bias"),sensor_bias.gyBias,time);
emit valueChanged(uasId,tr("Gz Bias"),sensor_bias.gzBias,time); emit valueChanged(uasId,tr("Gz Bias"),sensor_bias.gzBias,time);
emit slugsSensorBias(uasId, emit slugsSensorBias(this,
sensor_bias.axBias, sensor_bias.axBias,
sensor_bias.ayBias, sensor_bias.ayBias,
sensor_bias.azBias, sensor_bias.azBias,
sensor_bias.gxBias, sensor_bias.gxBias,
sensor_bias.gyBias, sensor_bias.gyBias,
sensor_bias.gzBias, sensor_bias.gzBias,
time); 0);
qDebug()<<"Entro";
break; break;
@ -103,13 +104,14 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId,tr("Diag S2"),diagnostic.diagSh2,time); emit valueChanged(uasId,tr("Diag S2"),diagnostic.diagSh2,time);
emit valueChanged(uasId,tr("Diag S3"),diagnostic.diagSh3,time); emit valueChanged(uasId,tr("Diag S3"),diagnostic.diagSh3,time);
emit slugsDiagnostic(uasId, // emit slugsDiagnostic(uasId,
diagnostic.diagFl1, // diagnostic.diagFl1,
diagnostic.diagFl2, // diagnostic.diagFl2,
diagnostic.diagFl3, // diagnostic.diagFl3,
diagnostic.diagSh1, // diagnostic.diagSh1,
diagnostic.diagSh2, // diagnostic.diagSh2,
diagnostic.diagSh3); // diagnostic.diagSh3,
// 0);
break; break;
} }
@ -124,13 +126,13 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId,"dr",pilot.dr,time); emit valueChanged(uasId,"dr",pilot.dr,time);
emit valueChanged(uasId,"de",pilot.de,time); emit valueChanged(uasId,"de",pilot.de,time);
emit slugsPilotConsolePWM(uasId, // emit slugsPilotConsolePWM(uasId,
pilot.dt, // pilot.dt,
pilot.dla, // pilot.dla,
pilot.dra, // pilot.dra,
pilot.dr, // pilot.dr,
pilot.de, // pilot.de,
time); // 0);
break; break;
@ -151,18 +153,18 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId,"da1_c",pwm.aux1,time); emit valueChanged(uasId,"da1_c",pwm.aux1,time);
emit valueChanged(uasId,"da2_c",pwm.aux2,time); emit valueChanged(uasId,"da2_c",pwm.aux2,time);
emit slugsPWM(uasId, // emit slugsPWM(uasId,
pwm.dt_c, // pwm.dt_c,
pwm.dla_c, // pwm.dla_c,
pwm.dra_c, // pwm.dra_c,
pwm.dr_c, // pwm.dr_c,
pwm.dle_c, // pwm.dle_c,
pwm.dre_c, // pwm.dre_c,
pwm.dlf_c, // pwm.dlf_c,
pwm.drf_c, // pwm.drf_c,
pwm.aux1, // pwm.aux1,
pwm.aux2, // pwm.aux2,
time); // 0);
break; break;

3
src/ui/SlugsDataSensorView.cc

@ -71,8 +71,7 @@ void SlugsDataSensorView::addUAS(UASInterface* uas)
connect(slugsMav, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugSpeedLocalPositionChanged(UASInterface*,double,double,double,quint64))); connect(slugsMav, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugSpeedLocalPositionChanged(UASInterface*,double,double,double,quint64)));
connect(slugsMav, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugAttitudeChanged(UASInterface*,double,double,double,quint64))); connect(slugsMav, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugAttitudeChanged(UASInterface*,double,double,double,quint64)));
connect(slugsMav, SIGNAL(slugsSensorBias(UASInterface*,double,double,double,double,double,double,quint64)), this, SLOT(slugsSensorBiasAcelerometerChanged(UASInterface*,double,double,double,quint64))); connect(slugsMav, SIGNAL(slugsSensorBias(UASInterface*,double,double,double,double,double,double,quint64)), this, SLOT(slugsSensorBiasAcelerometerChanged(UASInterface*,double,double,double,quint64)));
// connect(slugsMav, SIGNAL(slugsDiagnostic(UASInterface*,double,double,double,int16_t,int16_t,int16_t,quint64)),
// this, SLOT());
// Set this UAS as active if it is the first one // Set this UAS as active if it is the first one
if(activeUAS == 0) if(activeUAS == 0)

16
src/ui/SlugsDataSensorView.h

@ -126,14 +126,14 @@ public slots:
* *
* Adds the UAS and makes all the correct connections for data display on the Widgets * Adds the UAS and makes all the correct connections for data display on the Widgets
*/ */
void slugsDiagnosticMessageChanged(UASInterface* uasTemp, // void slugsDiagnosticMessageChanged(UASInterface* uasTemp,
double diagfl1, // double diagfl1,
double diagfl2, // double diagfl2,
double diagfl3, // double diagfl3,
int16_t diagsh1, // int16_t diagsh1,
int16_t diagsh2, // int16_t diagsh2,
int16_t diagsh3, // int16_t diagsh3,
quint64 time); // quint64 time);
protected: protected:
QTimer* updateTimer; QTimer* updateTimer;

Loading…
Cancel
Save