SlugsDataSensorView.cc 9.89 KB
Newer Older
1 2 3 4
#include "SlugsDataSensorView.h"
#include "ui_SlugsDataSensorView.h"

#include <UASManager.h>
tecnosapiens's avatar
tecnosapiens committed
5
#include "SlugsMAV.h"
6

7 8
#include <QDebug>

9 10 11 12
SlugsDataSensorView::SlugsDataSensorView(QWidget *parent) :
    QWidget(parent),
    ui(new Ui::SlugsDataSensorView)
{
13
  ui->setupUi(this);
14

15
  activeUAS = NULL;
16

17
  this->setVisible(false);
18 19 20 21
}

SlugsDataSensorView::~SlugsDataSensorView()
{
22
  delete ui;
23 24 25 26
}

void SlugsDataSensorView::addUAS(UASInterface* uas)
{
27
  SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(uas);
tecnosapiens's avatar
tecnosapiens committed
28

29
  if (slugsMav != NULL) {
30

31
    connect(slugsMav, SIGNAL(slugsRawImu(int, const mavlink_raw_imu_t&)), this, SLOT(slugRawDataChanged(int, const mavlink_raw_imu_t&)));
32

33
    #ifdef MAVLINK_ENABLED_SLUGS
34

35 36 37 38 39
    //connect standar messages
    connect(slugsMav, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugLocalPositionChanged(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(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugsGlobalPositionChanged(UASInterface*,double,double,double,quint64)));
40 41 42



43 44 45 46 47 48 49 50 51
    //connect slugs especial messages
    connect(slugsMav, SIGNAL(slugsSensorBias(int,const mavlink_sensor_bias_t&)), this, SLOT(slugsSensorBiasChanged(int,const mavlink_sensor_bias_t&)));
    connect(slugsMav, SIGNAL(slugsDiagnostic(int,const mavlink_diagnostic_t&)), this, SLOT(slugsDiagnosticMessageChanged(int,const mavlink_diagnostic_t&)));
    connect(slugsMav, SIGNAL(slugsCPULoad(int,const mavlink_cpu_load_t&)), this, SLOT(slugsCpuLoadChanged(int,const mavlink_cpu_load_t&)));
    connect(slugsMav, SIGNAL(slugsNavegation(int,const mavlink_slugs_navigation_t&)),this,SLOT(slugsNavegationChanged(int,const mavlink_slugs_navigation_t&)));
    connect(slugsMav, SIGNAL(slugsDataLog(int,const mavlink_data_log_t&)), this, SLOT(slugsDataLogChanged(int,const mavlink_data_log_t&)));
    connect(slugsMav, SIGNAL(slugsPWM(int,const mavlink_pwm_commands_t&)),this,SLOT(slugsPWMChanged(int,const mavlink_pwm_commands_t&)));
    connect(slugsMav, SIGNAL(slugsFilteredData(int,const mavlink_filtered_data_t&)),this,SLOT(slugsFilteredDataChanged(int,const mavlink_filtered_data_t&)));
    connect(slugsMav, SIGNAL(slugsGPSDateTime(int,const mavlink_gps_date_time_t&)),this,SLOT(slugsGPSDateTimeChanged(int,const mavlink_gps_date_time_t&)));
tecnosapiens's avatar
tecnosapiens committed
52

53
    #endif // MAVLINK_ENABLED_SLUGS
54

55 56 57
    // Set this UAS as active if it is the first one
    if(activeUAS == 0) {
      activeUAS = uas;
58
    }
59

60
  }
61 62
}

63 64
void SlugsDataSensorView::slugRawDataChanged(int uasId, const mavlink_raw_imu_t &rawData){
 Q_UNUSED(uasId);
65

66 67 68 69
 ui->m_Axr->setText(QString::number(rawData.xacc));
 ui->m_Ayr->setText(QString::number(rawData.yacc));
 ui->m_Azr->setText(QString::number(rawData.zacc));
}
70

71 72
void SlugsDataSensorView::setActiveUAS(UASInterface* uas){
    activeUAS = uas;
73 74
}

75 76
#ifdef MAVLINK_ENABLED_SLUGS

77 78 79 80
void SlugsDataSensorView::slugsGlobalPositionChanged(UASInterface *uas,
                                                     double lat,
                                                     double lon,
                                                     double alt,
81 82 83
                                                     quint64 time) {
 Q_UNUSED(uas);
 Q_UNUSED(time);
84

85 86 87
 ui->m_GpsLatitude->setText(QString::number(lat));
 ui->m_GpsLongitude->setText(QString::number(lon));
 ui->m_GpsHeight->setText(QString::number(alt));
88 89 90 91
}


void SlugsDataSensorView::slugLocalPositionChanged(UASInterface* uas,
92 93 94
                                                   double x,
                                                   double y,
                                                   double z,
95 96 97
                                                   quint64 time) {
  Q_UNUSED(uas);
  Q_UNUSED(time);
98

99 100 101
  ui->ed_x->setPlainText(QString::number(x));
  ui->ed_y->setPlainText(QString::number(y));
  ui->ed_z->setPlainText(QString::number(z));
102 103 104

}

105
void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface* uas,
106 107 108
                                                        double vx,
                                                        double vy,
                                                        double vz,
109 110 111 112 113 114 115
                                                        quint64 time) {
  Q_UNUSED( uas);
  Q_UNUSED(time);

  ui->ed_vx->setPlainText(QString::number(vx));
  ui->ed_vy->setPlainText(QString::number(vy));
  ui->ed_vz->setPlainText(QString::number(vz));
116 117 118

}

