diff --git a/src/ui/SlugsPIDControl.cpp b/src/ui/SlugsPIDControl.cpp index 08630c4e5d1f4fe7c5c40a18fc9276b4dceee917..779754aceb9b5ba641378ee9778ee214ded11240 100644 --- a/src/ui/SlugsPIDControl.cpp +++ b/src/ui/SlugsPIDControl.cpp @@ -463,9 +463,9 @@ void SlugsPIDControl::changeColor_GREEN_Pitch2dT_groupBox() //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(); + 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; @@ -532,6 +532,7 @@ void SlugsPIDControl::receivePidValues(int systemId, const mavlink_pid_t &pidVal break; case 8: ui->P2dT_FF_get->setText(QString::number(pidValues.pVal)); + break; default: diff --git a/src/ui/SlugsPIDControl.h b/src/ui/SlugsPIDControl.h index e6e818bee7e7cad0592b92d60e0e9ecb6b0ee6b2..4a0ee963c5c27a72681358ca39e87620127865ff 100644 --- a/src/ui/SlugsPIDControl.h +++ b/src/ui/SlugsPIDControl.h @@ -281,10 +281,10 @@ private: mavlink_slugs_action_t actionSlugs; QTimer* refreshTimerSet; ///< The main timer, controls the update view - QTimer* refreshTimerGet; ///< The main timer, controls the update view + QTimer* refreshTimerGet; ///< The main timer, controls the update view int counterRefreshSet; int counterRefreshGet; - QMutex valuesMutex; + QMutex valuesMutex; }; #endif // SLUGSPIDCONTROL_H diff --git a/src/ui/SlugsPIDControl.ui b/src/ui/SlugsPIDControl.ui index 042f3d92c3fe31622011b0295bb50fa622ff0a7b..6de57a0178d35a4d94f14b72a70e166ae82714cf 100644 --- a/src/ui/SlugsPIDControl.ui +++ b/src/ui/SlugsPIDControl.ui @@ -121,13 +121,6 @@ - - - - Recepcion - - - @@ -956,6 +949,13 @@ + + + + Recepcion + + + diff --git a/src/ui/SlugsPadCameraControl.cpp b/src/ui/SlugsPadCameraControl.cpp index 071585d39a46d23662cf615f104ec7005e5f5656..3e198c68be7473290b6bb517e3f65250acbdaf51 100644 --- a/src/ui/SlugsPadCameraControl.cpp +++ b/src/ui/SlugsPadCameraControl.cpp @@ -13,6 +13,9 @@ SlugsPadCameraControl::SlugsPadCameraControl(QWidget *parent) : ui->setupUi(this); x1= 0; y1 = 0; + bearingPad = 0; + distancePad = 0; + directionPad = "no"; } @@ -53,6 +56,9 @@ void SlugsPadCameraControl::mouseReleaseEvent(QMouseEvent *event) //emit mouseReleaseCoord(event->x(),event->y()); //getDeltaPositionPad(event->x(), event->y()); + xFin = event->x(); + yFin = event->y(); + } @@ -73,6 +79,13 @@ void SlugsPadCameraControl::paintEvent(QPaintEvent *pe) painter.drawLine(QPoint(ui->frame->geometry().topLeft().x(),ui->frame->height()/2), QPoint(ui->frame->geometry().bottomRight().x(),ui->frame->height()/2)); + painter.setPen(Qt::white); + + //QPointF coordTemp = getPointBy_BearingDistance(ui->frame->width()/2,ui->frame->height()/2,bearingPad,distancePad); + + painter.drawLine(QPoint(ui->frame->width()/2,ui->frame->height()/2), + QPoint(xFin,yFin)); + // painter.drawLine(QPoint()); //painter.drawLines(padLines); @@ -172,8 +185,15 @@ void SlugsPadCameraControl::getDeltaPositionPad(int x2, int y2) } + bearingPad = bearing; + distancePad = dist; + directionPad = dir; emit changeCursorPosition(bearing, dist, dir); + update(); + + + } double SlugsPadCameraControl::getDistPixel(int x1, int y1, int x2, int y2) @@ -245,3 +265,17 @@ QPointF SlugsPadCameraControl::ObtenerMarcacionDistanciaPixel(double lon1, doubl } + +QPointF SlugsPadCameraControl::getPointBy_BearingDistance(double lat1, double lon1, double rumbo, double distancia) +{ + double lon2 = 0; + double lat2 = 0; + double rad= M_PI/180; + + rumbo = rumbo*rad; + lon2=(lon1 + ((distancia/60) * (sin(rumbo)))); + lat2=(lat1 + ((distancia/60) * (cos(rumbo)))); + + return QPointF(lon2,lat2); +} + diff --git a/src/ui/SlugsPadCameraControl.h b/src/ui/SlugsPadCameraControl.h index ca7c04a681d51ba5f0dacf89edc9056ffe8547f6..bb35976cf2952d27c775f7ba1e6b7174e1f83495 100644 --- a/src/ui/SlugsPadCameraControl.h +++ b/src/ui/SlugsPadCameraControl.h @@ -21,6 +21,8 @@ public slots: void getDeltaPositionPad(int x, int y); double getDistPixel(int x1, int y1, int x2, int y2); QPointF ObtenerMarcacionDistanciaPixel(double lon1, double lat1, double lon2, double lat2); + QPointF getPointBy_BearingDistance(double lat1, double lon1, double rumbo, double distancia); + signals: @@ -37,11 +39,17 @@ protected: void mouseMoveEvent(QMouseEvent* event); void paintEvent(QPaintEvent *pe); + private: Ui::SlugsPadCameraControl *ui; bool dragging; int x1; int y1; + int xFin; + int yFin; + double bearingPad; + double distancePad; + QString directionPad; }; diff --git a/src/ui/SlugsVideoCamControl.cpp b/src/ui/SlugsVideoCamControl.cpp index 9f3ad7b6644a6f6d93e3cfc0ac0e4c925c82487b..7e091753ac1d3ecb0f1680687c7546f0a97125b7 100644 --- a/src/ui/SlugsVideoCamControl.cpp +++ b/src/ui/SlugsVideoCamControl.cpp @@ -41,41 +41,41 @@ SlugsVideoCamControl::~SlugsVideoCamControl() delete ui; } -void SlugsVideoCamControl::mouseMoveEvent(QMouseEvent *event) -{ - Q_UNUSED(event); +//void SlugsVideoCamControl::mouseMoveEvent(QMouseEvent *event) +//{ +// Q_UNUSED(event); -} +//} -void SlugsVideoCamControl::mousePressEvent(QMouseEvent *evnt) -{ - Q_UNUSED(evnt); +//void SlugsVideoCamControl::mousePressEvent(QMouseEvent *evnt) +//{ +// Q_UNUSED(evnt); -} +//} -void SlugsVideoCamControl::mouseReleaseEvent(QMouseEvent *evnt) -{ - Q_UNUSED(evnt); +//void SlugsVideoCamControl::mouseReleaseEvent(QMouseEvent *evnt) +//{ +// Q_UNUSED(evnt); -} +//} -void SlugsVideoCamControl::mousePadMoveEvent(int x, int y) -{ +//void SlugsVideoCamControl::mousePadMoveEvent(int x, int y) +//{ -} +//} -void SlugsVideoCamControl::mousePadPressEvent(int x, int y) -{ +//void SlugsVideoCamControl::mousePadPressEvent(int x, int y) +//{ -} +//} -void SlugsVideoCamControl::mousePadReleaseEvent(int x, int y) -{ +//void SlugsVideoCamControl::mousePadReleaseEvent(int x, int y) +//{ -} +//} void SlugsVideoCamControl::changeViewCamBorderAtMapStatus(bool status) { diff --git a/src/ui/SlugsVideoCamControl.h b/src/ui/SlugsVideoCamControl.h index 2580033a5e1dee3883ea60008707112b6f11f674..0180fd52a5c8737d73a1104113548c62715e30ea 100644 --- a/src/ui/SlugsVideoCamControl.h +++ b/src/ui/SlugsVideoCamControl.h @@ -27,22 +27,43 @@ public: ~SlugsVideoCamControl(); public slots: + /** + * @brief status = true: emit signal to draw a border cam over the map + */ void changeViewCamBorderAtMapStatus(bool status); - void getDeltaPositionPad(double dir, double dist, QString dirText); - - - void mousePadPressEvent(int x, int y); - void mousePadReleaseEvent(int x, int y); - void mousePadMoveEvent(int x, int y); + /** + * @brief show the values of mousepad on ui (labels) and emit a changeCamPosition(signal) + * with values: + * bearing and distance from mouse over the pad + * dirText: direction of mouse movement in text format (up, right,right up,right down, + * left, left up, left down, down) + */ + void getDeltaPositionPad(double bearing, double distance, QString dirText); + +// /** +// * @brief +// */ +// void mousePadPressEvent(int x, int y); +// void mousePadReleaseEvent(int x, int y); +// void mousePadMoveEvent(int x, int y); signals: - void changeCamPosition(double dist, double dir, QString textDir); + /** + * @brief emit values from mousepad: + * bearing and distance from mouse over the pad + * dirText: direction of mouse movement in text format (up, right,right up,right down, + * left, left up, left down, down) + */ + void changeCamPosition(double distance, double bearing, QString textDir); + /** + * @brief emit signal to draw a border cam over the map if status is true + */ void viewCamBorderAtMap(bool status); protected: - void mousePressEvent(QMouseEvent* event); - void mouseReleaseEvent(QMouseEvent* event); - void mouseMoveEvent(QMouseEvent* event); +// void mousePressEvent(QMouseEvent* event); +// void mouseReleaseEvent(QMouseEvent* event); +// void mouseMoveEvent(QMouseEvent* event);