Commit 5a8a8b2b authored by tecnosapiens's avatar tecnosapiens

not working send messages in SlugsPIDControl

parent 0b761f97
...@@ -39,6 +39,7 @@ SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) : ...@@ -39,6 +39,7 @@ SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) :
memset(&mlActionAck,0, sizeof(mavlink_action_ack_t)); memset(&mlActionAck,0, sizeof(mavlink_action_ack_t));
memset(&mlAction ,0, sizeof(mavlink_slugs_action_t)); memset(&mlAction ,0, sizeof(mavlink_slugs_action_t));
updateRoundRobin = 0; updateRoundRobin = 0;
...@@ -154,6 +155,12 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -154,6 +155,12 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
break; break;
case MAVLINK_MSG_ID_PID: //182 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; break;
...@@ -197,7 +204,7 @@ void SlugsMAV::emitSignals (void){ ...@@ -197,7 +204,7 @@ 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);
...@@ -241,4 +248,11 @@ void SlugsMAV::emitGpsSignals (void){ ...@@ -241,4 +248,11 @@ void SlugsMAV::emitGpsSignals (void){
} }
} }
void SlugsMAV::emitPidSignal()
{
qDebug() << "\nSLUGS RECEIVED PID Message";
emit slugsPidValues(uasId, mlSinglePid);
}
#endif // MAVLINK_ENABLED_SLUGS #endif // MAVLINK_ENABLED_SLUGS
...@@ -62,6 +62,8 @@ signals: ...@@ -62,6 +62,8 @@ signals:
void slugsGPSDateTime(int systemId, const mavlink_gps_date_time_t& gpsDateTime); void slugsGPSDateTime(int systemId, const mavlink_gps_date_time_t& gpsDateTime);
void slugsActionAck(int systemId, const mavlink_action_ack_t& actionAck); void slugsActionAck(int systemId, const mavlink_action_ack_t& actionAck);
void slugsPidValues(int systemId, const mavlink_pid_t& pidValues);
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);
...@@ -96,7 +98,7 @@ protected: ...@@ -96,7 +98,7 @@ protected:
mavlink_set_mode_t mlApMode; mavlink_set_mode_t mlApMode;
mavlink_pwm_commands_t mlPwmCommands; mavlink_pwm_commands_t mlPwmCommands;
mavlink_pid_values_t mlPidValues; mavlink_pid_values_t mlPidValues;
mavlink_pid_t mlSinglePid; mavlink_pid_t mlSinglePid;
mavlink_slugs_navigation_t mlNavigation; mavlink_slugs_navigation_t mlNavigation;
mavlink_data_log_t mlDataLog; mavlink_data_log_t mlDataLog;
...@@ -106,11 +108,14 @@ protected: ...@@ -106,11 +108,14 @@ protected:
mavlink_slugs_action_t mlAction; mavlink_slugs_action_t mlAction;
// Standart messages MAVLINK used by SLUGS // Standart messages MAVLINK used by SLUGS
private: private:
void emitGpsSignals (void); void emitGpsSignals (void);
void emitPidSignal(void);
int uasId; int uasId;
......
...@@ -943,7 +943,7 @@ void MainWindow::loadGlobalOperatorView() ...@@ -943,7 +943,7 @@ void MainWindow::loadGlobalOperatorView()
if (slugsCamControlWidget) if (slugsCamControlWidget)
{ {
addDockWidget(Qt::RightDockWidgetArea, slugsCamControlWidget); addDockWidget(Qt::BottomDockWidgetArea, slugsCamControlWidget);
slugsCamControlWidget->show(); slugsCamControlWidget->show();
} }
......
...@@ -22,15 +22,6 @@ SlugsPIDControl::SlugsPIDControl(QWidget *parent) : ...@@ -22,15 +22,6 @@ SlugsPIDControl::SlugsPIDControl(QWidget *parent) :
setRedColorStyle(); setRedColorStyle();
setGreenColorStyle(); setGreenColorStyle();
// connect_set_pushButtons();
// connect_AirSpeed_LineEdit();
// connect_PitchFollowei_LineEdit();
// connect_RollControl_LineEdit();
// connect_HeigthError_LineEdit();
// connect_YawDamper_LineEdit();
// connect_Pitch2dT_LineEdit();
} }
/** /**
...@@ -48,6 +39,7 @@ void SlugsPIDControl::activeUasSet(UASInterface* uas) ...@@ -48,6 +39,7 @@ void SlugsPIDControl::activeUasSet(UASInterface* uas)
if (slugsMav != NULL) if (slugsMav != NULL)
{ {
connect(slugsMav,SIGNAL(slugsActionAck(int,const mavlink_action_ack_t&)),this,SLOT(recibeMensaje(int,mavlink_action_ack_t))); connect(slugsMav,SIGNAL(slugsActionAck(int,const mavlink_action_ack_t&)),this,SLOT(recibeMensaje(int,mavlink_action_ack_t)));
connect(slugsMav,SIGNAL(slugsPidValues(int,mavlink_pid_t)),this, SLOT(receivePidValues(int,mavlink_pid_t)) );
} }
#endif // MAVLINK_ENABLED_SLUG #endif // MAVLINK_ENABLED_SLUG
...@@ -73,6 +65,7 @@ void SlugsPIDControl::connect_editLinesPDIvalues() ...@@ -73,6 +65,7 @@ void SlugsPIDControl::connect_editLinesPDIvalues()
if(activeUAS) if(activeUAS)
{ {
connect_set_pushButtons(); connect_set_pushButtons();
connect_get_pushButtons();
connect_AirSpeed_LineEdit(); connect_AirSpeed_LineEdit();
connect_PitchFollowei_LineEdit(); connect_PitchFollowei_LineEdit();
connect_RollControl_LineEdit(); connect_RollControl_LineEdit();
...@@ -140,6 +133,21 @@ void SlugsPIDControl::connect_set_pushButtons() ...@@ -140,6 +133,21 @@ void SlugsPIDControl::connect_set_pushButtons()
} }
/**
*@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() void SlugsPIDControl::connect_AirSpeed_LineEdit()
{ {
connect(ui->dT_P_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_AirSpeed_groupBox(QString))); connect(ui->dT_P_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_AirSpeed_groupBox(QString)));
...@@ -178,7 +186,16 @@ void SlugsPIDControl::changeColor_GREEN_AirSpeed_groupBox() ...@@ -178,7 +186,16 @@ void SlugsPIDControl::changeColor_GREEN_AirSpeed_groupBox()
} }
} }
void SlugsPIDControl::get_AirSpeed_PID()
{
qDebug() << "\nSend Message = Air Speed ";
sendMessagePIDStatus(0);
}
// Functions for PitchFollowei GroupBox
void SlugsPIDControl::connect_PitchFollowei_LineEdit() void SlugsPIDControl::connect_PitchFollowei_LineEdit()
{ {
connect(ui->dE_P_set, SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_PitchFollowei_groupBox(QString))); connect(ui->dE_P_set, SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_PitchFollowei_groupBox(QString)));
...@@ -195,9 +212,34 @@ void SlugsPIDControl::changeColor_RED_PitchFollowei_groupBox(QString text) ...@@ -195,9 +212,34 @@ void SlugsPIDControl::changeColor_RED_PitchFollowei_groupBox(QString text)
void SlugsPIDControl::changeColor_GREEN_PitchFollowei_groupBox() void SlugsPIDControl::changeColor_GREEN_PitchFollowei_groupBox()
{ {
ui->PitchFlowei_groupBox->setStyleSheet(GREENcolorStyle); SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
//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);
ui->PitchFlowei_groupBox->setStyleSheet(GREENcolorStyle);
}
} }
void SlugsPIDControl::get_PitchFollowei_PID()
{
qDebug() << "\nSend Message = Pitch Followei ";
sendMessagePIDStatus(2);
}
// Functions for Roll Control GroupBox // Functions for Roll Control GroupBox
/** /**
* @brief Change color style to red when PID values of Roll Control are edited * @brief Change color style to red when PID values of Roll Control are edited
...@@ -218,7 +260,24 @@ void SlugsPIDControl::changeColor_RED_RollControl_groupBox(QString text) ...@@ -218,7 +260,24 @@ void SlugsPIDControl::changeColor_RED_RollControl_groupBox(QString text)
*/ */
void SlugsPIDControl::changeColor_GREEN_RollControl_groupBox() void SlugsPIDControl::changeColor_GREEN_RollControl_groupBox()
{ {
ui->RollControl_groupBox->setStyleSheet(GREENcolorStyle); SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
//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);
ui->RollControl_groupBox->setStyleSheet(GREENcolorStyle);
}
} }
/** /**
...@@ -233,6 +292,13 @@ void SlugsPIDControl::connect_RollControl_LineEdit() ...@@ -233,6 +292,13 @@ void SlugsPIDControl::connect_RollControl_LineEdit()
connect(ui->dA_D_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 // Functions for Heigth Error GroupBox
/** /**
...@@ -254,7 +320,24 @@ void SlugsPIDControl::changeColor_RED_HeigthError_groupBox(QString text) ...@@ -254,7 +320,24 @@ void SlugsPIDControl::changeColor_RED_HeigthError_groupBox(QString text)
*/ */
void SlugsPIDControl::changeColor_GREEN_HeigthError_groupBox() void SlugsPIDControl::changeColor_GREEN_HeigthError_groupBox()
{ {
ui->HeightErrorLoPitch_groupBox->setStyleSheet(GREENcolorStyle); SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
//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);
ui->HeightErrorLoPitch_groupBox->setStyleSheet(GREENcolorStyle);
}
} }
/** /**
...@@ -269,6 +352,12 @@ void SlugsPIDControl::connect_HeigthError_LineEdit() ...@@ -269,6 +352,12 @@ void SlugsPIDControl::connect_HeigthError_LineEdit()
connect(ui->HELPComm_FF_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 // Functions for Yaw Damper GroupBox
/** /**
...@@ -290,7 +379,24 @@ void SlugsPIDControl::changeColor_RED_YawDamper_groupBox(QString text) ...@@ -290,7 +379,24 @@ void SlugsPIDControl::changeColor_RED_YawDamper_groupBox(QString text)
*/ */
void SlugsPIDControl::changeColor_GREEN_YawDamper_groupBox() void SlugsPIDControl::changeColor_GREEN_YawDamper_groupBox()
{ {
ui->YawDamper_groupBox->setStyleSheet(GREENcolorStyle); SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
//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);
ui->YawDamper_groupBox->setStyleSheet(GREENcolorStyle);
}
} }
/** /**
...@@ -307,6 +413,13 @@ void SlugsPIDControl::connect_YawDamper_LineEdit() ...@@ -307,6 +413,13 @@ void SlugsPIDControl::connect_YawDamper_LineEdit()
} }
void SlugsPIDControl::get_YawDamper_PID()
{
qDebug() << "\nSend Message = Yaw Damper ";
sendMessagePIDStatus(3);
}
// Functions for Pitch to dT GroupBox // Functions for Pitch to dT GroupBox
/** /**
* @brief Change color style to red when PID values of Pitch to dT are edited * @brief Change color style to red when PID values of Pitch to dT are edited
...@@ -327,7 +440,23 @@ void SlugsPIDControl::changeColor_RED_Pitch2dT_groupBox(QString text) ...@@ -327,7 +440,23 @@ void SlugsPIDControl::changeColor_RED_Pitch2dT_groupBox(QString text)
*/ */
void SlugsPIDControl::changeColor_GREEN_Pitch2dT_groupBox() void SlugsPIDControl::changeColor_GREEN_Pitch2dT_groupBox()
{ {
ui->Pitch2dTFFterm_groupBox->setStyleSheet(GREENcolorStyle); SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(activeUAS);
if (slugsMav != NULL)
{
//create the packet
pidMessage.target = activeUAS->getUASID();
pidMessage.idx = 8;
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);
ui->Pitch2dTFFterm_groupBox->setStyleSheet(GREENcolorStyle);
}
} }
/** /**
...@@ -340,11 +469,146 @@ void SlugsPIDControl::connect_Pitch2dT_LineEdit() ...@@ -340,11 +469,146 @@ void SlugsPIDControl::connect_Pitch2dT_LineEdit()
connect(ui->P2dT_FF_set,SIGNAL(textChanged(QString)),this,SLOT(changeColor_RED_Pitch2dT_groupBox(QString))); 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 #ifdef MAVLINK_ENABLED_SLUGS
void SlugsPIDControl::recibeMensaje(int systemId, const mavlink_action_ack_t& action) void SlugsPIDControl::recibeMensaje(int systemId, const mavlink_action_ack_t& action)
{ {
ui->recepcion_label->setText(QString::number(action.action)); 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 1:
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 2:
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 3:
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 4:
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 5:
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 9:
ui->P2dT_FF_get->setText(QString::number(pidValues.pVal));
break;
default:
qDebug() << "\nSLUGS RECEIVED AND SHOW PID type ID = " << pidValues.idx;
break;
}
}
void SlugsPIDControl::sendMessagePIDStatus(int PIDtype)
{
//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;
}
}
} }
#endif // MAVLINK_ENABLED_SLUGS #endif // MAVLINK_ENABLED_SLUGS
...@@ -48,6 +48,13 @@ public slots: ...@@ -48,6 +48,13 @@ public slots:
*/ */
void connect_set_pushButtons(); 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 * @brief Connect Edition Lines for PID Values
* *
...@@ -55,6 +62,13 @@ public slots: ...@@ -55,6 +62,13 @@ public slots:
*/ */
void connect_editLinesPDIvalues(); void connect_editLinesPDIvalues();
/**
* @brief send a PDI request message to UAS
*
* @param
*/
void sendMessagePIDStatus(int PIDtype);
// Fuctions for Air Speed GroupBox // Fuctions for Air Speed GroupBox
/** /**
* @brief Change color style to red when PID values of Air Speed are edited * @brief Change color style to red when PID values of Air Speed are edited
...@@ -75,6 +89,13 @@ public slots: ...@@ -75,6 +89,13 @@ public slots:
* @param * @param
*/ */
void connect_AirSpeed_LineEdit(); 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 // Functions for Pitch Followei GroupBox
/** /**
...@@ -96,6 +117,13 @@ public slots: ...@@ -96,6 +117,13 @@ public slots:
* @param * @param
*/ */
void connect_PitchFollowei_LineEdit(); 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 // Functions for Roll Control GroupBox
/** /**
...@@ -117,6 +145,13 @@ public slots: ...@@ -117,6 +145,13 @@ public slots:
* @param * @param
*/ */
void connect_RollControl_LineEdit(); 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 // Functions for Heigth Error GroupBox
/** /**
...@@ -138,6 +173,12 @@ public slots: ...@@ -138,6 +173,12 @@ public slots:
* @param * @param
*/ */
void connect_HeigthError_LineEdit(); 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 // Functions for Yaw Damper GroupBox
/** /**
...@@ -159,6 +200,14 @@ public slots: ...@@ -159,6 +200,14 @@ public slots:
* @param * @param
*/ */
void connect_YawDamper_LineEdit(); 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 // Functions for Pitch to dT GroupBox
/** /**
...@@ -180,6 +229,12 @@ public slots: ...@@ -180,6 +229,12 @@ public slots:
* @param * @param
*/ */
void connect_Pitch2dT_LineEdit(); void connect_Pitch2dT_LineEdit();
/**
* @brief get message PID Pitch2dT(loop index = 8) from UAS
*
* @param
*/
void get_Pitch2dT_PID();
//Create, send and get Messages PID //Create, send and get Messages PID
...@@ -187,6 +242,7 @@ public slots: ...@@ -187,6 +242,7 @@ public slots:
#ifdef MAVLINK_ENABLED_SLUGS #ifdef MAVLINK_ENABLED_SLUGS
void recibeMensaje(int systemId, const mavlink_action_ack_t& action); void recibeMensaje(int systemId, const mavlink_action_ack_t& action);
void receivePidValues(int systemId, const mavlink_pid_t& pidValues);
#endif // MAVLINK_ENABLED_SLUG #endif // MAVLINK_ENABLED_SLUG
...@@ -206,6 +262,7 @@ private: ...@@ -206,6 +262,7 @@ private:
//SlugsMav Message //SlugsMav Message
mavlink_pid_t pidMessage; mavlink_pid_t pidMessage;
mavlink_slugs_action_t actionSlugs;
}; };
#endif // SLUGSPIDCONTROL_H #endif // SLUGSPIDCONTROL_H
...@@ -72,14 +72,14 @@ ...@@ -72,14 +72,14 @@
<item row="0" column="1"> <item row="0" column="1">
<widget class="QLineEdit" name="dT_P_set"> <widget class="QLineEdit" name="dT_P_set">
<property name="text"> <property name="text">
<string>dT_P_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2"> <item row="0" column="2">
<widget class="QLineEdit" name="dT_P_get"> <widget class="QLineEdit" name="dT_P_get">
<property name="text"> <property name="text">
<string>dT_P_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -89,14 +89,14 @@ ...@@ -89,14 +89,14 @@
<item row="1" column="1"> <item row="1" column="1">
<widget class="QLineEdit" name="dT_I_set"> <widget class="QLineEdit" name="dT_I_set">
<property name="text"> <property name="text">
<string>dT_I_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="2"> <item row="1" column="2">
<widget class="QLineEdit" name="dT_I_get"> <widget class="QLineEdit" name="dT_I_get">
<property name="text"> <property name="text">
<string>dT_I_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -106,14 +106,14 @@ ...@@ -106,14 +106,14 @@
<item row="2" column="1"> <item row="2" column="1">
<widget class="QLineEdit" name="dT_D_set"> <widget class="QLineEdit" name="dT_D_set">
<property name="text"> <property name="text">
<string>dT_D_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="2"> <item row="2" column="2">
<widget class="QLineEdit" name="dT_D_get"> <widget class="QLineEdit" name="dT_D_get">
<property name="text"> <property name="text">
<string>dT_D_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -242,14 +242,14 @@ ...@@ -242,14 +242,14 @@
<item row="0" column="1"> <item row="0" column="1">
<widget class="QLineEdit" name="dE_P_set"> <widget class="QLineEdit" name="dE_P_set">
<property name="text"> <property name="text">
<string>dE_P_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2"> <item row="0" column="2">
<widget class="QLineEdit" name="dE_P_get"> <widget class="QLineEdit" name="dE_P_get">
<property name="text"> <property name="text">
<string>dE_P_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -259,14 +259,14 @@ ...@@ -259,14 +259,14 @@
<item row="1" column="1"> <item row="1" column="1">
<widget class="QLineEdit" name="dE_I_set"> <widget class="QLineEdit" name="dE_I_set">
<property name="text"> <property name="text">
<string>dE_I_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="2"> <item row="1" column="2">
<widget class="QLineEdit" name="dE_I_get"> <widget class="QLineEdit" name="dE_I_get">
<property name="text"> <property name="text">
<string>dE_I_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -276,14 +276,14 @@ ...@@ -276,14 +276,14 @@
<item row="2" column="1"> <item row="2" column="1">
<widget class="QLineEdit" name="dE_D_set"> <widget class="QLineEdit" name="dE_D_set">
<property name="text"> <property name="text">
<string>dE_D_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="2"> <item row="2" column="2">
<widget class="QLineEdit" name="dE_D_get"> <widget class="QLineEdit" name="dE_D_get">
<property name="text"> <property name="text">
<string>dE_D_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -405,14 +405,14 @@ ...@@ -405,14 +405,14 @@
<item row="0" column="1"> <item row="0" column="1">
<widget class="QLineEdit" name="dA_P_set"> <widget class="QLineEdit" name="dA_P_set">
<property name="text"> <property name="text">
<string>dA_P_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2"> <item row="0" column="2">
<widget class="QLineEdit" name="dA_P_get"> <widget class="QLineEdit" name="dA_P_get">
<property name="text"> <property name="text">
<string>dA_P_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -422,14 +422,14 @@ ...@@ -422,14 +422,14 @@
<item row="1" column="1"> <item row="1" column="1">
<widget class="QLineEdit" name="dA_I_set"> <widget class="QLineEdit" name="dA_I_set">
<property name="text"> <property name="text">
<string>dA_I_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="2"> <item row="1" column="2">
<widget class="QLineEdit" name="dA_I_get"> <widget class="QLineEdit" name="dA_I_get">
<property name="text"> <property name="text">
<string>dA_I_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -439,14 +439,14 @@ ...@@ -439,14 +439,14 @@
<item row="2" column="1"> <item row="2" column="1">
<widget class="QLineEdit" name="dA_D_set"> <widget class="QLineEdit" name="dA_D_set">
<property name="text"> <property name="text">
<string>dA_D_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="2"> <item row="2" column="2">
<widget class="QLineEdit" name="dA_D_get"> <widget class="QLineEdit" name="dA_D_get">
<property name="text"> <property name="text">
<string>dA_D_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -545,14 +545,14 @@ ...@@ -545,14 +545,14 @@
<item row="0" column="1"> <item row="0" column="1">
<widget class="QLineEdit" name="HELPComm_P_set"> <widget class="QLineEdit" name="HELPComm_P_set">
<property name="text"> <property name="text">
<string>HELPComm_P_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2"> <item row="0" column="2">
<widget class="QLineEdit" name="HELPComm_P_get"> <widget class="QLineEdit" name="HELPComm_P_get">
<property name="text"> <property name="text">
<string>HELPComm_P_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -562,14 +562,14 @@ ...@@ -562,14 +562,14 @@
<item row="1" column="1"> <item row="1" column="1">
<widget class="QLineEdit" name="HELPComm_I_set"> <widget class="QLineEdit" name="HELPComm_I_set">
<property name="text"> <property name="text">
<string>HELPComm_I_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="2"> <item row="1" column="2">
<widget class="QLineEdit" name="HELPComm_I_get"> <widget class="QLineEdit" name="HELPComm_I_get">
<property name="text"> <property name="text">
<string>HELPComm_I_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -646,14 +646,14 @@ ...@@ -646,14 +646,14 @@
<item row="0" column="1"> <item row="0" column="1">
<widget class="QLineEdit" name="HELPComm_FF_set"> <widget class="QLineEdit" name="HELPComm_FF_set">
<property name="text"> <property name="text">
<string>HELPComm_FF_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2"> <item row="0" column="2">
<widget class="QLineEdit" name="HELPComm_FF_get"> <widget class="QLineEdit" name="HELPComm_FF_get">
<property name="text"> <property name="text">
<string>HELPComm_FF_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -775,14 +775,14 @@ ...@@ -775,14 +775,14 @@
<item row="0" column="1"> <item row="0" column="1">
<widget class="QLineEdit" name="dR_P_set"> <widget class="QLineEdit" name="dR_P_set">
<property name="text"> <property name="text">
<string>dR_P_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2"> <item row="0" column="2">
<widget class="QLineEdit" name="dR_P_get"> <widget class="QLineEdit" name="dR_P_get">
<property name="text"> <property name="text">
<string>dR_P_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -792,14 +792,14 @@ ...@@ -792,14 +792,14 @@
<item row="1" column="1"> <item row="1" column="1">
<widget class="QLineEdit" name="dR_I_set"> <widget class="QLineEdit" name="dR_I_set">
<property name="text"> <property name="text">
<string>dR_I_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="1" column="2"> <item row="1" column="2">
<widget class="QLineEdit" name="dR_I_get"> <widget class="QLineEdit" name="dR_I_get">
<property name="text"> <property name="text">
<string>dR_I_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -809,14 +809,14 @@ ...@@ -809,14 +809,14 @@
<item row="2" column="1"> <item row="2" column="1">
<widget class="QLineEdit" name="dR_D_set"> <widget class="QLineEdit" name="dR_D_set">
<property name="text"> <property name="text">
<string>dR_D_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="2" column="2"> <item row="2" column="2">
<widget class="QLineEdit" name="dR_D_get"> <widget class="QLineEdit" name="dR_D_get">
<property name="text"> <property name="text">
<string>dR_D_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
...@@ -910,14 +910,14 @@ ...@@ -910,14 +910,14 @@
<item row="0" column="1"> <item row="0" column="1">
<widget class="QLineEdit" name="P2dT_FF_set"> <widget class="QLineEdit" name="P2dT_FF_set">
<property name="text"> <property name="text">
<string>P2dT_FF_set</string> <string>0.0</string>
</property> </property>
</widget> </widget>
</item> </item>
<item row="0" column="2"> <item row="0" column="2">
<widget class="QLineEdit" name="P2dT_FF_get"> <widget class="QLineEdit" name="P2dT_FF_get">
<property name="text"> <property name="text">
<string>P2dT_FF_get</string> <string>0.0</string>
</property> </property>
<property name="readOnly"> <property name="readOnly">
<bool>true</bool> <bool>true</bool>
......
...@@ -23,13 +23,7 @@ public: ...@@ -23,13 +23,7 @@ public:
protected: protected:
virtual void mousePressEvent(QMouseEvent* event); virtual void mousePressEvent(QMouseEvent* event);
virtual void mouseReleaseEvent(QMouseEvent* event); virtual void mouseReleaseEvent(QMouseEvent* event);
//void mouseMoveEvent(QMouseEvent* event); void mouseMoveEvent(QMouseEvent* event);
void mouseMoveEvent(QMouseEvent* event);
// virtual void wheelEvent(QWheelEvent* event);
//virtual void resizeEvent(QResizeEvent* event);
private: private:
Ui::SlugsVideoCamControl *ui; Ui::SlugsVideoCamControl *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