Commit e441869a authored by Mariano Lizarraga's avatar Mariano Lizarraga

Merge branch 'master' of git://github.com/tecnosapiens/qgroundcontrol into mergeRemote

parents 174f9253 30afdd85
......@@ -138,7 +138,9 @@ FORMS += src/ui/MainWindow.ui \
src/ui/QGCRemoteControlView.ui \
src/ui/WaypointGlobalView.ui \
src/ui/SlugsDataSensorView.ui \
src/ui/SlugsHilSim.ui
src/ui/SlugsHilSim.ui \
src/ui/SlugsDataSensorView.ui \
src/ui/SlugsPIDControl.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
......@@ -239,7 +241,8 @@ HEADERS += src/MG.h \
src/ui/map3D/Imagery.h \
src/comm/QGCMAVLink.h\
src/ui/SlugsDataSensorView.h \
src/ui/SlugsHilSim.h
src/ui/SlugsHilSim.h \
src/ui/SlugsPIDControl.h
SOURCES += src/main.cc \
src/Core.cc \
src/uas/UASManager.cc \
......@@ -320,7 +323,8 @@ SOURCES += src/main.cc \
src/ui/map3D/WebImage.cc \
src/ui/map3D/Imagery.cc \
src/ui/SlugsDataSensorView.cc \
src/ui/SlugsHilSim.cc
src/ui/SlugsHilSim.cc \
src/ui/SlugsPIDControl.cpp
RESOURCES = mavground.qrc
......
......@@ -47,7 +47,7 @@ void SlugsMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
cpu_load.ctrlLoad,
cpu_load.batVolt,
0);
qDebug()<<"--------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_CPU_LOAD 170";
//qDebug()<<"--------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_CPU_LOAD 170";
break;
}
case MAVLINK_MSG_ID_AIR_DATA://171
......@@ -64,7 +64,7 @@ qDebug()<<"--------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_CPU_LOAD 170";
air_data.staticPressure,
air_data.temperature,
time);
qDebug()<<"--------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_AIR_DATA 171";
//qDebug()<<"--------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_AIR_DATA 171";
break;
}
case MAVLINK_MSG_ID_SENSOR_BIAS://172
......@@ -87,7 +87,7 @@ qDebug()<<"--------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_AIR_DATA 171";
sensor_bias.gyBias,
sensor_bias.gzBias,
0);
qDebug()<<"------------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_SENSOR_BIAS 172";
// qDebug()<<"------------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_SENSOR_BIAS 172";
break;
......@@ -112,7 +112,7 @@ qDebug()<<"--------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_AIR_DATA 171";
diagnostic.diagSh2,
diagnostic.diagSh3,
0);
qDebug()<<"------->>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_DIAGNOSTIC 173";
//qDebug()<<"------->>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_DIAGNOSTIC 173";
break;
}
case MAVLINK_MSG_ID_PILOT_CONSOLE://174
......@@ -133,7 +133,7 @@ qDebug()<<"------->>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_DIAGNOSTIC 173";
pilot.dr,
pilot.de,
0);
qDebug()<<"---------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_PILOT_CONSOLE 174";
// qDebug()<<"---------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_PILOT_CONSOLE 174";
break;
......@@ -166,7 +166,7 @@ qDebug()<<"------->>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_DIAGNOSTIC 173";
pwm.aux1,
pwm.aux2,
0);
qDebug()<<"----------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_PWM_COMMANDS 175";
//qDebug()<<"----------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_PWM_COMMANDS 175";
break;
}
......@@ -197,7 +197,7 @@ qDebug()<<"----------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_PWM_COMMANDS 175"
nav.toWP,
time);
qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_SLUGS_NAVIGATION 176";
// qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_SLUGS_NAVIGATION 176";
break;
}
......@@ -222,7 +222,7 @@ qDebug()<<"----------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_PWM_COMMANDS 175"
dataLog.fl_6,
time);
qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO LOG DATA 177";
// qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO LOG DATA 177";
......@@ -259,7 +259,7 @@ qDebug()<<"----------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_PWM_COMMANDS 175"
qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO filtering data 178";
// qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO filtering data 178";
......@@ -291,52 +291,60 @@ qDebug()<<"----------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_PWM_COMMANDS 175"
qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_GPS_DATE_TIME 179";
// qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_GPS_DATE_TIME 179";
break;
}
case MAVLINK_MSG_ID_MID_LVL_CMDS://180
case MAVLINK_MSG_ID_ACTION_ACK:
{
qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_ACTION_ACK";
mavlink_action_ack_t ack;
mavlink_msg_action_ack_decode(&message,&ack);
emit slugsActionAck(uasId,ack.action,ack.result);
}
// case MAVLINK_MSG_ID_MID_LVL_CMDS://180
// {
qDebug()<<"------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_MID_LVL_CMDS 180";
// // qDebug()<<"------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_MID_LVL_CMDS 180";
break;
}
case MAVLINK_MSG_ID_CTRL_SRFC_PT://181
{
// break;
// }
// case MAVLINK_MSG_ID_CTRL_SRFC_PT://181
// {
qDebug()<<"--------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_CTRL_SRFC_PT 181";
// // qDebug()<<"--------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_CTRL_SRFC_PT 181";
break;
}
case MAVLINK_MSG_ID_PID://182
{
// break;
// }
// case MAVLINK_MSG_ID_PID://182
// {
qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_PID 182";
// // qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_PID 182";
break;
}
case MAVLINK_MSG_ID_SLUGS_ACTION://183
{
// break;
// }
// case MAVLINK_MSG_ID_SLUGS_ACTION://183
// {
qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_SLUGS_ACTION 183";
// // qDebug()<<"-------->>>>>>>>>>>>>>> EMITIENDO MAVLINK_MSG_ID_SLUGS_ACTION 183";
break;
}
// break;
// }
#endif
default:
......
......@@ -135,6 +135,10 @@ signals:
uint8_t gpsvisSat,
quint64 time);
void slugsActionAck(int systemId,
uint8_t action,
uint8_t result);
......
......@@ -437,6 +437,7 @@ void UASWaypointManager::readWaypoints()
void UASWaypointManager::writeWaypoints()
{
qDebug() << "+++++++++++++++++++>>>> Entro Funcion Write WP";
if (current_state == WP_IDLE)
{
if (waypoints.count() > 0)
......@@ -541,6 +542,7 @@ void UASWaypointManager::sendWaypointCount()
wpc.target_component = MAV_COMP_ID_WAYPOINTPLANNER;
wpc.count = current_count;
qDebug() << "sent waypoint count (" << wpc.count << ") to ID " << wpc.target_system;
emit updateStatusString(QString("start transmitting waypoints..."));
mavlink_msg_waypoint_count_encode(uas.mavlink->getSystemId(), uas.mavlink->getComponentId(), &message, &wpc);
......
......@@ -181,6 +181,9 @@ void MainWindow::buildWidgets()
slugsDataWidget = new QDockWidget(tr("Slugs Data"), this);
slugsDataWidget->setWidget( new SlugsDataSensorView(this));
slugsPIDControlWidget = new QDockWidget(tr("PID Control"), this);
slugsPIDControlWidget->setWidget(new SlugsPIDControl(this));
slugsHilSimWidget = new QDockWidget(tr("Slugs Hil Sim"), this);
slugsHilSimWidget->setWidget( new SlugsHilSim(this));
......@@ -225,6 +228,7 @@ void MainWindow::connectWidgets()
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), dynamic_cast<SlugsHilSim*>(slugsHilSimWidget->widget()), SLOT(activeUasSet(UASInterface*)) );
}
}
void MainWindow::arrangeCenterStack()
......@@ -917,6 +921,13 @@ void MainWindow::loadGlobalOperatorView()
slugsDataWidget->show();
}
// Slugs Data View
if (slugsPIDControlWidget)
{
addDockWidget(Qt::LeftDockWidgetArea, slugsPIDControlWidget);
slugsPIDControlWidget->show();
}
// // UAS CONTROL
......
......@@ -66,9 +66,13 @@ This file is part of the QGROUNDCONTROL project
#include "QMap3DWidget.h"
#include "SlugsDataSensorView.h"
#include "LogCompressor.h"
#include "SlugsPIDControl.h"
#include "slugshilsim.h"
/**
* @brief Main Application Window
*
......@@ -181,8 +185,10 @@ protected:
QPointer<QDockWidget> hsiDockWidget;
QPointer<QDockWidget> rcViewDockWidget;
QPointer<QDockWidget> slugsDataWidget;
QPointer<QDockWidget> slugsPIDControlWidget;
QPointer<QDockWidget> slugsHilSimWidget;
// Popup widgets
JoystickWidget* joystickWidget;
......
......@@ -432,7 +432,6 @@ void SlugsDataSensorView::slugsDataLogChanged(int systemId,
double logfl_6,
quint64 time)
{
qDebug()<<"----------------------------------------------------->>>>>>>>>>>>>>> ACTUALIZANDO LOG DATA";
Q_UNUSED(systemId);
Logfl_1 = logfl_1;
Logfl_2 = logfl_2;
......
#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();
// connect_set_pushButtons();
// connect_AirSpeed_LineEdit();
// connect_PitchFollowei_LineEdit();
// connect_RollControl_LineEdit();
// connect_HeigthError_LineEdit();
// connect_YawDamper_LineEdit();
// connect_Pitch2dT_LineEdit();
}
/**
* @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)
{
SlugsMAV* slugsMav = dynamic_cast<SlugsMAV*>(uas);
if (slugsMav != NULL)
{
connect(slugsMav,SIGNAL(slugsActionAck(int,uint8_t,uint8_t)),this,SLOT(recibeMensaje(int,uint8_t,uint8_t)));
}
// Set this UAS as active if it is the first one
if(activeUAS == 0)
{
activeUAS = uas;
systemId = activeUAS->getUASID();
connect_editLinesPDIvalues();
//qDebug()<<"------------------->Active UAS ID: "<<uas->getUASID();
}
}
/**
* @brief Connect Edition Lines for PID Values
*
* @param
*/
void SlugsPIDControl::connect_editLinesPDIvalues()
{
if(activeUAS)
{
connect_set_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()));
}
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()
{
//create the packet
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();
UAS *uas = dynamic_cast<UAS*>(UASManager::instance()->getActiveUAS());
mavlink_message_t msg;
mavlink_msg_pid_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &pidMessage);
uas->sendMessage(msg);
ui->AirSpeedHold_groupBox->setStyleSheet(GREENcolorStyle);
}
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()
{
ui->PitchFlowei_groupBox->setStyleSheet(GREENcolorStyle);
}
// 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()
{
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)));
}
// 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()
{
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)));
}
// 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()
{
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)));
}
// 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()
{
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::recibeMensaje(int systemId, uint8_t action, uint8_t result)
{
ui->recepcion_label->setText(QString::number(action));
}
#ifndef SLUGSPIDCONTROL_H
#define SLUGSPIDCONTROL_H
#include <QWidget>
#include<QGroupBox>
#include "UASInterface.h"
#include "QGCMAVLink.h"
#include "SlugsMAV.h"
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 Edition Lines for PID Values
*
* @param
*/
void connect_editLinesPDIvalues();
// 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();
// 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();
// 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();
// 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();
// 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();
// 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();
//Create, send and get Messages PID
// void createMessagePID();
void recibeMensaje(int systemId, uint8_t action, uint8_t result);
private:
Ui::SlugsPIDControl *ui;
UASInterface* activeUAS;
int systemId;
bool change_dT;
//Color Styles
QString REDcolorStyle;
QString GREENcolorStyle;
QString ORIGINcolorStyle;
//SlugsMav Message
mavlink_pid_t pidMessage;
};
#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>504</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="margin">
<number>2</number>
</property>
<item>
<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>dT_P_set</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="dT_P_get">
<property name="text">
<string>dT_P_get</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>dT_I_set</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLineEdit" name="dT_I_get">
<property name="text">
<string>dT_I_get</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>dT_D_set</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLineEdit" name="dT_D_get">
<property name="text">
<string>dT_D_get</string>
</property>
<property name="readOnly">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QLabel" name="recepcion_label">
<property name="text">
<string>Recepcion</string>
</property>
</widget>
</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>dE_P_set</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="dE_P_get">
<property name="text">
<string>dE_P_get</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>dE_I_set</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLineEdit" name="dE_I_get">
<property name="text">
<string>dE_I_get</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>dE_D_set</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLineEdit" name="dE_D_get">
<property name="text">
<string>dE_D_get</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>dA_P_set</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="dA_P_get">
<property name="text">
<string>dA_P_get</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>dA_I_set</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLineEdit" name="dA_I_get">
<property name="text">
<string>dA_I_get</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>dA_D_set</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLineEdit" name="dA_D_get">
<property name="text">
<string>dA_D_get</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>
<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>HELPComm_P_set</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="HELPComm_P_get">
<property name="text">
<string>HELPComm_P_get</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>HELPComm_I_set</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLineEdit" name="HELPComm_I_get">
<property name="text">
<string>HELPComm_I_get</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>HELPComm_FF_set</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="HELPComm_FF_get">
<property name="text">
<string>HELPComm_FF_get</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>dR_P_set</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="dR_P_get">
<property name="text">
<string>dR_P_get</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>dR_I_set</string>
</property>
</widget>
</item>
<item row="1" column="2">
<widget class="QLineEdit" name="dR_I_get">
<property name="text">
<string>dR_I_get</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>dR_D_set</string>
</property>
</widget>
</item>
<item row="2" column="2">
<widget class="QLineEdit" name="dR_D_get">
<property name="text">
<string>dR_D_get</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>P2dT_FF_set</string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QLineEdit" name="P2dT_FF_get">
<property name="text">
<string>P2dT_FF_get</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>
</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>
</widget>
<resources/>
<connections/>
</ui>
......@@ -200,6 +200,11 @@ float SlugsHilSim::getFloatFromDatagram (const QByteArray* datagram, unsigned ch
tmpF2C.chData[2] = datagram->at((*i)++);
tmpF2C.chData[3] = datagram->at((*i)++);
// if (uas != NULL) {
// //activeUas = uas;
// }
return tmpF2C.flData;
}
......@@ -210,6 +215,7 @@ uint16_t SlugsHilSim::getUint16FromDatagram (const QByteArray* datagram, unsigne
tmpU2C.chData[1] = datagram->at((*i)++);
return tmpU2C.uiData;
}
void SlugsHilSim::linkSelected(int cbIndex){
......
......@@ -105,6 +105,10 @@ public slots:
*/
void linkSelected (int cbIndex);
public slots:
private:
typedef union _tFloatToChar {
......
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