Commit 2226a433 authored by Mariano Lizarraga's avatar Mariano Lizarraga

Working on new messages and gui updates which are time based instead of reception based

parent 6d994de4
......@@ -139,7 +139,6 @@ FORMS += src/ui/MainWindow.ui \
src/ui/WaypointGlobalView.ui \
src/ui/SlugsDataSensorView.ui \
src/ui/SlugsHilSim.ui \
src/ui/SlugsDataSensorView.ui \
src/ui/SlugsPIDControl.ui
INCLUDEPATH += src \
src/ui \
......
#ifndef CONFIGURATION_H
#define CONFIGURATION_H
#include "mavlink.h"
/** @brief Polling interval in ms */
#ifdef MAVLINK_ENABLED_SLUGS_MESSAGES_QGC
#ifdef MAVLINK_ENABLED_SLUGS
#define SERIAL_POLL_INTERVAL 7
#else
#define SERIAL_POLL_INTERVAL 2
......
This diff is collapsed.
......@@ -26,7 +26,9 @@ This file is part of the QGROUNDCONTROL project
#include "UAS.h"
#include "mavlink.h"
#include <QTimer>
#define SLUGS_UPDATE_RATE 100 // in ms
class SlugsMAV : public UAS
{
Q_OBJECT
......@@ -38,109 +40,79 @@ public slots:
/** @brief Receive a MAVLink message from this MAV */
void receiveMessage(LinkInterface* link, mavlink_message_t message);
void emitSignals (void);
signals:
// ESPECIAL SLUGS MESSAGE
void slugsCPULoad(int systemId,
uint8_t sensLoad,
uint8_t ctrlLoad,
uint8_t batVolt,
quint64 time);
void slugsAirData(int systemId,
float dinamicPressure,
float staticPresure,
uint16_t temperature,
quint64 time);
void slugsSensorBias(int systemId,
double axBias,
double ayBias,
double azBias,
double gxBias,
double gyBias,
double gzBias,
quint64 time);
void slugsDiagnostic(int systemId,
double diagFl1,
double diagFl2,
double diagFl3,
int16_t diagSh1,
int16_t diagSh2,
int16_t diagSh3,
quint64 time);
void slugsPilotConsolePWM(int systemId,
uint16_t dt,
uint16_t dla,
uint16_t dra,
uint16_t dr,
uint16_t de,
quint64 time);
void slugsPWM(int systemId,
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);
void slugsNavegation(int systemId,
double u_m,
double phi_c,
double theta_c,
double psiDot_c,
double ay_body,
double totalDist,
double dist2Go,
uint8_t fromWP,
uint8_t toWP,
quint64 time);
void slugsDataLog(int systemId,
double logfl_1,
double logfl_2,
double logfl_3,
double logfl_4,
double logfl_5,
double logfl_6,
quint64 time);
void slugsFilteredData(int systemId,
double filaX,
double filaY,
double filaZ,
double filgX,
double filgY,
double filgZ,
double filmX,
double filmY,
double filmZ,
quint64 time);
void slugsGPSDateTime(int systemId,
uint8_t gpsyear,
uint8_t gpsmonth,
uint8_t gpsday,
uint8_t gpshour,
uint8_t gpsmin,
uint8_t gpssec,
uint8_t gpsvisSat,
quint64 time);
void slugsActionAck(int systemId,
uint8_t action,
uint8_t result);
void slugsRawImu(int uasId, const mavlink_raw_imu_t& rawData);
#ifdef MAVLINK_ENABLED_SLUGS
void slugsCPULoad(int systemId, const mavlink_cpu_load_t& cpuLoad);
void slugsAirData(int systemId, const mavlink_air_data_t& airData);
void slugsSensorBias(int systemId, const mavlink_sensor_bias_t& sensorBias);
void slugsDiagnostic(int systemId, const mavlink_diagnostic_t& diagnostic);
void slugsPilotConsolePWM(int systemId, const mavlink_pilot_console_t& pilotConsole);
void slugsPWM(int systemId, const mavlink_pwm_commands_t& pwmCommands);
void slugsNavegation(int systemId, const mavlink_slugs_navigation_t& slugsNavigation);
void slugsDataLog(int systemId, const mavlink_data_log_t& dataLog);
void slugsFilteredData(int systemId, const mavlink_filtered_data_t& filteredData);
void slugsGPSDateTime(int systemId, const mavlink_gps_date_time_t& gpsDateTime);
void slugsActionAck(int systemId, const mavlink_action_ack_t& actionAck);
void slugsBootMsg(int uasId, mavlink_boot_t& boot);
void slugsAttitude(int uasId, mavlink_attitude_t& attitude);
#endif
protected:
typedef struct _mavlink_pid_values_t {
float P[11];
float I[11];
float D[11];
}mavlink_pid_values_t;
unsigned char updateRoundRobin;
QTimer* widgetTimer;
mavlink_raw_imu_t mlRawImuData;
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_gps_raw_t mlGpsData;
mavlink_attitude_t mlAttitude;
mavlink_cpu_load_t mlCpuLoadData;
mavlink_air_data_t mlAirData;
mavlink_sensor_bias_t mlSensorBiasData;
mavlink_diagnostic_t mlDiagnosticData;
mavlink_pilot_console_t mlPilotConsoleData;
mavlink_filtered_data_t mlFilteredData;
mavlink_boot_t mlBoot;
mavlink_gps_date_time_t mlGpsDateTime;
mavlink_mid_lvl_cmds_t mlMidLevelCommands;
mavlink_set_mode_t mlApMode;
mavlink_pwm_commands_t mlPwmCommands;
mavlink_pid_values_t mlPidValues;
mavlink_pid_t mlSinglePid;
mavlink_slugs_navigation_t mlNavigation;
mavlink_data_log_t mlDataLog;
mavlink_ctrl_srfc_pt_t mlPassthrough;
mavlink_action_ack_t mlActionAck;
mavlink_slugs_action_t mlAction;
private:
void emitGpsSignals (void);
int uasId;
#endif // if SLUGS
};
......
......@@ -224,8 +224,14 @@ void MainWindow::connectWidgets()
connect(waypointsDockWidget->widget(), SIGNAL(changePositionWPGlobalBySpinBox(int,float,float)), mapWidget, SLOT(changeGlobalWaypointPositionBySpinBox(int,float,float)));
}
if (slugsHilSimWidget->widget()){
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), dynamic_cast<SlugsHilSim*>(slugsHilSimWidget->widget()), SLOT(activeUasSet(UASInterface*)) );
if (slugsHilSimWidget && slugsHilSimWidget->widget()){
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
slugsHilSimWidget->widget(), SLOT(activeUasSet(UASInterface*)));
}
if (slugsDataWidget && slugsDataWidget->widget()){
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
slugsDataWidget->widget(), SLOT(setActiveUAS(UASInterface*)));
}
......@@ -552,16 +558,16 @@ void MainWindow::UASCreated(UASInterface* uas)
PxQuadMAV* mav = dynamic_cast<PxQuadMAV*>(uas);
if (mav) loadPixhawkView();
SlugsMAV* mav2 = dynamic_cast<SlugsMAV*>(uas);
if (mav2)
{
dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget())->addUAS(uas);
loadSlugsView();
if (slugsDataWidget) {
SlugsDataSensorView* dataWidget = dynamic_cast<SlugsDataSensorView*>(slugsDataWidget->widget());
if (dataWidget) {
SlugsMAV* mav2 = dynamic_cast<SlugsMAV*>(uas);
if (mav2) {
dataWidget->addUAS(uas);
loadSlugsView();
}
}
}
}
}
......
This diff is collapsed.
......@@ -36,6 +36,7 @@ This file is part of the QGROUNDCONTROL project
#include "UASInterface.h"
#include "SlugsMAV.h"
#include "mavlink.h"
namespace Ui {
class SlugsDataSensorView;
......@@ -67,17 +68,10 @@ public slots:
*/
void setActiveUAS(UASInterface* uas);
/**
* @brief Adds the UAS for data display
*
* Adds the UAS and makes all the correct connections for data display on the Widgets
*/
void refresh();
void slugRawDataChanged (int uasId, const mavlink_raw_imu_t& rawData);
#ifdef MAVLINK_ENABLED_SLUGS
/**
* @brief Adds the UAS for data display
*
......@@ -120,240 +114,62 @@ public slots:
double alt,
quint64 time);
/**
* @brief Adds the UAS for data display
*
* Adds the UAS and makes all the correct connections for data display on the Widgets
* @brief Updates the sensor bias widget
*/
void slugsSensorBiasChanged(int systemId,
double axb,
double ayb,
double azb,
double gxb,
double gyb,
double gzb,
quint64 time);
const mavlink_sensor_bias_t& sensorBias);
/**
* @brief Adds the UAS for data display
*
* Adds the UAS and makes all the correct connections for data display on the Widgets
* @brief Updates the diagnostic widget
*/
void slugsDiagnosticMessageChanged(int systemId,
double diagfl1,
double diagfl2,
double diagfl3,
int16_t diagsh1,
int16_t diagsh2,
int16_t diagsh3,
quint64 time);
const mavlink_diagnostic_t& diagnostic);
/**
* @brief Adds the UAS for data display
*
* Adds the UAS and makes all the correct connections for data display on the Widgets
* @brief Updates the CPU load widget
*/
void slugsCpuLoadChanged(int systemId,
uint8_t sensload,
uint8_t ctrlload,
uint8_t batvolt,
quint64 time);
const mavlink_cpu_load_t& cpuLoad);
/**
* @brief Adds the UAS for data display
*
* Adds the UAS and makes all the correct connections for data display on the Widgets
* @brief Updates the Navigation widget
*/
void slugsNavegationChanged(int systemId,
double navu_m,
double navphi_c,
double navtheta_c,
double navpsiDot_c,
double navay_body,
double navtotalDist,
double navdist2Go,
uint8_t navfromWP,
uint8_t navtoWP,
quint64 time);
const mavlink_slugs_navigation_t& slugsNavigation);
/**
* @brief Adds the UAS for data display
*
* Adds the UAS and makes all the correct connections for data display on the Widgets
* @brief Updates the Data Log widget
*/
void slugsDataLogChanged(int systemId,
double logfl_1,
double logfl_2,
double logfl_3,
double logfl_4,
double logfl_5,
double logfl_6,
quint64 time);
const mavlink_data_log_t& dataLog);
/**
* @brief Adds the UAS for data display
*
* Adds the UAS and makes all the correct connections for data display on the Widgets
* @brief Updates the PWM Commands widget
*/
void slugsPWMChanged(int systemId,
uint16_t vdt_c,
uint16_t vdla_c,
uint16_t vdra_c,
uint16_t vdr_c,
uint16_t vdle_c,
uint16_t vdre_c,
uint16_t vdlf_c,
uint16_t vdrf_c,
uint16_t vda1_c,
uint16_t vda2_c,
quint64 time);
const mavlink_pwm_commands_t& pwmCommands);
/**
* @brief Adds the UAS for data display
*
* Adds the UAS and makes all the correct connections for data display on the Widgets
* @brief Updates the filtered sensor measurements widget
*/
void slugsFilteredDataChanged(int systemId,
double filaX,
double filaY,
double filaZ,
double filgX,
double filgY,
double filgZ,
double filmX,
double filmY,
double filmZ,
quint64 time);
const mavlink_filtered_data_t& filteredData);
/**
* @brief Updates the gps Date Time widget
*/
void slugsGPSDateTimeChanged(int systemId,
uint8_t gpsyear,
uint8_t gpsmonth,
uint8_t gpsday,
uint8_t gpshour,
uint8_t gpsmin,
uint8_t gpssec,
uint8_t gpsvisSat,
quint64 time);
const mavlink_gps_date_time_t& gpsDateTime);
#endif // MAVLINK_ENABLED_SLUGS
protected:
QTimer* updateTimer;
UASInterface* activeUAS;
//Global Position
double Latitude;
double Longitude;
double Height;
quint64 timeGlobalPosition;
// Position and Attitude
//Position
double Xpos;
double Ypos;
double Zpos;
quint64 TimeActualPosition;
//Speed
double VXpos;
double VYpos;
double VZpos;
quint64 TimeActualSpeed;
//Attitude
double roll;
double pitch;
double yaw;
quint64 TimeActualAttitude;
//Sensor Biases
//Acelerometer
double Axb;
double Ayb;
double Azb;
//Gyro
double Gxb;
double Gyb;
double Gzb;
quint64 TimeActualBias;
//Diagnostic
double diagFl1;
double diagFl2;
double diagFl3;
int16_t diagSh1;
int16_t diagSh2;
int16_t diagSh3;
quint64 timeDiagnostic;
//CPU Load
uint8_t sensLoad;
uint8_t ctrlLoad;
uint8_t batVolt;
quint64 timeCpuLoad;
//navigation data
double u_m;
double phi_c;
double theta_c;
double psiDot_c;
double ay_body;
double totalDist;
double dist2Go;
uint8_t fromWP;
uint8_t toWP;
quint64 timeNavigation;
// Data Log
double Logfl_1;
double Logfl_2;
double Logfl_3;
double Logfl_4;
double Logfl_5;
double Logfl_6;
quint64 timeDataLog;
//pwm commands
uint16_t dt_c; ///< AutoPilot's throttle command
uint16_t dla_c; ///< AutoPilot's left aileron command
uint16_t dra_c; ///< AutoPilot's right aileron command
uint16_t dr_c; ///< AutoPilot's rudder command
uint16_t dle_c; ///< AutoPilot's left elevator command
uint16_t dre_c; ///< AutoPilot's right elevator command
uint16_t dlf_c; ///< AutoPilot's left flap command
uint16_t drf_c; ///< AutoPilot's right flap command
uint16_t aux1; ///< AutoPilot's aux1 command
uint16_t aux2; ///< AutoPilot's aux2 command
quint64 timePWMCommand;
//filtered data
double aX; ///< Accelerometer X value (m/s^2)
double aY; ///< Accelerometer Y value (m/s^2)
double aZ; ///< Accelerometer Z value (m/s^2)
double gX; ///< Gyro X value (rad/s)
double gY; ///< Gyro Y value (rad/s)
double gZ; ///< Gyro Z value (rad/s)
double mX; ///< Magnetometer X (normalized to 1)
double mY; ///< Magnetometer Y (normalized to 1)
double mZ; ///< Magnetometer Z (normalized to 1)
quint64 timeFiltered;
//gps date and time
uint8_t year; ///< Year reported by Gps
uint8_t month; ///< Month reported by Gps
uint8_t day; ///< Day reported by Gps
uint8_t hour; ///< Hour reported by Gps
uint8_t min; ///< Min reported by Gps
uint8_t sec; ///< Sec reported by Gps
uint8_t visSat; ///< Visible sattelites reported by Gps
quint64 timeGPSDateTime;
private:
Ui::SlugsDataSensorView *ui;
void loadParameters();
};
......
This diff is collapsed.
......@@ -44,12 +44,13 @@ void SlugsPIDControl::activeUasSet(UASInterface* uas)
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(uas);
#ifdef MAVLINK_ENABLED_SLUGS
if (slugsMav != NULL)
{
connect(slugsMav,SIGNAL(slugsActionAck(int,uint8_t,uint8_t)),this,SLOT(recibeMensaje(int,uint8_t,uint8_t)));
connect(slugsMav,SIGNAL(slugsActionAck(int,const mavlink_action_ack_t&)),this,SLOT(recibeMensaje(int,mavlink_action_ack_t)));
}
#endif // MAVLINK_ENABLED_SLUG
// Set this UAS as active if it is the first one
if(activeUAS == 0)
{
......@@ -339,7 +340,11 @@ void SlugsPIDControl::connect_Pitch2dT_LineEdit()
connect(ui->P2dT_FF_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_Pitch2dT_groupBox(QString)));
}
void SlugsPIDControl::recibeMensaje(int systemId, uint8_t action, uint8_t result)
#ifdef MAVLINK_ENABLED_SLUGS
void SlugsPIDControl::recibeMensaje(int systemId, const mavlink_action_ack_t& action)
{
ui->recepcion_label->setText(QString::number(action));
ui->recepcion_label->setText(QString::number(action.action));
}
#endif // MAVLINK_ENABLED_SLUGS
......@@ -6,7 +6,7 @@
#include "UASInterface.h"
#include "QGCMAVLink.h"
#include "SlugsMAV.h"
#include "mavlink.h"
namespace Ui {
class SlugsPIDControl;
......@@ -184,9 +184,11 @@ public slots:
//Create, send and get Messages PID
// void createMessagePID();
#ifdef MAVLINK_ENABLED_SLUGS
void recibeMensaje(int systemId, uint8_t action, uint8_t result);
void recibeMensaje(int systemId, const mavlink_action_ack_t& action);
#endif // MAVLINK_ENABLED_SLUG
private:
Ui::SlugsPIDControl *ui;
......
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