119
void SlugsDataSensorView::slugAttitudeChanged(UASInterface* uas,
120 121 122 123
                                              double slugroll,
                                              double slugpitch,
                                              double slugyaw,
                                              quint64 time)
124
{
125
    Q_UNUSED( uas);
126
    Q_UNUSED(time);
127

128 129 130
    ui->m_Roll->setPlainText(QString::number(slugroll));
    ui->m_Pitch->setPlainText(QString::number(slugpitch));
    ui->m_Yaw->setPlainText(QString::number(slugyaw));
131

132
}
133

134

135 136 137
void SlugsDataSensorView::slugsSensorBiasChanged(int systemId,
                                                 const mavlink_sensor_bias_t& sensorBias){
  Q_UNUSED( systemId);
138

139 140 141 142 143 144
  ui->m_AxBiases->setText(QString::number(sensorBias.axBias));
  ui->m_AyBiases->setText(QString::number(sensorBias.ayBias));
  ui->m_AzBiases->setText(QString::number(sensorBias.azBias));
  ui->m_GxBiases->setText(QString::number(sensorBias.gxBias));
  ui->m_GyBiases->setText(QString::number(sensorBias.gyBias));
  ui->m_GzBiases->setText(QString::number(sensorBias.gzBias));
145 146 147

}

148
void SlugsDataSensorView::slugsDiagnosticMessageChanged(int systemId,
149 150
                                                        const mavlink_diagnostic_t& diagnostic){
  Q_UNUSED(systemId);
151

152 153 154 155 156 157 158
  ui->m_Fl1->setText(QString::number(diagnostic.diagFl1));
  ui->m_Fl2->setText(QString::number(diagnostic.diagFl2));
  ui->m_Fl3->setText(QString::number(diagnostic.diagFl2));
                                               
  ui->m_Sh1->setText(QString::number(diagnostic.diagSh1));
  ui->m_Sh2->setText(QString::number(diagnostic.diagSh2));
  ui->m_Sh3->setText(QString::number(diagnostic.diagSh3));
159 160 161 162
}


void SlugsDataSensorView::slugsCpuLoadChanged(int systemId,
163 164 165 166 167
                                              const mavlink_cpu_load_t& cpuLoad){
  Q_UNUSED(systemId);
  ui->ed_sens->setText(QString::number(cpuLoad.sensLoad));
  ui->ed_control->setText(QString::number(cpuLoad.ctrlLoad));
  ui->ed_batvolt->setText(QString::number(cpuLoad.batVolt));
168 169 170
}

