Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
f22025af
Commit
f22025af
authored
Dec 03, 2010
by
Mariano Lizarraga
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'experimental' of
git://github.com/tecnosapiens/qgroundcontrol
into experimental
parents
414a947c
f8a90520
Changes
13
Hide whitespace changes
Inline
Side-by-side
Showing
13 changed files
with
593 additions
and
36 deletions
+593
-36
qgroundcontrol.pro
qgroundcontrol.pro
+6
-3
UASWaypointManager.cc
src/uas/UASWaypointManager.cc
+7
-0
UASWaypointManager.h
src/uas/UASWaypointManager.h
+1
-0
MainWindow.cc
src/ui/MainWindow.cc
+5
-1
MapWidget.cc
src/ui/MapWidget.cc
+89
-1
MapWidget.h
src/ui/MapWidget.h
+21
-0
SlugsPIDControl.cpp
src/ui/SlugsPIDControl.cpp
+6
-6
SlugsPIDControl.ui
src/ui/SlugsPIDControl.ui
+46
-0
SlugsVideoCamControl.cpp
src/ui/SlugsVideoCamControl.cpp
+315
-11
SlugsVideoCamControl.h
src/ui/SlugsVideoCamControl.h
+26
-0
SlugsVideoCamControl.ui
src/ui/SlugsVideoCamControl.ui
+49
-12
WaypointList.cc
src/ui/WaypointList.cc
+20
-2
WaypointList.h
src/ui/WaypointList.h
+2
-0
No files found.
qgroundcontrol.pro
View file @
f22025af
...
...
@@ -140,7 +140,8 @@ FORMS += src/ui/MainWindow.ui \
src
/
ui
/
SlugsDataSensorView
.
ui
\
src
/
ui
/
SlugsHilSim
.
ui
\
src
/
ui
/
SlugsPIDControl
.
ui
\
src
/
ui
/
SlugsVideoCamControl
.
ui
src
/
ui
/
SlugsVideoCamControl
.
ui
\
src
/
ui
/
SlugsPadCameraControl
.
ui
INCLUDEPATH
+=
src
\
src
/
ui
\
src
/
ui
/
linechart
\
...
...
@@ -243,7 +244,8 @@ HEADERS += src/MG.h \
src
/
ui
/
SlugsDataSensorView
.
h
\
src
/
ui
/
SlugsHilSim
.
h
\
src
/
ui
/
SlugsPIDControl
.
h
\
src
/
ui
/
SlugsVideoCamControl
.
h
src
/
ui
/
SlugsVideoCamControl
.
h
\
src
/
ui
/
SlugsPadCameraControl
.
h
SOURCES
+=
src
/
main
.
cc
\
src
/
Core
.
cc
\
src
/
uas
/
UASManager
.
cc
\
...
...
@@ -326,7 +328,8 @@ SOURCES += src/main.cc \
src
/
ui
/
SlugsDataSensorView
.
cc
\
src
/
ui
/
SlugsHilSim
.
cc
\
src
/
ui
/
SlugsPIDControl
.
cpp
\
src
/
ui
/
SlugsVideoCamControl
.
cpp
src
/
ui
/
SlugsVideoCamControl
.
cpp
\
src
/
ui
/
SlugsPadCameraControl
.
cpp
RESOURCES
=
mavground
.
qrc
...
...
src/uas/UASWaypointManager.cc
View file @
f22025af
...
...
@@ -153,6 +153,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
current_partner_compid
=
0
;
protocol_timer
.
stop
();
emit
readGlobalWPFromUAS
(
false
);
emit
updateStatusString
(
"done."
);
qDebug
()
<<
"got all waypoints from ID "
<<
systemId
;
...
...
@@ -294,6 +295,7 @@ void UASWaypointManager::localAddWaypoint(Waypoint *wp)
{
wp
->
setId
(
waypoints
.
size
());
waypoints
.
insert
(
waypoints
.
size
(),
wp
);
emit
waypointListChanged
();
}
}
...
...
@@ -417,6 +419,7 @@ void UASWaypointManager::clearWaypointList()
void
UASWaypointManager
::
readWaypoints
()
{
emit
readGlobalWPFromUAS
(
true
);
if
(
current_state
==
WP_IDLE
)
{
while
(
waypoints
.
size
()
>
0
)
...
...
@@ -424,6 +427,7 @@ void UASWaypointManager::readWaypoints()
Waypoint
*
t
=
waypoints
.
back
();
delete
t
;
waypoints
.
pop_back
();
}
protocol_timer
.
start
(
PROTOCOL_TIMEOUT_MS
);
...
...
@@ -435,6 +439,7 @@ void UASWaypointManager::readWaypoints()
current_partner_compid
=
MAV_COMP_ID_WAYPOINTPLANNER
;
sendWaypointRequestList
();
}
}
...
...
@@ -569,6 +574,8 @@ void UASWaypointManager::sendWaypointRequestList()
MG
::
SLEEP
::
usleep
(
PROTOCOL_DELAY_MS
*
1000
);
qDebug
()
<<
"sent waypoint list request to ID "
<<
wprl
.
target_system
;
}
void
UASWaypointManager
::
sendWaypointRequest
(
quint16
seq
)
...
...
src/uas/UASWaypointManager.h
View file @
f22025af
...
...
@@ -122,6 +122,7 @@ signals:
void
updateStatusString
(
const
QString
&
);
///< emits the current status string
void
loadWPFile
();
///< emits signal that a file wp has been load
void
readGlobalWPFromUAS
(
bool
value
);
///< emits signal when finish to read Global WP from UAS
private:
UAS
&
uas
;
///< Reference to the corresponding UAS
...
...
src/ui/MainWindow.cc
View file @
f22025af
...
...
@@ -225,6 +225,9 @@ void MainWindow::connectWidgets()
connect
(
waypointsDockWidget
->
widget
(),
SIGNAL
(
createWaypointAtMap
(
QPointF
)),
mapWidget
,
SLOT
(
createWaypointGraphAtMap
(
QPointF
)));
// it notifies that a waypoint global change it¥s position by spinBox on Widget WaypointView
connect
(
waypointsDockWidget
->
widget
(),
SIGNAL
(
changePositionWPGlobalBySpinBox
(
int
,
float
,
float
)),
mapWidget
,
SLOT
(
changeGlobalWaypointPositionBySpinBox
(
int
,
float
,
float
)));
connect
(
slugsCamControlWidget
->
widget
(),
SIGNAL
(
viewCamBorderAtMap
(
bool
)),
mapWidget
,
SLOT
(
drawBorderCamAtMap
(
bool
)));
connect
(
slugsCamControlWidget
->
widget
(),
SIGNAL
(
changeCamPosition
(
double
,
double
,
QString
)),
mapWidget
,
SLOT
(
updateCameraPosition
(
double
,
double
,
QString
)));
}
if
(
slugsHilSimWidget
&&
slugsHilSimWidget
->
widget
()){
...
...
@@ -570,7 +573,8 @@ void MainWindow::UASCreated(UASInterface* uas)
SlugsMAV
*
mav2
=
dynamic_cast
<
SlugsMAV
*>
(
uas
);
if
(
mav2
)
{
dataWidget
->
addUAS
(
uas
);
loadSlugsView
();
//loadSlugsView();
loadGlobalOperatorView
();
}
}
}
...
...
src/ui/MapWidget.cc
View file @
f22025af
...
...
@@ -33,6 +33,7 @@ This file is part of the QGROUNDCONTROL project
#include <QComboBox>
#include <QGridLayout>
#include "MapWidget.h"
#include "ui_MapWidget.h"
#include "UASInterface.h"
...
...
@@ -42,6 +43,7 @@ This file is part of the QGROUNDCONTROL project
#include "MG.h"
MapWidget
::
MapWidget
(
QWidget
*
parent
)
:
QWidget
(
parent
),
zoomLevel
(
0
),
...
...
@@ -84,6 +86,8 @@ MapWidget::MapWidget(QWidget *parent) :
geomLayer
=
new
qmapcontrol
::
GeometryLayer
(
"Waypoints"
,
mapadapter
);
mc
->
addLayer
(
geomLayer
);
//
// Layer* gsatLayer = new Layer("Google Satellite", gsat, Layer::MapLayer);
// mc->addLayer(gsatLayer);
...
...
@@ -218,6 +222,19 @@ MapWidget::MapWidget(QWidget *parent) :
path
=
new
qmapcontrol
::
LineString
(
wps
,
"UAV Path"
,
pointPen
);
mc
->
layer
(
"Waypoints"
)
->
addGeometry
(
path
);
//Camera Control
// CAMERA INDICATOR LAYER
// create a layer with the mapadapter and type GeometryLayer (for camera indicator)
camLayer
=
new
qmapcontrol
::
GeometryLayer
(
"Camera"
,
mapadapter
);
mc
->
addLayer
(
camLayer
);
//camLine = new qmapcontrol::LineString(camPoints,"Camera Eje", camBorderPen);
drawCamBorder
=
false
;
radioCamera
=
10
;
this
->
setVisible
(
false
);
}
...
...
@@ -393,6 +410,7 @@ void MapWidget::createWaypointGraphAtMap(const QPointF coordinate)
// Create waypoint name
QString
str
;
str
=
QString
(
"%1"
).
arg
(
path
->
numberOfPoints
());
// create the WP and set everything in the LineString to display the path
...
...
@@ -414,8 +432,9 @@ void MapWidget::createWaypointGraphAtMap(const QPointF coordinate)
path
->
addPoint
(
tempPoint
);
wpIndex
.
insert
(
str
,
tempPoint
);
qDebug
()
<<
"Funcion createWaypointGraphAtMap WP= "
<<
str
<<
" -> x= "
<<
tempPoint
->
latitude
()
<<
" y= "
<<
tempPoint
->
longitude
();
// Refresh the screen
// Refresh the screen
mc
->
updateRequestNew
();
//// // emit signal mouse was clicked
...
...
@@ -602,6 +621,10 @@ void MapWidget::wheelEvent(QWheelEvent *event)
// Detail zoom level is the number of steps zoomed in further
// after the bounding has taken effect
detailZoom
=
qAbs
(
qMin
(
0
,
mc
->
currentZoom
()
-
newZoom
));
// visual field of camera
updateCameraPosition
(
20
*
newZoom
,
0
,
"no"
);
}
void
MapWidget
::
keyPressEvent
(
QKeyEvent
*
event
)
...
...
@@ -691,3 +714,68 @@ void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, floa
}
void
MapWidget
::
updateCameraPosition
(
double
radio
,
double
bearing
,
QString
dir
)
{
//camPoints.clear();
QPointF
currentPos
=
mc
->
currentCoordinate
();
// QPointF actualPos = getPointxBearing_Range(currentPos.y(),currentPos.x(),bearing,distance);
// qmapcontrol::Point* tempPoint1 = new qmapcontrol::Point(currentPos.x(), currentPos.y(),"inicial",qmapcontrol::Point::Middle);
// qmapcontrol::Point* tempPoint2 = new qmapcontrol::Point(actualPos.x(), actualPos.y(),"final",qmapcontrol::Point::Middle);
// camPoints.append(tempPoint1);
// camPoints.append(tempPoint2);
// camLine->setPoints(camPoints);
QPen
*
camBorderPen
=
new
QPen
(
QColor
(
255
,
0
,
0
));
camBorderPen
->
setWidth
(
2
);
//radio = mc->currentZoom()
if
(
drawCamBorder
)
{
//clear camera borders
mc
->
layer
(
"Camera"
)
->
clearGeometries
();
//create a camera borders
qmapcontrol
::
CirclePoint
*
camBorder
=
new
qmapcontrol
::
CirclePoint
(
currentPos
.
x
(),
currentPos
.
y
(),
radio
,
"camBorder"
,
qmapcontrol
::
Point
::
Middle
,
camBorderPen
);
//camBorder->setCoordinate(currentPos);
mc
->
layer
(
"Camera"
)
->
addGeometry
(
camBorder
);
// mc->layer("Camera")->addGeometry(camLine);
mc
->
updateRequestNew
();
}
else
{
//clear camera borders
mc
->
layer
(
"Camera"
)
->
clearGeometries
();
mc
->
updateRequestNew
();
}
}
void
MapWidget
::
drawBorderCamAtMap
(
bool
status
)
{
drawCamBorder
=
status
;
updateCameraPosition
(
20
,
0
,
"no"
);
}
QPointF
MapWidget
::
getPointxBearing_Range
(
double
lat1
,
double
lon1
,
double
bearing
,
double
distance
)
{
QPointF
temp
;
double
rad
=
M_PI
/
180
;
bearing
=
bearing
*
rad
;
temp
.
setX
((
lon1
+
((
distance
/
60
)
*
(
sin
(
bearing
)))));
temp
.
setY
((
lat1
+
((
distance
/
60
)
*
(
cos
(
bearing
)))));
return
temp
;
}
src/ui/MapWidget.h
View file @
f22025af
...
...
@@ -37,6 +37,11 @@ This file is part of the QGROUNDCONTROL project
#include <QMap>
#include "qmapcontrol.h"
#include "UASInterface.h"
#include "QPointF"
#include <qmath.h>
class
QMenu
;
...
...
@@ -63,10 +68,13 @@ public slots:
void
activeUASSet
(
UASInterface
*
uas
);
void
updateGlobalPosition
(
UASInterface
*
uas
,
double
lat
,
double
lon
,
double
alt
,
quint64
usec
);
void
updatePosition
(
float
time
,
double
lat
,
double
lon
);
void
updateCameraPosition
(
double
distance
,
double
bearing
,
QString
dir
);
QPointF
getPointxBearing_Range
(
double
lat1
,
double
lon1
,
double
bearing
,
double
distance
);
//ROCA
void
clearPath
();
void
changeGlobalWaypointPositionBySpinBox
(
int
index
,
float
lat
,
float
lon
);
void
drawBorderCamAtMap
(
bool
status
);
protected:
void
changeEvent
(
QEvent
*
e
);
...
...
@@ -93,6 +101,10 @@ protected:
qmapcontrol
::
Layer
*
l
;
///< Current map layer (background)
qmapcontrol
::
Layer
*
overlay
;
///< Street overlay (foreground)
qmapcontrol
::
GeometryLayer
*
geomLayer
;
///< Layer for waypoints
//only for experiment
qmapcontrol
::
GeometryLayer
*
camLayer
;
///< Layer for camera indicator
int
zoomLevel
;
int
detailZoom
;
///< Steps zoomed in further than qMapControl allows
static
const
int
scrollStep
=
40
;
///< Scroll n pixels per keypress
...
...
@@ -132,7 +144,16 @@ private:
QHash
<
QString
,
qmapcontrol
::
Point
*>
wpIndex
;
qmapcontrol
::
LineString
*
path
;
QPen
*
pointPen
;
bool
waypointIsDrag
;
qmapcontrol
::
LineString
*
camLine
;
QList
<
qmapcontrol
::
Point
*>
camPoints
;
QPointF
lastCamBorderPos
;
bool
drawCamBorder
;
int
radioCamera
;
};
#endif // MAPWIDGET_H
src/ui/SlugsPIDControl.cpp
View file @
f22025af
...
...
@@ -489,32 +489,32 @@ void SlugsPIDControl::receivePidValues(int systemId, const mavlink_pid_t &pidVal
qDebug
()
<<
"
\n
ACTUALIZANDO GUI = "
<<
pidValues
.
idx
;
switch
(
pidValues
.
idx
)
{
case
1
:
case
0
:
ui
->
dT_P_get
->
setText
(
QString
::
number
(
pidValues
.
pVal
));
ui
->
dT_I_get
->
setText
(
QString
::
number
(
pidValues
.
iVal
));
ui
->
dT_D_get
->
setText
(
QString
::
number
(
pidValues
.
dVal
));
break
;
case
2
:
case
1
:
ui
->
HELPComm_P_get
->
setText
(
QString
::
number
(
pidValues
.
pVal
));
ui
->
HELPComm_I_get
->
setText
(
QString
::
number
(
pidValues
.
iVal
));
ui
->
HELPComm_FF_get
->
setText
(
QString
::
number
(
pidValues
.
dVal
));
break
;
case
3
:
case
2
:
ui
->
dE_P_get
->
setText
(
QString
::
number
(
pidValues
.
pVal
));
ui
->
dE_I_get
->
setText
(
QString
::
number
(
pidValues
.
iVal
));
ui
->
dE_D_get
->
setText
(
QString
::
number
(
pidValues
.
dVal
));
break
;
case
4
:
case
3
:
ui
->
dR_P_get
->
setText
(
QString
::
number
(
pidValues
.
pVal
));
ui
->
dR_I_get
->
setText
(
QString
::
number
(
pidValues
.
iVal
));
ui
->
dR_D_get
->
setText
(
QString
::
number
(
pidValues
.
dVal
));
break
;
case
5
:
case
4
:
ui
->
dA_P_get
->
setText
(
QString
::
number
(
pidValues
.
pVal
));
ui
->
dA_I_get
->
setText
(
QString
::
number
(
pidValues
.
iVal
));
ui
->
dA_D_get
->
setText
(
QString
::
number
(
pidValues
.
dVal
));
break
;
case
9
:
case
8
:
ui
->
P2dT_FF_get
->
setText
(
QString
::
number
(
pidValues
.
pVal
));
break
;
...
...
src/ui/SlugsPIDControl.ui
View file @
f22025af
...
...
@@ -977,6 +977,52 @@
</item>
</layout>
</widget>
<tabstops>
<tabstop>
dT_P_set
</tabstop>
<tabstop>
dT_I_set
</tabstop>
<tabstop>
dT_D_set
</tabstop>
<tabstop>
dT_PID_set_pushButton
</tabstop>
<tabstop>
dT_PID_get_pushButton
</tabstop>
<tabstop>
HELPComm_P_set
</tabstop>
<tabstop>
HELPComm_I_set
</tabstop>
<tabstop>
HELPComm_FF_set
</tabstop>
<tabstop>
HELPComm_PDI_set_pushButton
</tabstop>
<tabstop>
HELPComm_PDI_get_pushButton
</tabstop>
<tabstop>
dE_P_set
</tabstop>
<tabstop>
dE_I_set
</tabstop>
<tabstop>
dE_D_set
</tabstop>
<tabstop>
dE_PID_set_pushButton
</tabstop>
<tabstop>
dE_PID_get_pushButton
</tabstop>
<tabstop>
dR_P_set
</tabstop>
<tabstop>
dR_I_set
</tabstop>
<tabstop>
dR_D_set
</tabstop>
<tabstop>
dR_PDI_set_pushButton
</tabstop>
<tabstop>
dR_PDI_get_pushButton
</tabstop>
<tabstop>
dA_P_set
</tabstop>
<tabstop>
dA_I_set
</tabstop>
<tabstop>
dA_D_set
</tabstop>
<tabstop>
dA_PID_set_pushButton
</tabstop>
<tabstop>
dA_PID_get_pushButton
</tabstop>
<tabstop>
P2dT_FF_set
</tabstop>
<tabstop>
Pitch2dT_PDI_set_pushButton
</tabstop>
<tabstop>
Pitch2dT_PDI_get_pushButton
</tabstop>
<tabstop>
dT_P_get
</tabstop>
<tabstop>
dT_I_get
</tabstop>
<tabstop>
dT_D_get
</tabstop>
<tabstop>
HELPComm_P_get
</tabstop>
<tabstop>
HELPComm_I_get
</tabstop>
<tabstop>
HELPComm_FF_get
</tabstop>
<tabstop>
dE_P_get
</tabstop>
<tabstop>
dE_I_get
</tabstop>
<tabstop>
dE_D_get
</tabstop>
<tabstop>
dR_P_get
</tabstop>
<tabstop>
dR_I_get
</tabstop>
<tabstop>
dR_D_get
</tabstop>
<tabstop>
dA_P_get
</tabstop>
<tabstop>
dA_I_get
</tabstop>
<tabstop>
dA_D_get
</tabstop>
<tabstop>
P2dT_FF_get
</tabstop>
</tabstops>
<resources/>
<connections/>
</ui>
src/ui/SlugsVideoCamControl.cpp
View file @
f22025af
...
...
@@ -8,6 +8,11 @@
#include <QMouseEvent>
#include <QWheelEvent>
#include <QDebug>
#include <qmath.h>
#include <QPainter>
#include <QGridLayout>
#include <QVBoxLayout>
#include <QHBoxLayout>
SlugsVideoCamControl
::
SlugsVideoCamControl
(
QWidget
*
parent
)
:
...
...
@@ -16,6 +21,27 @@ SlugsVideoCamControl::SlugsVideoCamControl(QWidget *parent) :
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
();
//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 camera pad widget
padCamera
=
new
SlugsPadCameraControl
();
padCameraLayout
->
addWidget
(
padCamera
);
// QGraphicsScene *scene = new QGraphicsScene(ui->CamControlPanel_graphicsView);
// scene->setItemIndexMethod(QGraphicsScene::NoIndex);
...
...
@@ -39,14 +65,16 @@ SlugsVideoCamControl::~SlugsVideoCamControl()
void
SlugsVideoCamControl
::
mouseMoveEvent
(
QMouseEvent
*
event
)
{
QPoint
tL
=
ui
->
widget
->
frameGeometry
().
topLeft
();
QPoint
bR
=
ui
->
widget
->
frameGeometry
().
bottomRight
();
// 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){
// }
if
(
!
(
event
->
x
()
>
bR
.
x
()
||
event
->
x
()
<
tL
.
x
()
||
event
->
y
()
>
bR
.
y
()
||
event
->
y
()
<
tL
.
y
()
)
&&
dragging
){
ui
->
label_x
->
setText
(
QString
::
number
(
event
->
x
()));
ui
->
label_y
->
setText
(
QString
::
number
(
event
->
y
()));
}
}
...
...
@@ -55,15 +83,291 @@ void SlugsVideoCamControl::mousePressEvent(QMouseEvent *evnt)
{
Q_UNUSED
(
evnt
);
x1
=
evnt
->
x
();
y1
=
evnt
->
y
();
dragging
=
true
;
}
void
SlugsVideoCamControl
::
mouseReleaseEvent
(
QMouseEvent
*
evnt
)
{
dragging
=
false
;
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((x2<x1)&&(y2<y1)) // left up
// {
// ui->label_dir->setText("left Up");
//// bearing = 315;
// dir = "left up";
// }
// else
// {
// if((x2<x1)&&(y2>y1)) // left down
// {
// ui->label_dir->setText("left down");
//// bearing = 225;
// dir = "left down";
// }
// else
// {
// if((x2<x1)&&(y2==y1))// left
// {
// ui->label_dir->setText("left");
//// bearing = 270;
// dir = "left";
// }
// else
// {
// if((x2==x1)&&(y2<y1)) // up
// {
// ui->label_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)&&(y2<y1))// right up
// {
// ui->label_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";
// }
// }
// }
// }
// }
// }
// }
// }
}
double
SlugsVideoCamControl
::
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;
}
//void SlugsVideoCamControl::mouseDoubleClickEvent(QMouseEvent *evnt)
//{
/**
* Esta funcin 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
)
{
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
);
}
void
SlugsVideoCamControl
::
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
(
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");
}
//}
src/ui/SlugsVideoCamControl.h
View file @
f22025af
...
...
@@ -6,6 +6,10 @@
#include <QGraphicsView>
#include <QGraphicsSceneMouseEvent>
#include <QGraphicsScene>
#include "SlugsPadCameraControl.h"
#define DELTA 1000
namespace
Ui
{
class
SlugsVideoCamControl
;
...
...
@@ -20,14 +24,36 @@ public:
explicit
SlugsVideoCamControl
(
QWidget
*
parent
=
0
);
~
SlugsVideoCamControl
();
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
);
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
);
private:
Ui
::
SlugsVideoCamControl
*
ui
;
bool
dragging
;
int
x1
;
int
y1
;
QPoint
tL
;
QPoint
bR
;
SlugsPadCameraControl
*
padCamera
;
};
#endif // SLUGSVIDEOCAMCONTROL_H
src/ui/SlugsVideoCamControl.ui
View file @
f22025af
...
...
@@ -6,46 +6,83 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
443
</width>
<height>
35
1
</height>
<width>
165
</width>
<height>
19
1
</height>
</rect>
</property>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
0
</height>
</size>
</property>
<property
name=
"mouseTracking"
>
<bool>
true
</bool>
</property>
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout_2"
>
<item>
<widget
class=
"QWidget"
name=
"widget"
native=
"true"
>
<layout
class=
"QGridLayout"
name=
"gridLayout"
>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QFrame"
name=
"padCamContro_frame"
>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
0
</height>
</size>
</property>
<property
name=
"mouseTracking"
>
<bool>
tru
e
</bool>
<bool>
fals
e
</bool>
</property>
<property
name=
"styleSheet"
>
<string
notr=
"true"
>
background-color: rgb(255, 193, 76);
</string>
<string
notr=
"true"
>
background-color: rgba(255, 170, 0,0%);
</string>
</property>
<property
name=
"frameShape"
>
<enum>
QFrame::WinPanel
</enum>
</property>
<property
name=
"frameShadow"
>
<enum>
QFrame::Sunken
</enum>
</property>
</widget>
</item>
<item>
<item
row=
"1"
column=
"0"
>
<layout
class=
"QVBoxLayout"
name=
"verticalLayout"
>
<item>
<widget
class=
"QLabel"
name=
"label_
y
"
>
<widget
class=
"QLabel"
name=
"label_
x
"
>
<property
name=
"mouseTracking"
>
<bool>
true
</bool>
</property>
<property
name=
"text"
>
<string>
TextLabel
</string>
<string>
Coord_X
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_
x
"
>
<widget
class=
"QLabel"
name=
"label_
y
"
>
<property
name=
"mouseTracking"
>
<bool>
true
</bool>
</property>
<property
name=
"text"
>
<string>
TextLabel
</string>
<string>
Coord_Y
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"label_dir"
>
<property
name=
"text"
>
<string>
Camera Pos
</string>
</property>
</widget>
</item>
</layout>
</item>
<item
row=
"2"
column=
"0"
>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
>
<item>
<widget
class=
"QCheckBox"
name=
"viewCamBordeatMap_checkBox"
>
<property
name=
"text"
>
<string>
Camera at Map
</string>
</property>
</widget>
</item>
...
...
src/ui/WaypointList.cc
View file @
f22025af
...
...
@@ -92,6 +92,7 @@ WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
isGlobalWP
=
false
;
isLocalWP
=
false
;
loadFileGlobalWP
=
false
;
readGlobalWP
=
false
;
centerMapCoordinate
.
setX
(
0.0
);
centerMapCoordinate
.
setY
(
0.0
);
...
...
@@ -133,6 +134,8 @@ void WaypointList::setUAS(UASInterface* uas)
connect
(
&
uas
->
getWaypointManager
(),
SIGNAL
(
waypointListChanged
(
void
)),
this
,
SLOT
(
waypointListChanged
(
void
)));
connect
(
&
uas
->
getWaypointManager
(),
SIGNAL
(
currentWaypointChanged
(
quint16
)),
this
,
SLOT
(
currentWaypointChanged
(
quint16
)));
connect
(
&
uas
->
getWaypointManager
(),
SIGNAL
(
loadWPFile
()),
this
,
SLOT
(
setIsLoadFileWP
()));
connect
(
&
uas
->
getWaypointManager
(),
SIGNAL
(
readGlobalWPFromUAS
(
bool
)),
this
,
SLOT
(
setIsReadGlobalWP
(
bool
)));
}
}
...
...
@@ -250,6 +253,8 @@ void WaypointList::addCurrentPositonWaypoint()
void
WaypointList
::
updateStatusLabel
(
const
QString
&
string
)
{
m_ui
->
statusLabel
->
setText
(
string
);
}
void
WaypointList
::
changeCurrentWaypoint
(
quint16
seq
)
...
...
@@ -341,7 +346,7 @@ void WaypointList::waypointListChanged()
WaypointGlobalView
*
wpgv
=
wpGlobalViews
.
value
(
wp
);
wpgv
->
updateValues
();
listLayout
->
addWidget
(
wpgv
);
if
(
loadFileGlobalWP
)
if
(
loadFileGlobalWP
||
readGlobalWP
)
{
emit
createWaypointAtMap
(
QPointF
(
wp
->
getX
(),
wp
->
getY
()));
qDebug
()
<<
"Emitiendo Pos: "
<<
wp
->
getX
()
<<
" - "
<<
wp
->
getY
();
...
...
@@ -475,11 +480,12 @@ void WaypointList::changeEvent(QEvent *e)
void
WaypointList
::
on_clearWPListButton_clicked
()
{
if
(
uas
)
{
if
(
isGlobalWP
)
{
emit
clearPathclicked
();
emit
clearPathclicked
();
const
QVector
<
Waypoint
*>
&
waypoints
=
uas
->
getWaypointManager
().
getWaypointList
();
while
(
!
waypoints
.
isEmpty
())
//for(int i = 0; i <= waypoints.size(); i++)
...
...
@@ -516,6 +522,13 @@ void WaypointList::on_clearWPListButton_clicked()
}
}
else
{
if
(
isGlobalWP
)
{
emit
clearPathclicked
();
}
}
}
/** @brief Add a waypoint by mouse click over the map */
...
...
@@ -638,3 +651,8 @@ void WaypointList::setIsLoadFileWP()
{
loadFileGlobalWP
=
true
;
}
void
WaypointList
::
setIsReadGlobalWP
(
bool
value
)
{
readGlobalWP
=
value
;
}
src/ui/WaypointList.h
View file @
f22025af
...
...
@@ -103,6 +103,7 @@ public slots:
void
removeWaypoint
(
Waypoint
*
wp
);
void
setIsLoadFileWP
();
void
setIsReadGlobalWP
(
bool
value
);
...
...
@@ -131,6 +132,7 @@ protected:
bool
isLocalWP
;
QPointF
centerMapCoordinate
;
bool
loadFileGlobalWP
;
bool
readGlobalWP
;
private:
Ui
::
WaypointList
*
m_ui
;
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment