Commit 915e3f3a authored by Alejandro's avatar Alejandro

Merge branch 'experimental' of git://128.168.1.167/malife/qgroundcontrol into experimental

parents 9ea3ca75 cfc36b0c
......@@ -146,7 +146,6 @@ FORMS += src/ui/MainWindow.ui \
src/ui/map3D/QGCGoogleEarthView.ui \
src/ui/SlugsDataSensorView.ui \
src/ui/SlugsHilSim.ui \
src/ui/SlugsPIDControl.ui \
src/ui/SlugsPadCameraControl.ui \
src/ui/uas/QGCUnconnectedInfoWidget.ui \
src/ui/designer/QGCToolWidget.ui \
......@@ -256,7 +255,6 @@ HEADERS += src/MG.h \
src/ui/map3D/QGCWebPage.h \
src/ui/SlugsDataSensorView.h \
src/ui/SlugsHilSim.h \
src/ui/SlugsPIDControl.h \
src/ui/SlugsPadCameraControl.h \
src/ui/QGCMainWindowAPConfigurator.h \
src/comm/MAVLinkSwarmSimulationLink.h \
......@@ -387,7 +385,6 @@ SOURCES += src/main.cc \
src/ui/map3D/QGCWebPage.cc \
src/ui/SlugsDataSensorView.cc \
src/ui/SlugsHilSim.cc \
src/ui/SlugsPIDControl.cpp \
src/ui/SlugsPadCameraControl.cpp \
src/ui/QGCMainWindowAPConfigurator.cc \
src/comm/MAVLinkSwarmSimulationLink.cc \
......
......@@ -26,14 +26,9 @@ SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) :
memset(&mlAirData, 0, sizeof(mavlink_air_data_t));
memset(&mlSensorBiasData, 0, sizeof(mavlink_sensor_bias_t));
memset(&mlDiagnosticData, 0, sizeof(mavlink_diagnostic_t));
memset(&mlPilotConsoleData, 0, sizeof(mavlink_pilot_console_t));
memset(&mlFilteredData ,0, sizeof(mavlink_filtered_data_t));
memset(&mlBoot ,0, sizeof(mavlink_boot_t));
memset(&mlGpsDateTime ,0, sizeof(mavlink_gps_date_time_t));
memset(&mlApMode ,0, sizeof(mavlink_set_mode_t));
memset(&mlPwmCommands ,0, sizeof(mavlink_pwm_commands_t));
memset(&mlPidValues ,0, sizeof(mavlink_pid_values_t));
memset(&mlSinglePid ,0, sizeof(mavlink_pid_t));
memset(&mlNavigation ,0, sizeof(mavlink_slugs_navigation_t));
memset(&mlDataLog ,0, sizeof(mavlink_data_log_t));
memset(&mlPassthrough ,0, sizeof(mavlink_ctrl_srfc_pt_t));
......@@ -106,14 +101,6 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_msg_diagnostic_decode(&message,&mlDiagnosticData);
break;
case MAVLINK_MSG_ID_PILOT_CONSOLE: //174
mavlink_msg_pilot_console_decode(&message,&mlPilotConsoleData);
break;
case MAVLINK_MSG_ID_PWM_COMMANDS: //175
mavlink_msg_pwm_commands_decode(&message,&mlPwmCommands);
break;
case MAVLINK_MSG_ID_SLUGS_NAVIGATION://176
mavlink_msg_slugs_navigation_decode(&message,&mlNavigation);
break;
......@@ -122,10 +109,6 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_msg_data_log_decode(&message,&mlDataLog);
break;
case MAVLINK_MSG_ID_FILTERED_DATA: //178
mavlink_msg_filtered_data_decode(&message,&mlFilteredData);
break;
case MAVLINK_MSG_ID_GPS_DATE_TIME: //179
mavlink_msg_gps_date_time_decode(&message,&mlGpsDateTime);
break;
......@@ -138,14 +121,6 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_msg_ctrl_srfc_pt_decode(&message, &mlPassthrough);
break;
case MAVLINK_MSG_ID_PID: //182
memset(&mlSinglePid,0,sizeof(mavlink_pid_t));
mavlink_msg_pid_decode(&message, &mlSinglePid);
// qDebug() << "\nSLUGS RECEIVED PID Message = "<<mlSinglePid.idx;
emit slugsPidValues(uasId, mlSinglePid);
break;
case MAVLINK_MSG_ID_SLUGS_ACTION: //183
mavlink_msg_slugs_action_decode(&message, &mlAction);
......@@ -196,26 +171,16 @@ void SlugsMAV::emitSignals (void){
break;
case 3:
emit remoteControlChannelScaledChanged(0,(mlPilotConsoleData.de- 1000.0f)/1000.0f);
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 slugsPWM(uasId, mlPwmCommands);
break;
case 4:
emit slugsNavegation(uasId, mlNavigation);
emit slugsDataLog(uasId, mlDataLog);
break;
case 5:
emit slugsFilteredData(uasId,mlFilteredData);
case 4:
emit slugsGPSDateTime(uasId, mlGpsDateTime);
break;
case 6:
case 5:
emit slugsActionAck(uasId,mlActionAck);
emit emitGpsSignals();
......@@ -256,29 +221,8 @@ void SlugsMAV::emitGpsSignals (void){
emit slugsGPSCogSog(uasId,mlGpsData.hdg, mlGpsData.v);
// // Smaller than threshold and not NaN
// if (mlGpsData.v < 1000000 && mlGpsData.v == 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()
{
// qDebug() << "\nSLUGS RECEIVED PID Message";
emit slugsPidValues(uasId, mlSinglePid);
}
mavlink_pwm_commands_t* SlugsMAV::getPwmCommands()
{
return &mlPwmCommands;
}
#endif // MAVLINK_ENABLED_SLUGS
......@@ -61,10 +61,6 @@ public slots:
void emitSignals (void);
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_pwm_commands_t* getPwmCommands();
#endif
signals:
void slugsRawImu(int uasId, const mavlink_raw_imu_t& rawData);
......@@ -76,11 +72,8 @@ signals:
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);
......@@ -97,11 +90,6 @@ signals:
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;
......@@ -116,15 +104,10 @@ protected:
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;
......
......@@ -1070,6 +1070,7 @@ void UAS::setHomePosition(double lat, double lon, double alt)
home.latitude = lat*1E7;
home.longitude = lon*1E7;
home.altitude = alt*1000;
qDebug() << "lat:" << home.latitude << " lon:" << home.longitude;
mavlink_message_t msg;
mavlink_msg_gps_set_global_origin_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &home);
sendMessage(msg);
......
......@@ -614,13 +614,6 @@ void MainWindow::buildSlugsWidgets()
addToToolsMenu (slugsDataWidget, tr("Telemetry Data"), SLOT(showToolWidget(bool)), MENU_SLUGS_DATA, Qt::RightDockWidgetArea);
}
if (!slugsPIDControlWidget)
{
slugsPIDControlWidget = new QDockWidget(tr("Slugs PID Control"), this);
slugsPIDControlWidget->setWidget(new SlugsPIDControl(this));
slugsPIDControlWidget->setObjectName("SLUGS_PID_CONTROL_DOCK_WIDGET");
addToToolsMenu (slugsPIDControlWidget, tr("PID Configuration"), SLOT(showToolWidget(bool)), MENU_SLUGS_PID, Qt::LeftDockWidgetArea);
}
if (!slugsHilSimWidget)
{
......@@ -1088,11 +1081,6 @@ void MainWindow::connectSlugsWidgets()
slugsDataWidget->widget(), SLOT(setActiveUAS(UASInterface*)));
}
if (slugsPIDControlWidget && slugsPIDControlWidget->widget()){
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
slugsPIDControlWidget->widget(), SLOT(activeUasSet(UASInterface*)));
}
if (controlParameterWidget && controlParameterWidget->widget()){
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)),
controlParameterWidget->widget(), SLOT(activeUasSet(UASInterface*)));
......
......@@ -70,8 +70,6 @@ This file is part of the QGROUNDCONTROL project
#include "SlugsDataSensorView.h"
#include "LogCompressor.h"
#include "SlugsPIDControl.h"
#include "SlugsHilSim.h"
#include "SlugsPadCameraControl.h"
......@@ -403,7 +401,6 @@ protected:
QPointer<QDockWidget> rcViewDockWidget;
QPointer<QDockWidget> hudDockWidget;
QPointer<QDockWidget> slugsDataWidget;
QPointer<QDockWidget> slugsPIDControlWidget;
QPointer<QDockWidget> slugsHilSimWidget;
QPointer<QDockWidget> slugsCamControlWidget;
......
......@@ -50,8 +50,8 @@ void SlugsDataSensorView::addUAS(UASInterface* uas)
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(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&)));
connect(slugsMav,SIGNAL(slugsAirData(int, const mavlink_air_data_t&)),this,SLOT(slugsAirDataChanged(int, const mavlink_air_data_t&)));
......
This diff is collapsed.
#ifndef SLUGSPIDCONTROL_H
#define SLUGSPIDCONTROL_H
#include <QWidget>
#include <QGroupBox>
#include "UASInterface.h"
#include "QGCMAVLink.h"
#include "SlugsMAV.h"
#include "mavlink.h"
#include <QTimer>
#include <QMutex>
namespace Ui {
class SlugsPIDControl;
}
class SlugsPIDControl : public QWidget
{
Q_OBJECT
public:
explicit SlugsPIDControl(QWidget *parent = 0);
~SlugsPIDControl();
public slots:
/**
* @brief Called when the a new UAS is set to active.
*
* Called when the a new UAS is set to active.
*
* @param uas The new active UAS
*/
void activeUasSet(UASInterface* uas);
/**
*/
void setRedColorStyle();
/**
* @brief Set color StyleSheet GREEN
*
* @param
*/
void setGreenColorStyle();
/**
* @brief Connect Set pushButtons to change the color GroupBox
*
* @param
*/
void connect_set_pushButtons();
/**
* @brief Connect Set pushButtons to change the color GroupBox
*
* @param
*/
void connect_get_pushButtons();
/**
* @brief Connect Edition Lines for PID Values
*
* @param
*/
void connect_editLinesPDIvalues();
/**
* @brief send a PDI request message to UAS
*
* @param
*/
void sendMessagePIDStatus(int PIDtype);
// Fuctions for Air Speed GroupBox
/**
* @brief Change color style to red when PID values of Air Speed are edited
*
*
* @param
*/
void changeColor_RED_AirSpeed_groupBox(QString text);
/**
* @brief Change color style to green when PID values of Air Speed are send to UAS
*
* @param
*/
void changeColor_GREEN_AirSpeed_groupBox();
/**
* @brief Connects the SIGNALS from the editline to SLOT changeColor_RED_AirSpeed_groupBox()
*
* @param
*/
void connect_AirSpeed_LineEdit();
/**
* @brief get message PID Air Speed(loop index = 0) from UAS
*
* @param
*/
void get_AirSpeed_PID();
// Functions for Pitch Followei GroupBox
/**
* @brief Change color style to red when PID values of Pitch Followei are edited
*
*
* @param
*/
void changeColor_RED_PitchFollowei_groupBox(QString text);
/**
* @brief Change color style to green when PID values of Pitch Followei are send to UAS
*
* @param
*/
void changeColor_GREEN_PitchFollowei_groupBox();
/**
* @brief Connects the SIGNALS from the editline to SLOT PitchFlowei_groupBox
*
* @param
*/
void connect_PitchFollowei_LineEdit();
/**
* @brief get message PID Pitch Followei(loop index = 2) from UAS
*
* @param
*/
void get_PitchFollowei_PID();
// Functions for Roll Control GroupBox
/**
* @brief Change color style to red when PID values of Roll Control are edited
*
*
* @param
*/
void changeColor_RED_RollControl_groupBox(QString text);
/**
* @brief Change color style to green when PID values of Roll Control are send to UAS
*
* @param
*/
void changeColor_GREEN_RollControl_groupBox();
/**
* @brief Connects the SIGNALS from the editline to SLOT RollControl_groupBox
*
* @param
*/
void connect_RollControl_LineEdit();
/**
* @brief get message PID Roll Control(loop index = 4) from UAS
*
* @param
*/
void get_RollControl_PID();
// Functions for Heigth Error GroupBox
/**
* @brief Change color style to red when PID values of Heigth Error are edited
*
*
* @param
*/
void changeColor_RED_HeigthError_groupBox(QString text);
/**
* @brief Change color style to green when PID values of Heigth Error are send to UAS
*
* @param
*/
void changeColor_GREEN_HeigthError_groupBox();
/**
* @brief Connects the SIGNALS from the editline to SLOT HeigthError_groupBox
*
* @param
*/
void connect_HeigthError_LineEdit();
/**
* @brief get message PID Heigth Error(loop index = 1) from UAS
*
* @param
*/
void get_HeigthError_PID();
// Functions for Yaw Damper GroupBox
/**
* @brief Change color style to red when PID values of Yaw Damper are edited
*
*
* @param
*/
void changeColor_RED_YawDamper_groupBox(QString text);
/**
* @brief Change color style to green when PID values of Yaw Damper are send to UAS
*
* @param
*/
void changeColor_GREEN_YawDamper_groupBox();
/**
* @brief Connects the SIGNALS from the editline to SLOT YawDamper_groupBox
*
* @param
*/
void connect_YawDamper_LineEdit();
/**
* @brief get message PID Yaw Damper(loop index = 3) from UAS
*
* @param
*/
void get_YawDamper_PID();
// Functions for Pitch to dT GroupBox
/**
* @brief Change color style to red when PID values of Pitch to dT are edited
*
*
* @param
*/
void changeColor_RED_Pitch2dT_groupBox(QString text);
/**
* @brief Change color style to green when PID values of Pitch to dT are send to UAS
*
* @param
*/
void changeColor_GREEN_Pitch2dT_groupBox();
/**
* @brief Connects the SIGNALS from the editline to SLOT Pitch2dT_groupBox
*
* @param
*/
void connect_Pitch2dT_LineEdit();
/**
* @brief get message PID Pitch2dT(loop index = 8) from UAS
*
* @param
*/
void get_Pitch2dT_PID();
/**
* @brief get and updates the values on widget
*/
void slugsGetGeneral();
/**
* @brief Sent all values to UAS
*/
void slugsSetGeneral();
void slugsTimerStartSet();
void slugsTimerStartGet();
void slugsTimerStop();
//Create, send and get Messages PID
// void createMessagePID();
#ifdef MAVLINK_ENABLED_SLUGS
void receiveMessage(int systemId, const mavlink_action_ack_t& action);
void receivePidValues(int systemId, const mavlink_pid_t& pidValues);
#endif // MAVLINK_ENABLED_SLUG
private:
Ui::SlugsPIDControl *ui;
UASInterface* activeUAS;
int systemId;
bool change_dT;
//Color Styles
QString REDcolorStyle;
QString GREENcolorStyle;
QString ORIGINcolorStyle;
//SlugsMav Message
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_pid_t pidMessage;
mavlink_slugs_action_t actionSlugs;
#endif
QTimer* refreshTimerSet; ///< The main timer, controls the update view
QTimer* refreshTimerGet; ///< The main timer, controls the update view
int counterRefreshSet;
int counterRefreshGet;
QMutex valuesMutex;
};
#endif // SLUGSPIDCONTROL_H
This diff is collapsed.
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