SlugsDataSensorView.cc 10.2 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 13
SlugsDataSensorView::SlugsDataSensorView(QWidget *parent) :
    QWidget(parent),
    ui(new Ui::SlugsDataSensorView)
{
    ui->setupUi(this);
14

15
    activeUAS = NULL;
16

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




22 23 24 25 26 27 28 29 30
}

SlugsDataSensorView::~SlugsDataSensorView()
{
    delete ui;
}

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

33
  if (slugsMav != NULL) {
34

35
    connect(slugsMav, SIGNAL(slugsRawImu(int, const mavlink_raw_imu_t&)), this, SLOT(slugRawDataChanged(int, const mavlink_raw_imu_t&)));
36

37
    #ifdef MAVLINK_ENABLED_SLUGS
38 39

        //connect standar messages
40
    connect(slugsMav, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugLocalPositionChanged(UASInterface*,double,double,double,quint64)));
41 42 43
    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)));
44 45 46



47
        //connect slugs especial messages
48 49 50 51 52 53 54 55
    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&)));
56
    //connect(slugsMav,SIGNAL(slugsAirData(int,mavlink_air_data_t&)),this,SLOT())
tecnosapiens's avatar
tecnosapiens committed
57

58
    #endif // MAVLINK_ENABLED_SLUGS
59
        // Set this UAS as active if it is the first one
60
    if(activeUAS == 0) {
61 62
            activeUAS = uas;
        }
63

64 65 66
    }
}

67 68
void SlugsDataSensorView::slugRawDataChanged(int uasId, const mavlink_raw_imu_t &rawData){
 Q_UNUSED(uasId);
69

70 71 72 73
 ui->m_Axr->setText(QString::number(rawData.xacc));
 ui->m_Ayr->setText(QString::number(rawData.yacc));
 ui->m_Azr->setText(QString::number(rawData.zacc));
}
74

75 76
void SlugsDataSensorView::setActiveUAS(UASInterface* uas){
    activeUAS = uas;
77 78
}

79 80
#ifdef MAVLINK_ENABLED_SLUGS

81 82 83 84
void SlugsDataSensorView::slugsGlobalPositionChanged(UASInterface *uas,
                                                     double lat,
                                                     double lon,
                                                     double alt,
85 86 87
                                                     quint64 time) {
 Q_UNUSED(uas);
 Q_UNUSED(time);
88

89 90 91
 ui->m_GpsLatitude->setText(QString::number(lat));
 ui->m_GpsLongitude->setText(QString::number(lon));
 ui->m_GpsHeight->setText(QString::number(alt));
92 93 94 95
}


void SlugsDataSensorView::slugLocalPositionChanged(UASInterface* uas,
96 97 98
                                                   double x,
                                                   double y,
                                                   double z,
99 100 101
                                                   quint64 time) {
  Q_UNUSED(uas);
  Q_UNUSED(time);
102

103 104 105
  ui->ed_x->setPlainText(QString::number(x));
  ui->ed_y->setPlainText(QString::number(y));
  ui->ed_z->setPlainText(QString::number(z));
106 107 108

}

109
void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface* uas,
110 111 112
                                                        double vx,
                                                        double vy,
                                                        double vz,
113
                                                        quint64 time) {
114
    Q_UNUSED( uas);
115 116 117 118 119
  Q_UNUSED(time);

  ui->ed_vx->setPlainText(QString::number(vx));
  ui->ed_vy->setPlainText(QString::number(vy));
  ui->ed_vz->setPlainText(QString::number(vz));
120 121 122

}

123
void SlugsDataSensorView::slugAttitudeChanged(UASInterface* uas,
124 125 126 127
                                              double slugroll,
                                              double slugpitch,
                                              double slugyaw,
                                              quint64 time)
