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&)));
......
#include "SlugsPIDControl.h"
#include "ui_SlugsPIDControl.h"
#include <QPalette>
#include<QColor>
#include <QDebug>
#include <UASManager.h>
#include <UAS.h>
#include "LinkManager.h"
SlugsPIDControl::SlugsPIDControl(QWidget *parent) :
QWidget(parent),
ui(new Ui::SlugsPIDControl)
{
ui->setupUi(this);
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUasSet(UASInterface*)));
activeUAS = NULL;
setRedColorStyle();
setGreenColorStyle();
refreshTimerGet = new QTimer(this);
refreshTimerGet->setInterval(200);//100); // 5 Hz
connect(refreshTimerGet, SIGNAL(timeout()), this, SLOT(slugsGetGeneral()));
refreshTimerSet = new QTimer(this);
refreshTimerSet->setInterval(200);//100); // 20 Hz
connect(refreshTimerSet, SIGNAL(timeout()), this, SLOT(slugsSetGeneral()));
counterRefreshGet = 1;
counterRefreshSet = 1;
}
/**
* @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 SlugsPIDControl::activeUasSet(UASInterface* uas)
{
#ifdef MAVLINK_ENABLED_SLUGS
SlugsMAV* slugsMav = qobject_cast<SlugsMAV*>(uas);
if (slugsMav)
{
connect(slugsMav,SIGNAL(slugsActionAck(int,const mavlink_action_ack_t&)),this,SLOT(receiveMessage(int,mavlink_action_ack_t)));
connect(slugsMav,SIGNAL(slugsPidValues(int,mavlink_pid_t)),this, SLOT(receivePidValues(int,mavlink_pid_t)) );
connect(ui->setGeneral_pushButton,SIGNAL(clicked()),this,SLOT(slugsTimerStartSet()));
connect(ui->getGeneral_pushButton,SIGNAL(clicked()),this,SLOT(slugsTimerStartGet()));
}
#endif // MAVLINK_ENABLED_SLUG
// Set this UAS as active if it is the first one
if(!activeUAS)
{
activeUAS = uas;
systemId = activeUAS->getUASID();
connect_editLinesPDIvalues();
}
}
/**
* @brief Connect Edition Lines for PID Values
*
* @param
*/
void SlugsPIDControl::connect_editLinesPDIvalues()
{
if(activeUAS)
{
connect_set_pushButtons();
connect_get_pushButtons();
connect_AirSpeed_LineEdit();
connect_PitchFollowei_LineEdit();
connect_RollControl_LineEdit();
connect_HeigthError_LineEdit();
connect_YawDamper_LineEdit();
connect_Pitch2dT_LineEdit();
}
}
SlugsPIDControl::~SlugsPIDControl()
{
delete ui;
}
/**
*@brief Set the background color RED style for the GroupBox PID when change lineEdit information
*
*/
void SlugsPIDControl::setRedColorStyle()
{
// GroupBox Color
QColor groupColor = QColor(231,72,28);
QString borderColor = "#FA4A4F";
groupColor = groupColor.darker(475);
REDcolorStyle = REDcolorStyle.sprintf("QGroupBox {background-color: #%02X%02X%02X; border: 5px solid %s; }",
groupColor.red(), groupColor.green(), groupColor.blue(), borderColor.toStdString().c_str());
}
/**
*@brief Set the background color GREEN style for the GroupBox PID when change lineEdit information
*
*/
void SlugsPIDControl::setGreenColorStyle()
{
// create Green color style
QColor groupColor = QColor(30,124,16);
QString borderColor = "#24AC23";
groupColor = groupColor.darker(475);
GREENcolorStyle = GREENcolorStyle.sprintf("QGroupBox {background-color: #%02X%02X%02X; border: 5px solid %s; }",
groupColor.red(), groupColor.green(), groupColor.blue(), borderColor.toStdString().c_str());
}
/**
*@brief Connection Signal and Slot of the set buttons on the widget
*/
void SlugsPIDControl::connect_set_pushButtons()
{
//ToDo connect buttons set and get. Before create the slots
connect(ui->dT_PID_set_pushButton, SIGNAL(clicked()),this,SLOT(changeColor_GREEN_AirSpeed_groupBox()));
connect(ui->dE_PID_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_PitchFollowei_groupBox()));
connect(ui->dA_PID_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_RollControl_groupBox()));
connect(ui->HELPComm_PDI_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_HeigthError_groupBox()));
connect(ui->dR_PDI_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_YawDamper_groupBox()));
connect(ui->Pitch2dT_PDI_set_pushButton,SIGNAL(clicked()),this,SLOT(changeColor_GREEN_Pitch2dT_groupBox()));
}
/**
*@brief Connection Signal and Slot of the set buttons on the widget
*/
void SlugsPIDControl::connect_get_pushButtons()
{
connect(ui->dT_PID_get_pushButton, SIGNAL(clicked()),this,SLOT(get_AirSpeed_PID()));
connect(ui->dE_PID_get_pushButton,SIGNAL(clicked()),this,SLOT(get_PitchFollowei_PID()));
connect(ui->dR_PDI_get_pushButton,SIGNAL(clicked()),this,SLOT(get_YawDamper_PID()));
connect(ui->dA_PID_get_pushButton,SIGNAL(clicked()),this,SLOT(get_RollControl_PID()));
connect(ui->Pitch2dT_PDI_get_pushButton,SIGNAL(clicked()),this,SLOT(get_Pitch2dT_PID()));
connect(ui->HELPComm_PDI_get_pushButton,SIGNAL(clicked()),this,SLOT(get_HeigthError_PID()));
}
// Functions for Air Speed GroupBox
void SlugsPIDControl::connect_AirSpeed_LineEdit()
{
connect(ui->dT_P_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_AirSpeed_groupBox(QString)));
connect(ui->dT_I_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_AirSpeed_groupBox(QString)));
connect(ui->dT_D_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_AirSpeed_groupBox(QString)));
}
void SlugsPIDControl::changeColor_RED_AirSpeed_groupBox(QString text)
{
Q_UNUSED(text);
ui->AirSpeedHold_groupBox->setStyleSheet(REDcolorStyle);
}
void SlugsPIDControl::changeColor_GREEN_AirSpeed_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
//create the packet
#ifdef MAVLINK_ENABLED_SLUGS
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 0;
pidMessage.pVal = ui->dT_P_set->text().toFloat();
pidMessage.iVal = ui->dT_I_set->text().toFloat();
pidMessage.dVal = ui->dT_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->AirSpeedHold_groupBox->setStyleSheet(GREENcolorStyle);
}
}
void SlugsPIDControl::get_AirSpeed_PID()
{
qDebug() << "\nSend Message = Air Speed ";
sendMessagePIDStatus(0);
}
// Functions for PitchFollowei GroupBox
void SlugsPIDControl::connect_PitchFollowei_LineEdit()
{
connect(ui->dE_P_set, SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_PitchFollowei_groupBox(QString)));
connect(ui->dE_I_set, SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_PitchFollowei_groupBox(QString)));
connect(ui->dE_D_set, SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_PitchFollowei_groupBox(QString)));
}
void SlugsPIDControl::changeColor_RED_PitchFollowei_groupBox(QString text)
{
Q_UNUSED(text);
ui->PitchFlowei_groupBox->setStyleSheet(REDcolorStyle);
}
void SlugsPIDControl::changeColor_GREEN_PitchFollowei_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 2;
pidMessage.pVal = ui->dE_P_set->text().toFloat();
pidMessage.iVal = ui->dE_I_set->text().toFloat();
pidMessage.dVal = ui->dE_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->PitchFlowei_groupBox->setStyleSheet(GREENcolorStyle);
}
}
void SlugsPIDControl::get_PitchFollowei_PID()
{
qDebug() << "\nSend Message = Pitch Followei ";
sendMessagePIDStatus(2);
}
// Functions for Roll Control GroupBox
/**
* @brief Change color style to red when PID values of Roll Control are edited
*
*
* @param
*/
void SlugsPIDControl::changeColor_RED_RollControl_groupBox(QString text)
{
Q_UNUSED(text);
ui->RollControl_groupBox->setStyleSheet(REDcolorStyle);
}
/**
* @brief Change color style to green when PID values of Roll Control are send to UAS
*
* @param
*/
void SlugsPIDControl::changeColor_GREEN_RollControl_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 4;
pidMessage.pVal = ui->dA_P_set->text().toFloat();
pidMessage.iVal = ui->dA_I_set->text().toFloat();
pidMessage.dVal = ui->dA_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->RollControl_groupBox->setStyleSheet(GREENcolorStyle);
}
}
/**
* @brief Connects the SIGNALS from the editline to SLOT RollControl_groupBox
*
* @param
*/
void SlugsPIDControl::connect_RollControl_LineEdit()
{
connect(ui->dA_P_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_RollControl_groupBox(QString)));
connect(ui->dA_I_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_RollControl_groupBox(QString)));
connect(ui->dA_D_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_RollControl_groupBox(QString)));
}
void SlugsPIDControl::get_RollControl_PID()
{
qDebug() << "\nSend Message = Roll Control ";
sendMessagePIDStatus(4);
}
// Functions for Heigth Error GroupBox
/**
* @brief Change color style to red when PID values of Heigth Error are edited
*
*
* @param
*/
void SlugsPIDControl::changeColor_RED_HeigthError_groupBox(QString text)
{
Q_UNUSED(text);
ui->HeightErrorLoPitch_groupBox->setStyleSheet(REDcolorStyle);
}
/**
* @brief Change color style to green when PID values of Heigth Error are send to UAS
*
* @param
*/
void SlugsPIDControl::changeColor_GREEN_HeigthError_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 1;
pidMessage.pVal = ui->HELPComm_P_set->text().toFloat();
pidMessage.iVal = ui->HELPComm_I_set->text().toFloat();
pidMessage.dVal = ui->HELPComm_FF_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->HeightErrorLoPitch_groupBox->setStyleSheet(GREENcolorStyle);
}
}
/**
* @brief Connects the SIGNALS from the editline to SLOT HeigthError_groupBox
*
* @param
*/
void SlugsPIDControl::connect_HeigthError_LineEdit()
{
connect(ui->HELPComm_P_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_HeigthError_groupBox(QString)));
connect(ui->HELPComm_I_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_HeigthError_groupBox(QString)));
connect(ui->HELPComm_FF_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_HeigthError_groupBox(QString)));
}
void SlugsPIDControl::get_HeigthError_PID()
{
qDebug() << "\nSend Message = Heigth Error ";
sendMessagePIDStatus(1);
}
// Functions for Yaw Damper GroupBox
/**
* @brief Change color style to red when PID values of Yaw Damper are edited
*
*
* @param
*/
void SlugsPIDControl::changeColor_RED_YawDamper_groupBox(QString text)
{
Q_UNUSED(text);
ui->YawDamper_groupBox->setStyleSheet(REDcolorStyle);
}
/**
* @brief Change color style to green when PID values of Yaw Damper are send to UAS
*
* @param
*/
void SlugsPIDControl::changeColor_GREEN_YawDamper_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 3;
pidMessage.pVal = ui->dR_P_set->text().toFloat();
pidMessage.iVal = ui->dR_I_set->text().toFloat();
pidMessage.dVal = ui->dR_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->YawDamper_groupBox->setStyleSheet(GREENcolorStyle);
}
}
/**
* @brief Connects the SIGNALS from the editline to SLOT YawDamper_groupBox
*
* @param
*/
void SlugsPIDControl::connect_YawDamper_LineEdit()
{
connect(ui->dR_P_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_YawDamper_groupBox(QString)));
connect(ui->dR_I_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_YawDamper_groupBox(QString)));
connect(ui->dR_D_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_YawDamper_groupBox(QString)));
}
void SlugsPIDControl::get_YawDamper_PID()
{
qDebug() << "\nSend Message = Yaw Damper ";
sendMessagePIDStatus(3);
}
// Functions for Pitch to dT GroupBox
/**
* @brief Change color style to red when PID values of Pitch to dT are edited
*
*
* @param
*/
void SlugsPIDControl::changeColor_RED_Pitch2dT_groupBox(QString text)
{
Q_UNUSED(text);
ui->Pitch2dTFFterm_groupBox->setStyleSheet(REDcolorStyle);
}
/**
* @brief Change color style to green when PID values of Pitch to dT are send to UAS
*
* @param
*/
void SlugsPIDControl::changeColor_GREEN_Pitch2dT_groupBox()
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
#ifdef MAVLINK_ENABLED_SLUGS
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 8;
pidMessage.pVal = ui->P2dT_FF_set->text().toFloat();
pidMessage.iVal = 0;//ui->dR_I_set->text().toFloat();
pidMessage.dVal = 0;//ui->dR_D_set->text().toFloat();
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
slugsMav->sendMessage(msg);
#endif
ui->Pitch2dTFFterm_groupBox->setStyleSheet(GREENcolorStyle);
}
}
/**
* @brief Connects the SIGNALS from the editline to SLOT Pitch2dT_groupBox
*
* @param
*/
void SlugsPIDControl::connect_Pitch2dT_LineEdit()
{
connect(ui->P2dT_FF_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_Pitch2dT_groupBox(QString)));
}
void SlugsPIDControl::get_Pitch2dT_PID()
{
qDebug() << "\nSend Message = Pitch to dT ";
sendMessagePIDStatus(8);
}
#ifdef MAVLINK_ENABLED_SLUGS
void SlugsPIDControl::receiveMessage(int systemId, const mavlink_action_ack_t& action)
{
Q_UNUSED(systemId);
ui->recepcion_label->setText(QString::number(action.action) + ":" + QString::number(action.result));
}
void SlugsPIDControl::receivePidValues(int systemId, const mavlink_pid_t &pidValues)
{
Q_UNUSED(systemId);
qDebug() << "\nACTUALIZANDO GUI = " << pidValues.idx;
switch(pidValues.idx)
{
case 0:
ui->dT_P_get->setText(QString::number(pidValues.pVal));
ui->dT_I_get->setText(QString::number(pidValues.iVal));
ui->dT_D_get->setText(QString::number(pidValues.dVal));
break;
case 1:
ui->HELPComm_P_get->setText(QString::number(pidValues.pVal));
ui->HELPComm_I_get->setText(QString::number(pidValues.iVal));
ui->HELPComm_FF_get->setText(QString::number(pidValues.dVal));
break;
case 2:
ui->dE_P_get->setText(QString::number(pidValues.pVal));
ui->dE_I_get->setText(QString::number(pidValues.iVal));
ui->dE_D_get->setText(QString::number(pidValues.dVal));
break;
case 3:
ui->dR_P_get->setText(QString::number(pidValues.pVal));
ui->dR_I_get->setText(QString::number(pidValues.iVal));
ui->dR_D_get->setText(QString::number(pidValues.dVal));
break;
case 4:
ui->dA_P_get->setText(QString::number(pidValues.pVal));
ui->dA_I_get->setText(QString::number(pidValues.iVal));
ui->dA_D_get->setText(QString::number(pidValues.dVal));
break;
case 8:
ui->P2dT_FF_get->setText(QString::number(pidValues.pVal));
break;
default:
qDebug() << "\nSLUGS RECEIVED AND SHOW PID type ID = " << pidValues.idx;
break;
}
}
#endif // MAVLINK_ENABLED_SLUG
void SlugsPIDControl::sendMessagePIDStatus(int PIDtype)
{
#ifdef MAVLINK_ENABLED_SLUGS
//ToDo remplace actionId values
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
mavlink_message_t msg;
qDebug() << "\n Send Message SLUGS PID with loop index = " << PIDtype;
switch(PIDtype)
{
case 0: //Air Speed PID values Request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 0;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 1: //Heigth Error lo Pitch Comm PID values request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 1;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 2://Pitch Followei PID values Request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 2;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 3:// Yaw Damper PID values request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 3;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 4: // Roll Control PID values request
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 4;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
case 8: // Pitch to dT FF term
actionSlugs.target = activeUAS->getUASID();
actionSlugs.actionId = 9;
actionSlugs.actionVal = 8;
mavlink_msg_slugs_action_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &actionSlugs);
slugsMav->sendMessage(msg);
break;
default:
qDebug() << "\nSLUGS RECEIVED PID type ID = " << PIDtype;
break;
}
}
#else
Q_UNUSED(PIDtype);
#endif // MAVLINK_ENABLED_SLUG
}
void SlugsPIDControl::slugsGetGeneral()
{
valuesMutex.lock();
switch(counterRefreshGet)
{
case 1:
ui->dT_PID_get_pushButton->click();
break;
case 2:
ui->HELPComm_PDI_get_pushButton->click();
break;
case 3:
ui->dE_PID_get_pushButton->click();
break;
case 4:
ui->dR_PDI_get_pushButton->click();
break;
case 5:
ui->dA_PID_get_pushButton->click();
break;
case 6:
ui->Pitch2dT_PDI_get_pushButton->click();
break;
default:
refreshTimerGet->stop();
break;
}
counterRefreshGet++;
valuesMutex.unlock();
}
void SlugsPIDControl::slugsSetGeneral()
{
valuesMutex.lock();
switch(counterRefreshSet)
{
case 1:
ui->dT_PID_set_pushButton->click();
break;
case 2:
ui->HELPComm_PDI_set_pushButton->click();
break;
case 3:
ui->dE_PID_set_pushButton->click();
break;
case 4:
ui->dR_PDI_set_pushButton->click();
break;
case 5:
ui->dA_PID_set_pushButton->click();
break;
case 6:
ui->Pitch2dT_PDI_set_pushButton->click();
break;
default:
refreshTimerSet->stop();
break;
}
counterRefreshSet++;
valuesMutex.unlock();
}
void SlugsPIDControl::slugsTimerStartSet()
{
counterRefreshSet = 1;
refreshTimerSet->start();
}
void SlugsPIDControl::slugsTimerStartGet()
{
counterRefreshGet = 1;
refreshTimerGet->start();
}
void SlugsPIDControl::slugsTimerStop()
{
// refreshTimerGet->stop();
// counterRefresh = 1;
}
#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
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>SlugsPIDControl</class>
<widget class="QWidget" name="SlugsPIDControl">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>429</width>
<height>579</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout_4">
<item row="0" column="0">
<layout class="QGridLayout" name="gridLayout_3">
<item row="0" column="0">
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QGroupBox" name="AirSpeedHold_groupBox">
<property name="title">
<string>Air Speed Hold (dT)</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_4">
<item>
<layout class="QGridLayout" name="gridLayout_7">
<item row="0" column="0">
<widget class="QLabel" name="label_10">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_11">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_12">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLineEdit" name="dT_P_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="dT_P_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLineEdit" name="dT_I_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLineEdit" name="dT_I_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLineEdit" name="dT_D_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLineEdit" name="dT_D_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_5">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QGridLayout" name="gridLayout_8">
<item row="0" column="0">
<widget class="QPushButton" name="dT_PID_set_pushButton">
<property name="text">
<string>SET</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QPushButton" name="dT_PID_get_pushButton">
<property name="text">
<string>GET</string>
</property>
</widget>
</item>
<item row="0" column="1">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer_9">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="PitchFlowei_groupBox">
<property name="title">
<string>Pitch Followei (dE)</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_3">
<item>
<layout class="QGridLayout" name="gridLayout_5">
<item row="0" column="0">
<widget class="QLabel" name="label_7">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_8">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_9">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLineEdit" name="dE_P_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="dE_P_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLineEdit" name="dE_I_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLineEdit" name="dE_I_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLineEdit" name="dE_D_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLineEdit" name="dE_D_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_4">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QGridLayout" name="gridLayout_6">
<item row="0" column="0">
<widget class="QPushButton" name="dE_PID_set_pushButton">
<property name="text">
<string>SET</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QPushButton" name="dE_PID_get_pushButton">
<property name="text">
<string>GET</string>
</property>
</widget>
</item>
<item row="0" column="1">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer_10">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="RollControl_groupBox">
<property name="title">
<string>Roll Control (dA)</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_5">
<item>
<layout class="QGridLayout" name="gridLayout_9">
<item row="0" column="0">
<widget class="QLabel" name="label_13">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_14">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_15">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLineEdit" name="dA_P_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="dA_P_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLineEdit" name="dA_I_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLineEdit" name="dA_I_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLineEdit" name="dA_D_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLineEdit" name="dA_D_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_6">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QGridLayout" name="gridLayout_10">
<item row="0" column="0">
<widget class="QPushButton" name="dA_PID_set_pushButton">
<property name="text">
<string>SET</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QPushButton" name="dA_PID_get_pushButton">
<property name="text">
<string>GET</string>
</property>
</widget>
</item>
<item row="0" column="1">
<spacer name="horizontalSpacer_5">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
</layout>
</widget>
</item>
</layout>
</item>
<item row="0" column="1">
<layout class="QVBoxLayout" name="verticalLayout_6">
<item>
<widget class="QGroupBox" name="HeightErrorLoPitch_groupBox">
<property name="title">
<string>Heigth Error lo Pitch Comm</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<layout class="QGridLayout" name="gridLayout_11">
<item row="0" column="0">
<widget class="QLabel" name="label_16">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_17">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLineEdit" name="HELPComm_P_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="HELPComm_P_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLineEdit" name="HELPComm_I_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLineEdit" name="HELPComm_I_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="Line" name="line">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="frameShadow">
<enum>QFrame::Sunken</enum>
</property>
<property name="lineWidth">
<number>5</number>
</property>
<property name="midLineWidth">
<number>1</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_2">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QGridLayout" name="gridLayout">
<item row="0" column="0">
<widget class="QLabel" name="label_18">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>FF</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLineEdit" name="HELPComm_FF_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="HELPComm_FF_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QGridLayout" name="gridLayout_12">
<item row="0" column="0">
<widget class="QPushButton" name="HELPComm_PDI_set_pushButton">
<property name="text">
<string>SET</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QPushButton" name="HELPComm_PDI_get_pushButton">
<property name="text">
<string>GET</string>
</property>
</widget>
</item>
<item row="0" column="1">
<spacer name="horizontalSpacer_6">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer_11">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="YawDamper_groupBox">
<property name="title">
<string>Yaw Damper (dR)</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_7">
<item>
<layout class="QGridLayout" name="gridLayout_13">
<item row="0" column="0">
<widget class="QLabel" name="label_19">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>P</string>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label_20">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>I</string>
</property>
</widget>
</item>
<item row="2" column="0">
<widget class="QLabel" name="label_21">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>D</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLineEdit" name="dR_P_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="dR_P_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QLineEdit" name="dR_I_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLineEdit" name="dR_I_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
<item row="2" column="1">
<widget class="QLineEdit" name="dR_D_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLineEdit" name="dR_D_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item>
<spacer name="verticalSpacer_8">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>10</height>
</size>
</property>
</spacer>
</item>
<item>
<layout class="QGridLayout" name="gridLayout_14">
<item row="0" column="0">
<widget class="QPushButton" name="dR_PDI_set_pushButton">
<property name="text">
<string>SET</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QPushButton" name="dR_PDI_get_pushButton">
<property name="text">
<string>GET</string>
</property>
</widget>
</item>
<item row="0" column="1">
<spacer name="horizontalSpacer_7">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer_12">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="Pitch2dTFFterm_groupBox">
<property name="title">
<string>Pitch to dT FF term</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_8">
<item>
<layout class="QGridLayout" name="gridLayout_2">
<item row="0" column="0">
<widget class="QLabel" name="label_25">
<property name="font">
<font>
<pointsize>10</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>FF</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QLineEdit" name="P2dT_FF_set">
<property name="text">
<string>0.0</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="P2dT_FF_get">
<property name="text">
<string>0.0</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QGridLayout" name="gridLayout_16">
<item row="0" column="0">
<widget class="QPushButton" name="Pitch2dT_PDI_set_pushButton">
<property name="text">
<string>SET</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QPushButton" name="Pitch2dT_PDI_get_pushButton">
<property name="text">
<string>GET</string>
</property>
</widget>
</item>
<item row="0" column="1">
<spacer name="horizontalSpacer_8">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>40</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="QLabel" name="recepcion_label">
<property name="text">
<string>Recepcion</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="verticalSpacer_7">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
</layout>
</item>
<item row="1" column="0">
<spacer name="verticalSpacer_13">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
<item row="2" column="0">
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QPushButton" name="setGeneral_pushButton">
<property name="text">
<string>Set General</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="getGeneral_pushButton">
<property name="text">
<string>Get General</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
<zorder>verticalSpacer_13</zorder>
</widget>
<tabstops>
<tabstop>dT_P_set</tabstop>
<tabstop>dT_I_set</tabstop>
<tabstop>dT_D_set</tabstop>
<tabstop>dT_PID_set_pushButton</tabstop>
<tabstop>dT_PID_get_pushButton</tabstop>
<tabstop>HELPComm_P_set</tabstop>
<tabstop>HELPComm_I_set</tabstop>
<tabstop>HELPComm_FF_set</tabstop>
<tabstop>HELPComm_PDI_set_pushButton</tabstop>
<tabstop>HELPComm_PDI_get_pushButton</tabstop>
<tabstop>dE_P_set</tabstop>
<tabstop>dE_I_set</tabstop>
<tabstop>dE_D_set</tabstop>
<tabstop>dE_PID_set_pushButton</tabstop>
<tabstop>dE_PID_get_pushButton</tabstop>
<tabstop>dR_P_set</tabstop>
<tabstop>dR_I_set</tabstop>
<tabstop>dR_D_set</tabstop>
<tabstop>dR_PDI_set_pushButton</tabstop>
<tabstop>dR_PDI_get_pushButton</tabstop>
<tabstop>dA_P_set</tabstop>
<tabstop>dA_I_set</tabstop>
<tabstop>dA_D_set</tabstop>
<tabstop>dA_PID_set_pushButton</tabstop>
<tabstop>dA_PID_get_pushButton</tabstop>
<tabstop>P2dT_FF_set</tabstop>
<tabstop>Pitch2dT_PDI_set_pushButton</tabstop>
<tabstop>Pitch2dT_PDI_get_pushButton</tabstop>
<tabstop>dT_P_get</tabstop>
<tabstop>dT_I_get</tabstop>
<tabstop>dT_D_get</tabstop>
<tabstop>HELPComm_P_get</tabstop>
<tabstop>HELPComm_I_get</tabstop>
<tabstop>HELPComm_FF_get</tabstop>
<tabstop>dE_P_get</tabstop>
<tabstop>dE_I_get</tabstop>
<tabstop>dE_D_get</tabstop>
<tabstop>dR_P_get</tabstop>
<tabstop>dR_I_get</tabstop>
<tabstop>dR_D_get</tabstop>
<tabstop>dA_P_get</tabstop>
<tabstop>dA_I_get</tabstop>
<tabstop>dA_D_get</tabstop>
<tabstop>P2dT_FF_get</tabstop>
</tabstops>
<resources/>
<connections/>
</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