void SlugsDataSensorView::slugsNavegationChanged(int systemId,
171 172 173 174 175 176 177 178 179 180 181
                                                 const mavlink_slugs_navigation_t& slugsNavigation){
  Q_UNUSED(systemId);
  ui->m_Um->setText(QString::number(slugsNavigation.u_m));
  ui->m_PhiC->setText(QString::number(slugsNavigation.phi_c));
  ui->m_PitchC->setText(QString::number(slugsNavigation.theta_c));
  ui->m_PsidC->setText(QString::number(slugsNavigation.psiDot_c));
  ui->m_AyBody->setText(QString::number(slugsNavigation.ay_body));
  ui->m_TotRun->setText(QString::number(slugsNavigation.totalDist));
  ui->m_DistToGo->setText(QString::number(slugsNavigation.dist2Go));
  ui->m_FromWP->setText(QString::number(slugsNavigation.fromWP));
  ui->m_ToWP->setText(QString::number(slugsNavigation.toWP));
182 183 184 185 186
}



void SlugsDataSensorView::slugsDataLogChanged(int systemId,
187 188 189 190 191 192 193 194
                                              const mavlink_data_log_t& dataLog){
  Q_UNUSED(systemId);
  ui->m_logFl1->setText(QString::number(dataLog.fl_1));
  ui->m_logFl2->setText(QString::number(dataLog.fl_2));
  ui->m_logFl3->setText(QString::number(dataLog.fl_3));
  ui->m_logFl4->setText(QString::number(dataLog.fl_4));
  ui->m_logFl5->setText(QString::number(dataLog.fl_5));
  ui->m_logFl6->setText(QString::number(dataLog.fl_6));
195 196 197
}

void SlugsDataSensorView::slugsPWMChanged(int systemId,
198 199 200 201 202 203 204 205 206 207 208
                                          const mavlink_pwm_commands_t& pwmCommands){
  Q_UNUSED(systemId);
  ui->m_pwmThro->setText(QString::number(pwmCommands.dt_c));
  ui->m_pwmAile->setText(QString::number(pwmCommands.dla_c));
  ui->m_pwmElev->setText(QString::number(pwmCommands.dle_c));
  ui->m_pwmRudd->setText(QString::number(pwmCommands.dr_c));

  ui->m_pwmThroTrim->setText(QString::number(pwmCommands.dre_c));
  ui->m_pwmAileTrim->setText(QString::number(pwmCommands.dlf_c));
  ui->m_pwmElevTrim->setText(QString::number(pwmCommands.drf_c));
  ui->m_pwmRuddTrim->setText(QString::number(pwmCommands.aux1));
209 210 211 212

}

void SlugsDataSensorView::slugsFilteredDataChanged(int systemId,
213 214 215 216 217 218 219 220 221 222 223
                                                   const mavlink_filtered_data_t& filteredData){
  Q_UNUSED(systemId);
  ui->m_Axf->setText(QString::number(filteredData.aX));
  ui->m_Ayf->setText(QString::number(filteredData.aY));
  ui->m_Azf->setText(QString::number(filteredData.aZ));
  ui->m_Gxf->setText(QString::number(filteredData.gX));
  ui->m_Gyf->setText(QString::number(filteredData.gY));
  ui->m_Gzf->setText(QString::number(filteredData.gZ));
  ui->m_Mxf->setText(QString::number(filteredData.mX));
  ui->m_Myf->setText(QString::number(filteredData.mY));
  ui->m_Mzf->setText(QString::number(filteredData.mZ));
224 225 226
}

void SlugsDataSensorView::slugsGPSDateTimeChanged(int systemId,
227 228 229 230 231
                                                  const mavlink_gps_date_time_t& gpsDateTime){
  Q_UNUSED(systemId);
  ui->m_GpsDate->setText(QString::number(gpsDateTime.month) + "/" +
                         QString::number(gpsDateTime.day) + "/" +
                         QString::number(gpsDateTime.year));
232

233 234 235
  ui->m_GpsTime->setText(QString::number(gpsDateTime.hour) + ":" +
                         QString::number(gpsDateTime.min) + ":" +
                         QString::number(gpsDateTime.sec));
236

237
  ui->m_GpsSat->setText(QString::number(gpsDateTime.visSat));
238
}
239 240

#endif // MAVLINK_ENABLED_SLUGS