128
{
129
    Q_UNUSED( uas);
130
    Q_UNUSED(time);
131

132 133 134
    ui->m_Roll->setPlainText(QString::number(slugroll));
    ui->m_Pitch->setPlainText(QString::number(slugpitch));
    ui->m_Yaw->setPlainText(QString::number(slugyaw));
135

136
}
137

138

139 140
void SlugsDataSensorView::slugsSensorBiasChanged(int systemId,
                                                 const mavlink_sensor_bias_t& sensorBias){
141
     Q_UNUSED( systemId);
142

143 144 145 146 147 148
  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));
149 150 151

}

152

153
void SlugsDataSensorView::slugsDiagnosticMessageChanged(int systemId,
154
                                                        const mavlink_diagnostic_t& diagnostic){
155 156
    Q_UNUSED(systemId);

157 158 159
  ui->m_Fl1->setText(QString::number(diagnostic.diagFl1));
  ui->m_Fl2->setText(QString::number(diagnostic.diagFl2));
  ui->m_Fl3->setText(QString::number(diagnostic.diagFl2));
160

161 162 163
  ui->m_Sh1->setText(QString::number(diagnostic.diagSh1));
  ui->m_Sh2->setText(QString::number(diagnostic.diagSh2));
  ui->m_Sh3->setText(QString::number(diagnostic.diagSh3));
164 165 166 167
}


void SlugsDataSensorView::slugsCpuLoadChanged(int systemId,
168
                                              const mavlink_cpu_load_t& cpuLoad){
169
     Q_UNUSED(systemId);
170 171 172
  ui->ed_sens->setText(QString::number(cpuLoad.sensLoad));
  ui->ed_control->setText(QString::number(cpuLoad.ctrlLoad));
  ui->ed_batvolt->setText(QString::number(cpuLoad.batVolt));
173 174 175
}

void SlugsDataSensorView::slugsNavegationChanged(int systemId,
176
                                                 const mavlink_slugs_navigation_t& slugsNavigation){
177
     Q_UNUSED(systemId);
178 179 180 181 182 183 184 185 186
  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));
187 188 189 190 191
}



void SlugsDataSensorView::slugsDataLogChanged(int systemId,
192
                                              const mavlink_data_log_t& dataLog){
193
     Q_UNUSED(systemId);
194 195 196 197 198 199
  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));
200 201 202
}

void SlugsDataSensorView::slugsPWMChanged(int systemId,
203
                                          const mavlink_pwm_commands_t& pwmCommands){
204
       Q_UNUSED(systemId);
205 206 207 208 209 210 211 212 213
  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));
214 215 216 217

}

void SlugsDataSensorView::slugsFilteredDataChanged(int systemId,
218
                                                   const mavlink_filtered_data_t& filteredData){
219
    Q_UNUSED(systemId);
220 221 222 223 224 225 226 227 228
  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));
229 230 231
}

void SlugsDataSensorView::slugsGPSDateTimeChanged(int systemId,
232
                                                  const mavlink_gps_date_time_t& gpsDateTime){
233
    Q_UNUSED(systemId);
234 235 236
  ui->m_GpsDate->setText(QString::number(gpsDateTime.month) + "/" +
                         QString::number(gpsDateTime.day) + "/" +
                         QString::number(gpsDateTime.year));
237

238 239 240
  ui->m_GpsTime->setText(QString::number(gpsDateTime.hour) + ":" +
                         QString::number(gpsDateTime.min) + ":" +
                         QString::number(gpsDateTime.sec));
241

242
  ui->m_GpsSat->setText(QString::number(gpsDateTime.visSat));
243
}
244

245 246 247 248 249 250 251 252 253 254 255 256
/**
     * @brief Updates the air data widget - 171
*/
void SlugsDataSensorView::slugsAirDataChanged(int systemId, const mavlink_air_data_t &airData)
{
     Q_UNUSED(systemId);

     //ToDo add widget to view value


}

257 258


259
#endif // MAVLINK_ENABLED_SLUGS