Commit 0f064266 authored by tecnosapiens's avatar tecnosapiens

finished the connection of signal of the slugs data in SlugsDataSensorView

parent 7ab17928
...@@ -169,11 +169,16 @@ void SlugsMAV::emitSignals (void){ ...@@ -169,11 +169,16 @@ void SlugsMAV::emitSignals (void){
case 2: case 2:
emit slugsAirData(uasId, mlAirData); emit slugsAirData(uasId, mlAirData);
emit slugsDiagnostic(uasId,mlDiagnosticData); emit slugsDiagnostic(uasId,mlDiagnosticData);
break; break;
case 3: case 3:
emit remoteControlChannelScaledChanged(0,(mlPilotConsoleData.de- 1000.0f)/1000.0f); emit remoteControlChannelScaledChanged(0,(mlPilotConsoleData.de- 1000.0f)/1000.0f);
emit remoteControlChannelScaledChanged(1,0.75); emit remoteControlChannelScaledChanged(1,(mlPilotConsoleData.dla- 1000.0f)/1000.0f);
emit remoteControlChannelScaledChanged(2,(mlPilotConsoleData.dr- 1000.0f)/1000.0f);
emit remoteControlChannelScaledChanged(3,(mlPilotConsoleData.dra- 1000.0f)/1000.0f);
emit remoteControlChannelScaledChanged(0,(mlPilotConsoleData.dt- 1000.0f)/1000.0f);
emit slugsPWM(uasId, mlPwmCommands); emit slugsPWM(uasId, mlPwmCommands);
break; break;
...@@ -185,11 +190,13 @@ void SlugsMAV::emitSignals (void){ ...@@ -185,11 +190,13 @@ void SlugsMAV::emitSignals (void){
case 5: case 5:
emit slugsFilteredData(uasId,mlFilteredData); emit slugsFilteredData(uasId,mlFilteredData);
emit slugsGPSDateTime(uasId, mlGpsDateTime); emit slugsGPSDateTime(uasId, mlGpsDateTime);
break; break;
case 6: case 6:
emit slugsActionAck(uasId,mlActionAck); emit slugsActionAck(uasId,mlActionAck);
emit emitGpsSignals(); emit emitGpsSignals();
break; break;
} }
...@@ -213,20 +220,30 @@ void SlugsMAV::emitSignals (void){ ...@@ -213,20 +220,30 @@ void SlugsMAV::emitSignals (void){
#ifdef MAVLINK_ENABLED_SLUGS #ifdef MAVLINK_ENABLED_SLUGS
void SlugsMAV::emitGpsSignals (void){ void SlugsMAV::emitGpsSignals (void){
if (mlGpsData.fix_type > 0){ qDebug()<<"After Emit GPS Signal"<<mlGpsData.fix_type;
//ToDo Uncomment if. it was comment only to test
// if (mlGpsData.fix_type > 0){
emit globalPositionChanged(this, emit globalPositionChanged(this,
mlGpsData.lon, mlGpsData.lon,
mlGpsData.lat, mlGpsData.lat,
mlGpsData.alt, mlGpsData.alt,
0.0); 0.0);
// Smaller than threshold and not NaN emit slugsGPSCogSog(uasId,mlGpsData.hdg, mlGpsData.v);
if (mlGpsData.v < 1000000 && mlGpsData.v == mlGpsData.v){
emit speedChanged(this, (double)mlGpsData.v, 0.0, 0.0, 0.0); // // Smaller than threshold and not NaN
} else { // if (mlGpsData.v < 1000000 && mlGpsData.v == mlGpsData.v){
emit textMessageReceived(uasId, uasId, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(mlGpsData.v)); // // emit speedChanged(this, (double)mlGpsData.v, 0.0, 0.0, 0.0);
}
} // }
// else {
// emit textMessageReceived(uasId, uasId, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(mlGpsData.v));
// }
//}
} }
void SlugsMAV::emitPidSignal() void SlugsMAV::emitPidSignal()
......
...@@ -47,6 +47,7 @@ public slots: ...@@ -47,6 +47,7 @@ public slots:
signals: signals:
void slugsRawImu(int uasId, const mavlink_raw_imu_t& rawData); void slugsRawImu(int uasId, const mavlink_raw_imu_t& rawData);
void slugsGPSCogSog(int uasId, double cog, double sog);
#ifdef MAVLINK_ENABLED_SLUGS #ifdef MAVLINK_ENABLED_SLUGS
...@@ -67,6 +68,8 @@ signals: ...@@ -67,6 +68,8 @@ signals:
void slugsBootMsg(int uasId, mavlink_boot_t& boot); void slugsBootMsg(int uasId, mavlink_boot_t& boot);
void slugsAttitude(int uasId, mavlink_attitude_t& attitude); void slugsAttitude(int uasId, mavlink_attitude_t& attitude);
#endif #endif
protected: protected:
......
...@@ -328,6 +328,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -328,6 +328,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "Vz", pos.vz, time); emit valueChanged(uasId, "Vz", pos.vz, time);
emit localPositionChanged(this, pos.x, pos.y, pos.z, time); emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
emit speedChanged(this, pos.vx, pos.vy, pos.vz, time); emit speedChanged(this, pos.vx, pos.vy, pos.vz, time);
// qDebug()<<"Local Position = "<<pos.x<<" - "<<pos.y<<" - "<<pos.z;
// qDebug()<<"Speed Local Position = "<<pos.vx<<" - "<<pos.vy<<" - "<<pos.vz;
//emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time); //emit attitudeChanged(this, pos.roll, pos.pitch, pos.yaw, time);
// Set internal state // Set internal state
if (!positionLock) if (!positionLock)
......
...@@ -79,16 +79,16 @@ public: ...@@ -79,16 +79,16 @@ public:
/** @brief Get the links associated with this robot */ /** @brief Get the links associated with this robot */
QList<LinkInterface*>* getLinks(); QList<LinkInterface*>* getLinks();
double getLocalX() const { return localX; }; double getLocalX() const { return localX; }
double getLocalY() const { return localY; }; double getLocalY() const { return localY; }
double getLocalZ() const { return localZ; }; double getLocalZ() const { return localZ; }
double getLatitude() const { return latitude; }; double getLatitude() const { return latitude; }
double getLongitude() const { return longitude; }; double getLongitude() const { return longitude; }
double getAltitude() const { return altitude; }; double getAltitude() const { return altitude; }
double getRoll() const { return roll; }; double getRoll() const { return roll; }
double getPitch() const { return pitch; }; double getPitch() const { return pitch; }
double getYaw() const { return yaw; }; double getYaw() const { return yaw; }
friend class UASWaypointManager; friend class UASWaypointManager;
......
...@@ -41,6 +41,8 @@ void SlugsDataSensorView::addUAS(UASInterface* uas) ...@@ -41,6 +41,8 @@ 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(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugsGlobalPositionChanged(UASInterface*,double,double,double,quint64))); connect(slugsMav, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(slugsGlobalPositionChanged(UASInterface*,double,double,double,quint64)));
connect(slugsMav,SIGNAL(slugsGPSCogSog(int,double,double)),this,SLOT(slugsGPSCogSog(int,double,double)));
...@@ -53,7 +55,8 @@ void SlugsDataSensorView::addUAS(UASInterface* uas) ...@@ -53,7 +55,8 @@ void SlugsDataSensorView::addUAS(UASInterface* uas)
connect(slugsMav, SIGNAL(slugsPWM(int,const mavlink_pwm_commands_t&)),this,SLOT(slugsPWMChanged(int,const mavlink_pwm_commands_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(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&))); connect(slugsMav, SIGNAL(slugsGPSDateTime(int,const mavlink_gps_date_time_t&)),this,SLOT(slugsGPSDateTimeChanged(int,const mavlink_gps_date_time_t&)));
connect(slugsMav,SIGNAL(slugsAirData(int,mavlink_air_data_t&)),this,SLOT(slugsAirDataChanged(int,mavlink_air_data_t&))); connect(slugsMav,SIGNAL(slugsAirData(int, const mavlink_air_data_t&)),this,SLOT(slugsAirDataChanged(int, const mavlink_air_data_t&)));
#endif // MAVLINK_ENABLED_SLUGS #endif // MAVLINK_ENABLED_SLUGS
// Set this UAS as active if it is the first one // Set this UAS as active if it is the first one
...@@ -70,6 +73,15 @@ void SlugsDataSensorView::slugRawDataChanged(int uasId, const mavlink_raw_imu_t ...@@ -70,6 +73,15 @@ void SlugsDataSensorView::slugRawDataChanged(int uasId, const mavlink_raw_imu_t
ui->m_Axr->setText(QString::number(rawData.xacc)); ui->m_Axr->setText(QString::number(rawData.xacc));
ui->m_Ayr->setText(QString::number(rawData.yacc)); ui->m_Ayr->setText(QString::number(rawData.yacc));
ui->m_Azr->setText(QString::number(rawData.zacc)); ui->m_Azr->setText(QString::number(rawData.zacc));
ui->m_Mxr->setText(QString::number(rawData.xmag));
ui->m_Myr->setText(QString::number(rawData.ymag));
ui->m_Mzr->setText(QString::number(rawData.zmag));
ui->m_Gxr->setText(QString::number(rawData.xgyro));
ui->m_Gyr->setText(QString::number(rawData.ygyro));
ui->m_Gzr->setText(QString::number(rawData.zgyro));
} }
void SlugsDataSensorView::setActiveUAS(UASInterface* uas){ void SlugsDataSensorView::setActiveUAS(UASInterface* uas){
...@@ -86,9 +98,13 @@ void SlugsDataSensorView::slugsGlobalPositionChanged(UASInterface *uas, ...@@ -86,9 +98,13 @@ void SlugsDataSensorView::slugsGlobalPositionChanged(UASInterface *uas,
Q_UNUSED(uas); Q_UNUSED(uas);
Q_UNUSED(time); Q_UNUSED(time);
ui->m_GpsLatitude->setText(QString::number(lat)); ui->m_GpsLatitude->setText(QString::number(lat));
ui->m_GpsLongitude->setText(QString::number(lon)); ui->m_GpsLongitude->setText(QString::number(lon));
ui->m_GpsHeight->setText(QString::number(alt)); ui->m_GpsHeight->setText(QString::number(alt));
qDebug()<<"GPS Position = "<<lat<<" - "<<lon<<" - "<<alt;
} }
...@@ -104,6 +120,8 @@ void SlugsDataSensorView::slugLocalPositionChanged(UASInterface* uas, ...@@ -104,6 +120,8 @@ void SlugsDataSensorView::slugLocalPositionChanged(UASInterface* uas,
ui->ed_y->setPlainText(QString::number(y)); ui->ed_y->setPlainText(QString::number(y));
ui->ed_z->setPlainText(QString::number(z)); ui->ed_z->setPlainText(QString::number(z));
//qDebug()<<"Local Position = "<<x<<" - "<<y<<" - "<<z;
} }
void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface* uas, void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface* uas,
...@@ -118,6 +136,9 @@ void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface* uas, ...@@ -118,6 +136,9 @@ void SlugsDataSensorView::slugSpeedLocalPositionChanged(UASInterface* uas,
ui->ed_vy->setPlainText(QString::number(vy)); ui->ed_vy->setPlainText(QString::number(vy));
ui->ed_vz->setPlainText(QString::number(vz)); ui->ed_vz->setPlainText(QString::number(vz));
//qDebug()<<"Speed Local Position = "<<vx<<" - "<<vy<<" - "<<vz;
} }
void SlugsDataSensorView::slugAttitudeChanged(UASInterface* uas, void SlugsDataSensorView::slugAttitudeChanged(UASInterface* uas,
...@@ -133,6 +154,8 @@ void SlugsDataSensorView::slugAttitudeChanged(UASInterface* uas, ...@@ -133,6 +154,8 @@ void SlugsDataSensorView::slugAttitudeChanged(UASInterface* uas,
ui->m_Pitch->setPlainText(QString::number(slugpitch)); ui->m_Pitch->setPlainText(QString::number(slugpitch));
ui->m_Yaw->setPlainText(QString::number(slugyaw)); ui->m_Yaw->setPlainText(QString::number(slugyaw));
qDebug()<<"Attitude change = "<<slugroll<<" - "<<slugpitch<<" - "<<slugyaw;
} }
...@@ -231,15 +254,37 @@ void SlugsDataSensorView::slugsFilteredDataChanged(int systemId, ...@@ -231,15 +254,37 @@ void SlugsDataSensorView::slugsFilteredDataChanged(int systemId,
void SlugsDataSensorView::slugsGPSDateTimeChanged(int systemId, void SlugsDataSensorView::slugsGPSDateTimeChanged(int systemId,
const mavlink_gps_date_time_t& gpsDateTime){ const mavlink_gps_date_time_t& gpsDateTime){
Q_UNUSED(systemId); Q_UNUSED(systemId);
ui->m_GpsDate->setText(QString::number(gpsDateTime.month) + "/" +
QString::number(gpsDateTime.day) + "/" + QString month, day;
month = QString::number(gpsDateTime.month);
day = QString::number(gpsDateTime.day);
if(gpsDateTime.month < 10) month = "0" + QString::number(gpsDateTime.month);
if(gpsDateTime.day < 10) day = "0" + QString::number(gpsDateTime.day);
ui->m_GpsDate->setText(day + "/" +
month + "/" +
QString::number(gpsDateTime.year)); QString::number(gpsDateTime.year));
ui->m_GpsTime->setText(QString::number(gpsDateTime.hour) + ":" + QString hour, min, sec;
QString::number(gpsDateTime.min) + ":" +
QString::number(gpsDateTime.sec)); hour = QString::number(gpsDateTime.hour);
min = QString::number(gpsDateTime.min);
sec = QString::number(gpsDateTime.sec);
if(gpsDateTime.hour < 10) hour = "0" + QString::number(gpsDateTime.hour);
if(gpsDateTime.min < 10) min = "0" + QString::number(gpsDateTime.min);
if(gpsDateTime.sec < 10) sec = "0" + QString::number(gpsDateTime.sec);
ui->m_GpsTime->setText(hour + ":" +
min + ":" +
sec);
ui->m_GpsSat->setText(QString::number(gpsDateTime.visSat)); ui->m_GpsSat->setText(QString::number(gpsDateTime.visSat));
} }
/** /**
...@@ -252,8 +297,31 @@ void SlugsDataSensorView::slugsAirDataChanged(int systemId, const mavlink_air_da ...@@ -252,8 +297,31 @@ void SlugsDataSensorView::slugsAirDataChanged(int systemId, const mavlink_air_da
ui->ed_static->setText(QString::number(airData.staticPressure)); ui->ed_static->setText(QString::number(airData.staticPressure));
ui->ed_temp->setText(QString::number(airData.temperature)); ui->ed_temp->setText(QString::number(airData.temperature));
// qDebug()<<"Air Data = "<<airData.dynamicPressure<<" - "
// <<airData.staticPressure<<" - "
// <<airData.temperature;
} }
/**
* @brief set COG and SOG values
*
* COG and SOG GPS display on the Widgets
*/
void SlugsDataSensorView::slugsGPSCogSog(int systemId,
double cog,
double sog)
{
Q_UNUSED(systemId);
ui->m_GpsCog->setText(QString::number(cog));
ui->m_GpsSog->setText(QString::number(sog));
}
......
...@@ -70,6 +70,9 @@ public slots: ...@@ -70,6 +70,9 @@ public slots:
void setActiveUAS(UASInterface* uas); void setActiveUAS(UASInterface* uas);
/**
* @brief Updates the Raw Data widget
*/
void slugRawDataChanged (int uasId, const mavlink_raw_imu_t& rawData); void slugRawDataChanged (int uasId, const mavlink_raw_imu_t& rawData);
#ifdef MAVLINK_ENABLED_SLUGS #ifdef MAVLINK_ENABLED_SLUGS
...@@ -115,6 +118,16 @@ public slots: ...@@ -115,6 +118,16 @@ public slots:
double alt, double alt,
quint64 time); quint64 time);
/**
* @brief set COG and SOG values
*
* COG and SOG GPS display on the Widgets
*/
void slugsGPSCogSog(int systemId,
double cog,
double sog);
/** /**
* @brief Updates the CPU load widget - 170 * @brief Updates the CPU load widget - 170
...@@ -174,6 +187,9 @@ public slots: ...@@ -174,6 +187,9 @@ public slots:
#endif // MAVLINK_ENABLED_SLUGS #endif // MAVLINK_ENABLED_SLUGS
protected: protected:
......
...@@ -35,7 +35,7 @@ ...@@ -35,7 +35,7 @@
<item row="0" column="0"> <item row="0" column="0">
<widget class="QTabWidget" name="SlugsSensorView_tabWidget"> <widget class="QTabWidget" name="SlugsSensorView_tabWidget">
<property name="currentIndex"> <property name="currentIndex">
<number>2</number> <number>1</number>
</property> </property>
<widget class="QWidget" name="tab"> <widget class="QWidget" name="tab">
<attribute name="title"> <attribute name="title">
......
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