diff --git a/src/ui/SlugsDataSensorView.cc b/src/ui/SlugsDataSensorView.cc
index fae39cc0cb9a00da4f7bb1c9c3890f7f3d9786fc..749f2bd19506eb1e35ea26e0c2523616ffe51b0c 100644
--- a/src/ui/SlugsDataSensorView.cc
+++ b/src/ui/SlugsDataSensorView.cc
@@ -15,6 +15,10 @@ SlugsDataSensorView::SlugsDataSensorView(QWidget *parent) :
activeUAS = NULL;
this->setVisible(false);
+
+
+
+
}
SlugsDataSensorView::~SlugsDataSensorView()
@@ -236,4 +240,6 @@ void SlugsDataSensorView::slugsGPSDateTimeChanged(int systemId,
ui->m_GpsSat->setText(QString::number(gpsDateTime.visSat));
}
+
+
#endif // MAVLINK_ENABLED_SLUGS
diff --git a/src/ui/SlugsDataSensorView.h b/src/ui/SlugsDataSensorView.h
index 6cd40b01bbd70d9dca789d52c40a78c5b8cd5aad..ed0b9f07c7dd2195ddca02c739a7b1e795635fc7 100644
--- a/src/ui/SlugsDataSensorView.h
+++ b/src/ui/SlugsDataSensorView.h
@@ -38,6 +38,7 @@ This file is part of the QGROUNDCONTROL project
#include "SlugsMAV.h"
#include "mavlink.h"
+
namespace Ui {
class SlugsDataSensorView;
}
@@ -163,6 +164,8 @@ public slots:
void slugsGPSDateTimeChanged(int systemId,
const mavlink_gps_date_time_t& gpsDateTime);
+
+
#endif // MAVLINK_ENABLED_SLUGS
protected:
@@ -172,6 +175,11 @@ private:
Ui::SlugsDataSensorView *ui;
+
+
+
+
+
};
#endif // SLUGSDATASENSORVIEW_H
diff --git a/src/ui/SlugsDataSensorView.ui b/src/ui/SlugsDataSensorView.ui
index 917e4571738f72967e0f48d57d1ea724e850e682..4a6e2de6bc0a1e9004a25ffdd440a16eb4c1a06a 100644
--- a/src/ui/SlugsDataSensorView.ui
+++ b/src/ui/SlugsDataSensorView.ui
@@ -35,7 +35,7 @@
-
- 2
+ 0
diff --git a/src/ui/SlugsPIDControl.cpp b/src/ui/SlugsPIDControl.cpp
index 9168eb99f4c20712b91d35b3a73e94cac58bc3d3..18fd516304cd92f4aff41c4726dc55ffecc8051f 100644
--- a/src/ui/SlugsPIDControl.cpp
+++ b/src/ui/SlugsPIDControl.cpp
@@ -22,6 +22,19 @@ SlugsPIDControl::SlugsPIDControl(QWidget *parent) :
setRedColorStyle();
setGreenColorStyle();
+ refreshTimerGet = new QTimer(this);
+ refreshTimerGet->setInterval(100); // 20 Hz
+ connect(refreshTimerGet, SIGNAL(timeout()), this, SLOT(slugsGetGeneral()));
+
+
+ refreshTimerSet = new QTimer(this);
+ refreshTimerSet->setInterval(100); // 20 Hz
+ connect(refreshTimerSet, SIGNAL(timeout()), this, SLOT(slugsSetGeneral()));
+
+
+ counterRefreshGet = 1;
+ counterRefreshSet = 1;
+
}
/**
@@ -40,6 +53,8 @@ void SlugsPIDControl::activeUasSet(UASInterface* uas)
{
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)) );
+
+ connect(ui->setGeneral_pushButton,SIGNAL(clicked()),this,SLOT(slugsTimerStartSet()));
}
#endif // MAVLINK_ENABLED_SLUG
@@ -611,4 +626,90 @@ void SlugsPIDControl::sendMessagePIDStatus(int PIDtype)
}
}
+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;
+
+}
#endif // MAVLINK_ENABLED_SLUGS
diff --git a/src/ui/SlugsPIDControl.h b/src/ui/SlugsPIDControl.h
index d701de07d71d0345c5de26aac93ab3f41554b9c2..e6e818bee7e7cad0592b92d60e0e9ecb6b0ee6b2 100644
--- a/src/ui/SlugsPIDControl.h
+++ b/src/ui/SlugsPIDControl.h
@@ -7,6 +7,8 @@
#include "QGCMAVLink.h"
#include "SlugsMAV.h"
#include "mavlink.h"
+#include
+#include
namespace Ui {
class SlugsPIDControl;
@@ -236,6 +238,20 @@ public slots:
*/
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();
@@ -263,6 +279,12 @@ private:
//SlugsMav Message
mavlink_pid_t pidMessage;
mavlink_slugs_action_t actionSlugs;
+
+ 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
diff --git a/src/ui/SlugsPIDControl.ui b/src/ui/SlugsPIDControl.ui
index 936f2de402db8c2782d23d10917c3d560e4d50ef..042f3d92c3fe31622011b0295bb50fa622ff0a7b 100644
--- a/src/ui/SlugsPIDControl.ui
+++ b/src/ui/SlugsPIDControl.ui
@@ -7,759 +7,591 @@
0
0
429
- 504
+ 579
Form
-
-
- 2
-
-
-
-
-
-
-
-
- Air Speed Hold (dT)
-
-
-
-
-
-
-
-
-
-
- 10
- 75
- true
-
-
-
- P
-
-
-
- -
-
-
-
- 10
- 75
- true
-
-
-
- I
-
-
-
- -
-
-
-
- 10
- 75
- true
-
-
-
- D
-
-
-
- -
-
-
- 0.0
-
-
-
- -
-
-
- 0.0
-
-
- true
-
-
-
- -
-
-
- 0.0
-
-
-
- -
-
-
- 0.0
-
-
- true
-
-
-
- -
-
+
+
-
+
+
-
+
+
-
+
+
+ Air Speed Hold (dT)
+
+
+
-
+
+
-
+
+
+
+ 10
+ 75
+ true
+
+
+
+ P
+
+
+
+ -
+
+
+
+ 10
+ 75
+ true
+
+
+
+ I
+
+
+
+ -
+
+
+
+ 10
+ 75
+ true
+
+
+
+ D
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+
+
+ -
+
- 0.0
+ Recepcion
- -
-
-
- 0.0
-
-
- true
-
-
-
-
-
- -
-
-
- Recepcion
-
-
-
- -
-
-
- Qt::Vertical
-
-
-
- 20
- 10
-
-
-
-
- -
-
-
-
-
-
- SET
-
-
-
- -
-
-
- GET
-
-
-
- -
-
+
-
+
- Qt::Horizontal
+ Qt::Vertical
- 40
- 20
+ 20
+ 10
-
-
-
-
-
- -
-
-
- Qt::Vertical
-
-
-
- 20
- 40
-
-
-
-
- -
-
-
- Pitch Followei (dE)
-
-
-
-
-
-
-
-
-
-
- 10
- 75
- true
-
-
-
- P
-
-
-
- -
-
-
-
- 10
- 75
- true
-
-
-
- I
-
-
-
- -
-
-
-
- 10
- 75
- true
-
-
-
- D
-
-
-
- -
-
-
- 0.0
-
-
-
- -
-
-
- 0.0
-
-
- true
-
-
-
- -
-
-
- 0.0
-
-
-
- -
-
-
- 0.0
-
-
- true
-
-
-
- -
-
-
- 0.0
-
-
-
- -
-
-
- 0.0
-
-
- true
-
-
+
-
+
+
-
+
+
+ SET
+
+
+
+ -
+
+
+ GET
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+
-
- -
-
-
- Qt::Vertical
-
-
-
- 20
- 10
-
-
-
-
- -
-
-
-
-
-
- SET
-
-
-
- -
-
-
- GET
-
-
-
- -
-
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+ -
+
+
+ Pitch Followei (dE)
+
+
+
-
+
+
-
+
+
+
+ 10
+ 75
+ true
+
+
+
+ P
+
+
+
+ -
+
+
+
+ 10
+ 75
+ true
+
+
+
+ I
+
+
+
+ -
+
+
+
+ 10
+ 75
+ true
+
+
+
+ D
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+
+
+ -
+
- Qt::Horizontal
+ Qt::Vertical
- 40
- 20
+ 20
+ 10
-
-
-
-
-
- -
-
-
- Qt::Vertical
-
-
-
- 20
- 40
-
-
-
-
- -
-
-
- Roll Control (dA)
-
-
-
-
-
-
-
-
-
-
- 10
- 75
- true
-
-
-
- P
-
-
-
- -
-
-
-
- 10
- 75
- true
-
-
-
- I
-
-
-
- -
-
-
-
- 10
- 75
- true
-
-
-
- D
-
-
-
- -
-
-
- 0.0
-
-
-
- -
-
-
- 0.0
-
-
- true
-
-
-
- -
-
-
- 0.0
-
-
-
- -
-
-
- 0.0
-
-
- true
-
-
-
- -
-
-
- 0.0
-
-
-
- -
-
-
- 0.0
-
-
- true
-
-
+
-
+
+
-
+
+
+ SET
+
+
+
+ -
+
+
+ GET
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+
-
- -
-
-
- Qt::Vertical
-
-
-
- 20
- 10
-
-
-
-
- -
-
-
-
-
-
- SET
-
-
-
- -
-
-
- GET
-
-
-
- -
-
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+ -
+
+
+ Roll Control (dA)
+
+
+
-
+
+
-
+
+
+
+ 10
+ 75
+ true
+
+
+
+ P
+
+
+
+ -
+
+
+
+ 10
+ 75
+ true
+
+
+
+ I
+
+
+
+ -
+
+
+
+ 10
+ 75
+ true
+
+
+
+ D
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+
+
+ -
+
- Qt::Horizontal
+ Qt::Vertical
- 40
- 20
+ 20
+ 10
-
-
-
-
-
-
-
- -
-
-
-
-
-
- Heigth Error lo Pitch Comm
-
-
-
-
-
-
-
-
-
-
- 10
- 75
- true
-
-
-
- P
-
-
-
- -
-
-
-
- 10
- 75
- true
-
-
-
- I
-
-
-
- -
-
-
- 0.0
-
-
-
- -
-
-
- 0.0
-
-
- true
-
-
-
- -
-
-
- 0.0
-
-
-
- -
-
-
- 0.0
-
-
- true
-
-
-
-
-
- -
-
-
- Qt::Vertical
-
-
-
- 20
- 10
-
-
-
-
- -
-
-
-
- 10
- 75
- true
-
-
-
- QFrame::Sunken
-
-
- 5
-
-
- 1
-
-
- Qt::Horizontal
-
-
-
- -
-
-
- Qt::Vertical
-
-
-
- 20
- 10
-
-
-
-
- -
-
-
-
-
-
-
- 10
- 75
- true
-
-
-
- FF
-
-
-
- -
-
-
- 0.0
-
-
-
- -
-
-
- 0.0
-
-
- true
-
-
+
-
+
+
-
+
+
+ SET
+
+
+
+ -
+
+
+ GET
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+
-
- -
-
-
- Qt::Vertical
-
-
-
- 20
- 10
-
-
-
-
- -
-
-
-
-
-
- SET
-
-
-
- -
-
-
- GET
-
-
-
- -
-
+
+
+
+
+ -
+
+
-
+
+
+ Heigth Error lo Pitch Comm
+
+
+
-
+
+
-
+
+
+
+ 10
+ 75
+ true
+
+
+
+ P
+
+
+
+ -
+
+
+
+ 10
+ 75
+ true
+
+
+
+ I
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+
+
+ -
+
- Qt::Horizontal
+ Qt::Vertical
- 40
- 20
+ 20
+ 10
-
-
-
-
-
- -
-
-
- Qt::Vertical
-
-
-
- 20
- 40
-
-
-
-
- -
-
-
- Yaw Damper (dR)
-
-
-
-
-
-
-
-
-
-
- 10
- 75
- true
-
-
-
- P
-
-
-
- -
-
-
-
- 10
- 75
- true
-
-
-
- I
-
-
-
- -
-
+
-
+
10
@@ -767,215 +599,416 @@
true
-
- D
-
-
-
- -
-
-
- 0.0
-
-
-
- -
-
-
- 0.0
-
-
- true
-
-
-
- -
-
-
- 0.0
-
-
-
- -
-
-
- 0.0
-
-
- true
-
-
-
- -
-
-
- 0.0
-
-
-
- -
-
-
- 0.0
+
+ QFrame::Sunken
-
- true
+
+ 5
-
-
-
-
- -
-
-
- Qt::Vertical
-
-
-
- 20
- 10
-
-
-
-
- -
-
-
-
-
-
- SET
+
+ 1
-
-
- -
-
-
- GET
+
+ Qt::Horizontal
- -
-
+
-
+
- Qt::Horizontal
+ Qt::Vertical
- 40
- 20
+ 20
+ 10
-
-
-
-
-
- -
-
-
- Qt::Vertical
-
-
-
- 20
- 40
-
-
-
-
- -
-
-
- Pitch to dT FF term
-
-
-
-
-
-
-
-
-
-
- 10
- 75
- true
-
-
-
- FF
+
-
+
+
-
+
+
+
+ 10
+ 75
+ true
+
+
+
+ FF
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+
+
+ -
+
+
+ Qt::Vertical
-
-
- -
-
-
- 0.0
+
+
+ 20
+ 10
+
-
+
- -
-
-
- 0.0
-
-
- true
-
-
+
-
+
+
-
+
+
+ SET
+
+
+
+ -
+
+
+ GET
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+
-
- -
-
-
-
-
-
- SET
-
-
-
- -
-
-
- GET
-
-
-
- -
-
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+ -
+
+
+ Yaw Damper (dR)
+
+
+
-
+
+
-
+
+
+
+ 10
+ 75
+ true
+
+
+
+ P
+
+
+
+ -
+
+
+
+ 10
+ 75
+ true
+
+
+
+ I
+
+
+
+ -
+
+
+
+ 10
+ 75
+ true
+
+
+
+ D
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+
+
+ -
+
- Qt::Horizontal
+ Qt::Vertical
- 40
- 20
+ 20
+ 10
+ -
+
+
-
+
+
+ SET
+
+
+
+ -
+
+
+ GET
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+
+
-
-
-
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+ -
+
+
+ Pitch to dT FF term
+
+
+
-
+
+
-
+
+
+
+ 10
+ 75
+ true
+
+
+
+ FF
+
+
+
+ -
+
+
+ 0.0
+
+
+
+ -
+
+
+ 0.0
+
+
+ true
+
+
+
+
+
+ -
+
+
-
+
+
+ SET
+
+
+
+ -
+
+
+ GET
+
+
+
+ -
+
+
+ Qt::Horizontal
+
+
+
+ 40
+ 20
+
+
+
+
+
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+
+
+
+ -
+
+
+ Qt::Vertical
+
+
+
+ 20
+ 40
+
+
+
+
+ -
+
-
-
-
- Qt::Vertical
+
+
+ Set General
-
-
- 20
- 40
-
+
+
+ -
+
+
+ Get General
-
+
+ verticalSpacer_13
dT_P_set
diff --git a/src/ui/SlugsPadCameraControl.cpp b/src/ui/SlugsPadCameraControl.cpp
index 79262ba26cf7e42680e1474eb22671bddea74479..40b40c072ec83feb6c385387f04c696cccac969e 100644
--- a/src/ui/SlugsPadCameraControl.cpp
+++ b/src/ui/SlugsPadCameraControl.cpp
@@ -1,14 +1,231 @@
#include "SlugsPadCameraControl.h"
#include "ui_SlugsPadCameraControl.h"
+#include
+#include
+#include
+#include
SlugsPadCameraControl::SlugsPadCameraControl(QWidget *parent) :
- QWidget(parent),
- ui(new Ui::SlugsPadCameraControl)
+ QWidget(parent), //QGraphicsView(parent),
+ ui(new Ui::SlugsPadCameraControl),
+ dragging(0)
{
ui->setupUi(this);
+ x1= 0;
+ y1 = 0;
+
}
SlugsPadCameraControl::~SlugsPadCameraControl()
{
delete ui;
}
+
+void SlugsPadCameraControl::mouseMoveEvent(QMouseEvent *event)
+{
+ emit mouseMoveCoord(event->x(),event->y());
+
+}
+
+void SlugsPadCameraControl::mousePressEvent(QMouseEvent *event)
+{
+ emit mousePressCoord(event->x(),event->y());
+ x1 = event->x();
+ y1 = event->y();
+
+}
+
+void SlugsPadCameraControl::mouseReleaseEvent(QMouseEvent *event)
+{
+ emit mouseReleaseCoord(event->x(),event->y());
+ getDeltaPositionPad(event->x(), event->y());
+
+}
+
+void SlugsPadCameraControl::paintEvent(QPaintEvent *pe)
+{
+ Q_UNUSED(pe);
+ QPainter painter(this);
+ painter.setPen(Qt::blue);
+ painter.setFont(QFont("Arial", 30));
+
+// QRectF rectangle(tL.x(), tL.y(), ui->padCamContro_frame->width(), ui->padCamContro_frame->height());
+// int startAngle = 30 * 16;
+// int spanAngle = 120 * 16;
+
+ painter.drawLine(QPoint(ui->frame->width()/2,ui->frame->geometry().topLeft().y()),
+ QPoint(ui->frame->width()/2,ui->frame->geometry().bottomRight().y()));
+
+ painter.drawLine(QPoint(ui->frame->geometry().topLeft().x(),ui->frame->height()/2),
+ QPoint(ui->frame->geometry().bottomRight().x(),ui->frame->height()/2));
+
+
+ // painter.drawLine(QPoint());
+ //painter.drawLines(padLines);
+
+
+ // painter.drawPie(rectangle, startAngle, spanAngle);
+
+ //painter.drawText(rect(), Qt::AlignCenter, "Qt");
+}
+
+void SlugsPadCameraControl::getDeltaPositionPad(int x2, int y2)
+{
+
+ QString dir = "nd";
+ QPointF localMeasures = ObtenerMarcacionDistanciaPixel(y1,x1,y2,x2);
+
+ double bearing = localMeasures.x();
+ double dist = getDistPixel(y1,x1,y2,x2);
+
+
+
+ if(((bearing > 330)&&(bearing < 360)) || ((bearing >= 0)&&(bearing <= 30)))
+ {
+ emit dirCursorText("up");
+ //bearing = 315;
+ dir = "up";
+ }
+ else
+ {
+ if((bearing > 30)&&(bearing <= 60) )
+ {
+ emit dirCursorText("right up");
+ //bearing = 315;
+ dir = "riht up";
+ }
+ else
+ {
+ if((bearing > 60)&&(bearing <= 105) )
+ {
+ emit dirCursorText("right");
+ //bearing = 315;
+ dir = "riht";
+ }
+ else
+ {
+ if((bearing > 105)&&(bearing <= 150) )
+ {
+ emit dirCursorText("right down");
+ //bearing = 315;
+ dir = "riht down";
+ }
+ else
+ {
+ if((bearing > 150)&&(bearing <= 195) )
+ {
+ emit dirCursorText("down");
+ //bearing = 315;
+ dir = "down";
+ }
+ else
+ {
+ if((bearing > 195)&&(bearing <= 240) )
+ {
+ emit dirCursorText("left down");
+ //bearing = 315;
+ dir = "left down";
+ }
+ else
+ {
+ if((bearing > 240)&&(bearing <= 300) )
+ {
+ emit dirCursorText("left");
+ //bearing = 315;
+ dir = "left";
+ }
+ else
+ {
+ if((bearing > 300)&&(bearing <= 330) )
+ {
+ emit dirCursorText("left up");
+ //bearing = 315;
+ dir = "left up";
+ }
+
+ }
+
+ }
+
+ }
+
+ }
+
+ }
+
+ }
+
+ }
+
+
+ emit changeCursorPosition(bearing, dist, dir);
+
+}
+
+double SlugsPadCameraControl::getDistPixel(int x1, int y1, int x2, int y2)
+{
+ double cateto_opuesto,cateto_adyacente;
+ //latitud y longitud del primer punto
+
+
+ cateto_opuesto = abs((x1-x2)); //diferencia de latitudes entre PCR1 y PCR2
+ cateto_adyacente = abs((y1-y2));//diferencia de longitudes entre PCR1 y PCR2
+
+ return sqrt(pow(cateto_opuesto,2) + pow(cateto_adyacente,2));
+
+ // distancia = (float) hipotenusa;
+}
+
+/**
+ * Esta función xxxxxxxxx
+ * @param double lat1 -->
+ * @param double lon1 -->
+ * @param double lat2 -->
+ * @param double lon2 -->
+ * @param ref double rumbo -->
+ * @param ref double distancia -->
+ */
+QPointF SlugsPadCameraControl::ObtenerMarcacionDistanciaPixel(double lon1, double lat1, double lon2, double lat2)
+{
+ double cateto_opuesto,cateto_adyacente, hipotenusa, distancia, marcacion;
+
+ //latitude and longitude first point
+
+ if(lat1<0) lat1= lat1*(-1);
+ if(lat2<0) lat2= lat2*(-1);
+ if(lon1<0) lon1= lon1*(-1);
+ if(lon2<0) lon1= lon1*(-1);
+
+ cateto_opuesto = abs((lat1-lat2));
+ cateto_adyacente = abs((lon1-lon2));
+
+ hipotenusa = sqrt(pow(cateto_opuesto,2) + pow(cateto_adyacente,2));
+ distancia = hipotenusa*60;
+
+
+ if ((lat1 < lat2) && (lon1 > lon2)) //primer cuadrante
+ marcacion = 360 -((asin(cateto_adyacente/hipotenusa))/ 0.017453292);
+ else if ((lat1 < lat2) && (lon1 < lon2)) //segundo cuadrante
+ marcacion = (asin(cateto_adyacente/hipotenusa))/ 0.017453292;
+ else if((lat1 > lat2) && (lon1 < lon2)) //tercer cuadrante
+ marcacion = 180 -((asin(cateto_adyacente/hipotenusa))/ 0.017453292);
+ else if((lat1 > lat2) && (lon1 > lon2)) //cuarto cuadrante
+ marcacion = 180 +((asin(cateto_adyacente/hipotenusa))/ 0.017453292);
+ else if((lat1 < lat2) && (lon1 == lon2)) //360
+ marcacion = 360;
+ else if((lat1 == lat2) && (lon1 > lon2)) //270
+ marcacion = 270;
+ else if((lat1 > lat2) && (lon1 == lon2)) //180
+ marcacion = 180;
+ else if((lat1 == lat2) && (lon1 < lon2)) //90
+ marcacion =90;
+ else if((lat1 == lat2) && (lon1 == lon2)) //0
+ marcacion = 0.0;
+
+ // this only convert real bearing to frame widget bearing
+ marcacion = marcacion +90;
+ if(marcacion>= 360) marcacion = marcacion - 360;
+
+ return QPointF(marcacion,distancia);
+
+}
diff --git a/src/ui/SlugsPadCameraControl.h b/src/ui/SlugsPadCameraControl.h
index a9843a387a017df0c7b828f344773c1a92c3964d..06a923328c5c12042a81d197072254fec56df9c4 100644
--- a/src/ui/SlugsPadCameraControl.h
+++ b/src/ui/SlugsPadCameraControl.h
@@ -2,21 +2,46 @@
#define SLUGSPADCAMERACONTROL_H
#include
+#include
namespace Ui {
class SlugsPadCameraControl;
}
-class SlugsPadCameraControl : public QWidget
+class SlugsPadCameraControl : public QWidget //QGraphicsView//
{
Q_OBJECT
public:
explicit SlugsPadCameraControl(QWidget *parent = 0);
+
~SlugsPadCameraControl();
+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);
+
+signals:
+ void mouseMoveCoord(int x, int y);
+ void mousePressCoord(int x, int y);
+ void mouseReleaseCoord(int x, int y);
+ void dirCursorText(QString dir);
+ void distance_Bearing(double dist, double bearing);
+ void changeCursorPosition(double bearing, double distance, QString textDir);
+
+protected:
+ void mousePressEvent(QMouseEvent* event);
+ void mouseReleaseEvent(QMouseEvent* event);
+ void mouseMoveEvent(QMouseEvent* event);
+ void paintEvent(QPaintEvent *pe);
+
private:
Ui::SlugsPadCameraControl *ui;
+ bool dragging;
+ int x1;
+ int y1;
+
};
#endif // SLUGSPADCAMERACONTROL_H
diff --git a/src/ui/SlugsPadCameraControl.ui b/src/ui/SlugsPadCameraControl.ui
index aad00293ca4a65c895fe4485ff2a1713116d95b8..f96e02a006d094f0e8a0fcab16ebfe8506c07bb8 100644
--- a/src/ui/SlugsPadCameraControl.ui
+++ b/src/ui/SlugsPadCameraControl.ui
@@ -6,8 +6,8 @@
0
0
- 400
- 300
+ 183
+ 127
@@ -16,6 +16,36 @@
background-color: rgb(255, 170, 0);
+
+
+ 1
+
+
+ 1
+
+ -
+
+
+
+ 181
+ 125
+
+
+
+ true
+
+
+ background-color: rgba(255, 0, 0,50%);
+
+
+ QFrame::StyledPanel
+
+
+ QFrame::Raised
+
+
+
+
diff --git a/src/ui/SlugsVideoCamControl.cpp b/src/ui/SlugsVideoCamControl.cpp
index 0949c6ac18cf62c33b02f06a7ad53dc751cec653..30ea6cb47dc0be103ae1ac4bb6f580b88c8a3098 100644
--- a/src/ui/SlugsVideoCamControl.cpp
+++ b/src/ui/SlugsVideoCamControl.cpp
@@ -13,33 +13,52 @@
#include
#include
#include
+#include
+#include "SlugsPadCameraControl.h"
SlugsVideoCamControl::SlugsVideoCamControl(QWidget *parent) :
QWidget(parent),
ui(new Ui::SlugsVideoCamControl),
dragging(0)
+
{
ui->setupUi(this);
x1= 0;
y1 = 0;
connect(ui->viewCamBordeatMap_checkBox,SIGNAL(clicked(bool)),this,SLOT(changeViewCamBorderAtMapStatus(bool)));
- tL = ui->padCamContro_frame->frameGeometry().topLeft();
- bR = ui->padCamContro_frame->frameGeometry().bottomRight();
+// tL = ui->padCamContro_frame->frameGeometry().topLeft();
+// bR = ui->padCamContro_frame->frameGeometry().bottomRight();
//ui->padCamContro_frame->setVisible(true);
- // create a layout for camera pad
- QGridLayout* padCameraLayout = new QGridLayout(ui->padCamContro_frame);
- padCameraLayout->setSpacing(2);
- padCameraLayout->setMargin(0);
- padCameraLayout->setAlignment(Qt::AlignTop);
- ui->padCamContro_frame->setLayout(padCameraLayout);
+// // create a layout for camera pad
+// QGridLayout* padCameraLayout = new QGridLayout(this);
+// padCameraLayout->setSpacing(2);
+// padCameraLayout->setMargin(0);
+// padCameraLayout->setAlignment(Qt::AlignTop);
+
+ //ui->padCamContro_frame->setLayout(padCameraLayout);
// create a camera pad widget
- padCamera = new SlugsPadCameraControl();
+ //test = new QPushButton(QIcon(":/images/actions/list-add.svg"), "", this);
+ //test->setMaximumWidth(50);
+ //ui->gridLayout->addWidget(test, 0,0);
+
+ padCamera = new SlugsPadCameraControl(this);
+
+ ui->gridLayout->addWidget(padCamera);
+
+ connect(padCamera,SIGNAL(mouseMoveCoord(int,int)),this,SLOT(mousePadMoveEvent(int,int)));
+ connect(padCamera,SIGNAL(mousePressCoord(int,int)),this,SLOT(mousePadPressEvent(int,int)));
+ connect(padCamera,SIGNAL(mouseReleaseCoord(int,int)),this,SLOT(mousePadReleaseEvent(int,int)));
+ connect(padCamera,SIGNAL(changeCursorPosition(double,double,QString)),this,SLOT(getDeltaPositionPad(double,double,QString)));
- padCameraLayout->addWidget(padCamera);
+ //padCamera->setVisible(true);
+
+
+
+ // padCameraLayout->addWidget(padCamera);
@@ -65,16 +84,7 @@ SlugsVideoCamControl::~SlugsVideoCamControl()
void SlugsVideoCamControl::mouseMoveEvent(QMouseEvent *event)
{
- // ui->label_dir->setText("Camera Pos = " + QString::number(event->x()) + " - " + QString::number(event->y()));
-// QPoint tL = ui->padCamContro_frame->frameGeometry().topLeft();
-// QPoint bR = ui->padCamContro_frame->frameGeometry().bottomRight();
-
-// if (!(event->x() > bR.x() || event->x() < tL.x() ||
-// event->y() > bR.y() || event->y() < tL.y() ) && dragging){
-
-
-// }
-
+ Q_UNUSED(event);
}
@@ -83,291 +93,42 @@ void SlugsVideoCamControl::mousePressEvent(QMouseEvent *evnt)
{
Q_UNUSED(evnt);
- x1 = evnt->x();
- y1 = evnt->y();
-
- dragging = true;
}
void SlugsVideoCamControl::mouseReleaseEvent(QMouseEvent *evnt)
{
Q_UNUSED(evnt);
- dragging = false;
- getDeltaPositionPad(evnt->x(), evnt->y());
-}
-void SlugsVideoCamControl::changeViewCamBorderAtMapStatus(bool status)
-{
- emit viewCamBorderAtMap(status);
}
-void SlugsVideoCamControl::getDeltaPositionPad(int x2, int y2)
-{
- //double dist = getDistPixel(x1,y1,x2,y2);
-
- QString dir = "nd";
- QPointF localMeasures = ObtenerMarcacionDistanciaPixel(y1,x1,y2,x2);
-
- double bearing = localMeasures.x();
- double dist = localMeasures.y();
-
- bearing = bearing +90;
- if(bearing>= 360) bearing = bearing - 360;
-
- if(((bearing > 330)&&(bearing < 360)) || ((bearing >= 0)&&(bearing <= 30)))
- {
- ui->label_dir->setText("up");
- //bearing = 315;
- dir = "up";
- }
- else
- {
- if((bearing > 30)&&(bearing <= 60) )
- {
- ui->label_dir->setText("right up");
- //bearing = 315;
- dir = "riht up";
- }
- else
- {
- if((bearing > 60)&&(bearing <= 105) )
- {
- ui->label_dir->setText("right");
- //bearing = 315;
- dir = "riht";
- }
- else
- {
- if((bearing > 105)&&(bearing <= 150) )
- {
- ui->label_dir->setText("right down");
- //bearing = 315;
- dir = "riht down";
- }
- else
- {
- if((bearing > 150)&&(bearing <= 195) )
- {
- ui->label_dir->setText("down");
- //bearing = 315;
- dir = "down";
- }
- else
- {
- if((bearing > 195)&&(bearing <= 240) )
- {
- ui->label_dir->setText("left down");
- //bearing = 315;
- dir = "left down";
- }
- else
- {
- if((bearing > 240)&&(bearing <= 300) )
- {
- ui->label_dir->setText("left");
- //bearing = 315;
- dir = "left";
- }
- else
- {
- if((bearing > 300)&&(bearing <= 330) )
- {
- ui->label_dir->setText("left up");
- //bearing = 315;
- dir = "left up";
- }
-
- }
-
- }
-
- }
-
- }
-
- }
-
- }
-
- }
-
- ui->label_x->setText("Distancia= " + QString::number(dist) + " - x =" + QString::number(x1) );
- ui->label_y->setText("Bearing= " + QString::number(bearing) + " - y = " + QString::number(y1));
-
-
-
- emit changeCamPosition(20, bearing, dir);
-
-// if((x2label_dir->setText("left Up");
-//// bearing = 315;
-// dir = "left up";
-
-
-// }
-// else
-// {
-// if((x2y1)) // left down
-// {
-// ui->label_dir->setText("left down");
-//// bearing = 225;
-// dir = "left down";
-
-
-// }
-// else
-// {
-// if((x2label_dir->setText("left");
-//// bearing = 270;
-// dir = "left";
-
-// }
-// else
-// {
-// if((x2==x1)&&(y2label_dir->setText("Up");
-//// bearing = 0;
-// dir = "up";
-
-// }
-// else
-// {
-// if((x2==x1)&&(y2>y1)) // down
-// {
-// ui->label_dir->setText("down");
-//// bearing = 180;
-// dir = "down";
-
-// }
-// else
-// {
-// if((x2>x1)&&(y2==y1)) // right
-// {
-// ui->label_dir->setText("right");
-//// bearing = 90;
-// dir = "right";
-
-// }
-// else
-// {
-// if((x2>x1)&&(y2label_dir->setText("right Up");
-//// bearing = 45;
-// dir = "right up";
-
-// }
-// else
-// {
-// if((x2>x1)&&(y2>y1))//right down
-// {
-// ui->label_dir->setText("right down");
-//// bearing = 135;
-// dir = "right down";
-
-// }
-// }
-// }
-// }
-// }
-// }
-// }
-// }
-
+void SlugsVideoCamControl::mousePadMoveEvent(int x, int y)
+{
}
-double SlugsVideoCamControl::getDistPixel(int x1, int y1, int x2, int y2)
+void SlugsVideoCamControl::mousePadPressEvent(int x, int y)
{
- double cateto_opuesto,cateto_adyacente;
- //latitud y longitud del primer punto
+}
- cateto_opuesto = abs((x1-x2)); //diferencia de latitudes entre PCR1 y PCR2
- cateto_adyacente = abs((y1-y2));//diferencia de longitudes entre PCR1 y PCR2
+void SlugsVideoCamControl::mousePadReleaseEvent(int x, int y)
+{
- return sqrt(pow(cateto_opuesto,2) + pow(cateto_adyacente,2));
- // distancia = (float) hipotenusa;
}
-/**
- * Esta función xxxxxxxxx
- * @param double lat1 -->
- * @param double lon1 -->
- * @param double lat2 -->
- * @param double lon2 -->
- * @param ref double rumbo -->
- * @param ref double distancia -->
- */
-QPointF SlugsVideoCamControl::ObtenerMarcacionDistanciaPixel(double lon1, double lat1, double lon2, double lat2)
+void SlugsVideoCamControl::changeViewCamBorderAtMapStatus(bool status)
{
- double cateto_opuesto,cateto_adyacente, hipotenusa, distancia, marcacion;
-
- //latitude and longitude first point
-
- if(lat1<0) lat1= lat1*(-1);
- if(lat2<0) lat2= lat2*(-1);
- if(lon1<0) lon1= lon1*(-1);
- if(lon2<0) lon1= lon1*(-1);
-
- cateto_opuesto = abs((lat1-lat2));
- cateto_adyacente = abs((lon1-lon2));
-
- hipotenusa = sqrt(pow(cateto_opuesto,2) + pow(cateto_adyacente,2));
- distancia = hipotenusa*60;
-
-
- if ((lat1 < lat2) && (lon1 > lon2)) //primer cuadrante
- marcacion = 360 -((asin(cateto_adyacente/hipotenusa))/ 0.017453292);
- else if ((lat1 < lat2) && (lon1 < lon2)) //segundo cuadrante
- marcacion = (asin(cateto_adyacente/hipotenusa))/ 0.017453292;
- else if((lat1 > lat2) && (lon1 < lon2)) //tercer cuadrante
- marcacion = 180 -((asin(cateto_adyacente/hipotenusa))/ 0.017453292);
- else if((lat1 > lat2) && (lon1 > lon2)) //cuarto cuadrante
- marcacion = 180 +((asin(cateto_adyacente/hipotenusa))/ 0.017453292);
- else if((lat1 < lat2) && (lon1 == lon2)) //360
- marcacion = 360;
- else if((lat1 == lat2) && (lon1 > lon2)) //270
- marcacion = 270;
- else if((lat1 > lat2) && (lon1 == lon2)) //180
- marcacion = 180;
- else if((lat1 == lat2) && (lon1 < lon2)) //90
- marcacion =90;
- else if((lat1 == lat2) && (lon1 == lon2)) //0
- marcacion = 0.0;
-
- return QPointF(marcacion,distancia);
-
+ emit viewCamBorderAtMap(status);
}
-void SlugsVideoCamControl::paintEvent(QPaintEvent *pe)
+void SlugsVideoCamControl::getDeltaPositionPad(double bearing, double distance, QString dirText)
{
- Q_UNUSED(pe);
- QPainter painter(this);
- painter.setPen(Qt::blue);
- painter.setFont(QFont("Arial", 30));
+ ui->label_dir->setText(dirText);
+ ui->label_x->setText("Distancia= " + QString::number(distance));
+ ui->label_y->setText("Bearing= " + QString::number(bearing));
-// QRectF rectangle(tL.x(), tL.y(), ui->padCamContro_frame->width(), ui->padCamContro_frame->height());
-// int startAngle = 30 * 16;
-// int spanAngle = 120 * 16;
-
- painter.drawLine(QPoint(tL.x(),tL.y()),QPoint(bR.x(),bR.y()));
- // painter.drawLine(QPoint());
- //painter.drawLines(padLines);
-
-
- // painter.drawPie(rectangle, startAngle, spanAngle);
-
- //painter.drawText(rect(), Qt::AlignCenter, "Qt");
+ emit changeCamPosition(20, bearing, dirText);
}
-
-
-
-
diff --git a/src/ui/SlugsVideoCamControl.h b/src/ui/SlugsVideoCamControl.h
index 793879d22b556cfba6100aebe38eeef3f3c72dbf..2580033a5e1dee3883ea60008707112b6f11f674 100644
--- a/src/ui/SlugsVideoCamControl.h
+++ b/src/ui/SlugsVideoCamControl.h
@@ -7,6 +7,8 @@
#include
#include
#include "SlugsPadCameraControl.h"
+#include
+
#define DELTA 1000
@@ -26,33 +28,29 @@ public:
public slots:
void changeViewCamBorderAtMapStatus(bool status);
- 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);
+ 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);
signals:
void changeCamPosition(double dist, double dir, QString textDir);
void viewCamBorderAtMap(bool status);
protected:
- virtual void mousePressEvent(QMouseEvent* event);
- virtual void mouseReleaseEvent(QMouseEvent* event);
- void mouseMoveEvent(QMouseEvent* event);
- //virtual void paintEvent(QPaintEvent *pe);
- void paintEvent(QPaintEvent *pe);
+ void mousePressEvent(QMouseEvent* event);
+ void mouseReleaseEvent(QMouseEvent* event);
+ void mouseMoveEvent(QMouseEvent* event);
-private:
- Ui::SlugsVideoCamControl *ui;
- bool dragging;
- int x1;
- int y1;
- QPoint tL;
- QPoint bR;
- SlugsPadCameraControl* padCamera;
+private:
+ Ui::SlugsVideoCamControl *ui;
+ SlugsPadCameraControl* padCamera;
};
diff --git a/src/ui/SlugsVideoCamControl.ui b/src/ui/SlugsVideoCamControl.ui
index a94832ac34aae54e649d3edf9863f63b3aca5d33..c89c2e7ef26e6c05ecb9e103c616c02506d1934b 100644
--- a/src/ui/SlugsVideoCamControl.ui
+++ b/src/ui/SlugsVideoCamControl.ui
@@ -24,29 +24,6 @@
-
-
-
-
- 0
- 0
-
-
-
- false
-
-
- background-color: rgba(255, 170, 0,0%);
-
-
-
- QFrame::WinPanel
-
-
- QFrame::Sunken
-
-
-
- -
-
@@ -77,7 +54,7 @@
- -
+
-
-