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
c84b1d0e
Commit
c84b1d0e
authored
Mar 03, 2011
by
Alejandro
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Remove SlugsVideoCamControl and modification of SlugsPadCameraControl
parent
3cc8eb8a
Changes
12
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
12 changed files
with
494 additions
and
663 deletions
+494
-663
qgroundcontrol.pro
qgroundcontrol.pro
+0
-3
MainWindow.cc
src/ui/MainWindow.cc
+26
-22
MainWindow.h
src/ui/MainWindow.h
+1
-1
MapWidget.cc
src/ui/MapWidget.cc
+2
-2
MapWidget.h
src/ui/MapWidget.h
+1
-1
SlugsPadCameraControl.cpp
src/ui/SlugsPadCameraControl.cpp
+201
-275
SlugsPadCameraControl.h
src/ui/SlugsPadCameraControl.h
+68
-60
SlugsPadCameraControl.ui
src/ui/SlugsPadCameraControl.ui
+91
-52
SlugsVideoCamControl.cpp
src/ui/SlugsVideoCamControl.cpp
+95
-95
SlugsVideoCamControl.h
src/ui/SlugsVideoCamControl.h
+0
-78
SlugsVideoCamControl.ui
src/ui/SlugsVideoCamControl.ui
+0
-68
UASControlParameters.cpp
src/ui/uas/UASControlParameters.cpp
+9
-6
No files found.
qgroundcontrol.pro
View file @
c84b1d0e
...
...
@@ -147,7 +147,6 @@ FORMS += src/ui/MainWindow.ui \
src
/
ui
/
SlugsDataSensorView
.
ui
\
src
/
ui
/
SlugsHilSim
.
ui
\
src
/
ui
/
SlugsPIDControl
.
ui
\
src
/
ui
/
SlugsVideoCamControl
.
ui
\
src
/
ui
/
SlugsPadCameraControl
.
ui
\
src
/
ui
/
uas
/
QGCUnconnectedInfoWidget
.
ui
\
src
/
ui
/
designer
/
QGCToolWidget
.
ui
\
...
...
@@ -255,7 +254,6 @@ HEADERS += src/MG.h \
src
/
ui
/
SlugsDataSensorView
.
h
\
src
/
ui
/
SlugsHilSim
.
h
\
src
/
ui
/
SlugsPIDControl
.
h
\
src
/
ui
/
SlugsVideoCamControl
.
h
\
src
/
ui
/
SlugsPadCameraControl
.
h
\
src
/
ui
/
QGCMainWindowAPConfigurator
.
h
\
src
/
comm
/
MAVLinkSwarmSimulationLink
.
h
\
...
...
@@ -383,7 +381,6 @@ SOURCES += src/main.cc \
src
/
ui
/
SlugsDataSensorView
.
cc
\
src
/
ui
/
SlugsHilSim
.
cc
\
src
/
ui
/
SlugsPIDControl
.
cpp
\
src
/
ui
/
SlugsVideoCamControl
.
cpp
\
src
/
ui
/
SlugsPadCameraControl
.
cpp
\
src
/
ui
/
QGCMainWindowAPConfigurator
.
cc
\
src
/
comm
/
MAVLinkSwarmSimulationLink
.
cc
\
...
...
src/ui/MainWindow.cc
View file @
c84b1d0e
...
...
@@ -394,13 +394,7 @@ void MainWindow::buildCommonWidgets()
addToCentralWidgetsMenu
(
dataplotWidget
,
"Logfile Plot"
,
SLOT
(
showCentralWidget
()),
CENTRAL_DATA_PLOT
);
}
if
(
!
controlParameterWidget
)
{
controlParameterWidget
=
new
QDockWidget
(
tr
(
"Control Parameters"
),
this
);
controlParameterWidget
->
setObjectName
(
"UNMANNED_SYSTEM_CONTROL_PARAMETERWIDGET"
);
controlParameterWidget
->
setWidget
(
new
UASControlParameters
(
this
)
);
addToToolsMenu
(
controlParameterWidget
,
tr
(
"Control Parameters"
),
SLOT
(
showToolWidget
(
bool
)),
MENU_UAS_CONTROL_PARAM
,
Qt
::
LeftDockWidgetArea
);
}
}
...
...
@@ -625,14 +619,22 @@ void MainWindow::buildSlugsWidgets()
addToToolsMenu
(
slugsHilSimWidget
,
tr
(
"HIL Sim Configuration"
),
SLOT
(
showToolWidget
(
bool
)),
MENU_SLUGS_HIL
,
Qt
::
LeftDockWidgetArea
);
}
if
(
!
controlParameterWidget
)
{
controlParameterWidget
=
new
QDockWidget
(
tr
(
"Control Parameters"
),
this
);
controlParameterWidget
->
setObjectName
(
"UNMANNED_SYSTEM_CONTROL_PARAMETERWIDGET"
);
controlParameterWidget
->
setWidget
(
new
UASControlParameters
(
this
)
);
addToToolsMenu
(
controlParameterWidget
,
tr
(
"Control Parameters"
),
SLOT
(
showToolWidget
(
bool
)),
MENU_UAS_CONTROL_PARAM
,
Qt
::
LeftDockWidgetArea
);
}
if
(
!
slugsCamControlWidget
)
{
slugsCamControlWidget
=
new
QDockWidget
(
tr
(
"Camera Control"
),
this
);
slugsCamControlWidget
->
setWidget
(
new
SlugsPadCameraControl
(
this
));
slugsCamControlWidget
->
setObjectName
(
"SLUGS_CAM_CONTROL_DOCK_WIDGET"
);
addToToolsMenu
(
slugsCamControlWidget
,
tr
(
"Camera Control"
),
SLOT
(
showToolWidget
(
bool
)),
MENU_SLUGS_CAMERA
,
Qt
::
BottomDockWidgetArea
);
}
// if (!slugsCamControlWidget)
// {
// slugsCamControlWidget = new QDockWidget(tr("Slugs Video Camera Control"), this);
// slugsCamControlWidget->setWidget(new SlugsVideoCamControl(this));
// slugsCamControlWidget->setObjectName("SLUGS_CAM_CONTROL_DOCK_WIDGET");
// addToToolsMenu (slugsCamControlWidget, tr("Camera Control"), SLOT(showToolWidget()), MENU_SLUGS_CAMERA, Qt::BottomDockWidgetArea);
// }
}
...
...
@@ -1024,15 +1026,7 @@ void MainWindow::connectCommonWidgets()
slugsHilSimWidget
->
widget
(),
SLOT
(
activeUasSet
(
UASInterface
*
)));
}
if
(
controlParameterWidget
&&
controlParameterWidget
->
widget
()){
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
controlParameterWidget
->
widget
(),
SLOT
(
activeUasSet
(
UASInterface
*
)));
}
if
(
controlDockWidget
&&
controlParameterWidget
)
{
connect
(
controlDockWidget
->
widget
(),
SIGNAL
(
changedMode
(
int
)),
controlParameterWidget
->
widget
(),
SLOT
(
changedMode
(
int
)));
}
}
void
MainWindow
::
createCustomWidget
()
...
...
@@ -1080,7 +1074,15 @@ void MainWindow::connectSlugsWidgets()
slugsPIDControlWidget
->
widget
(),
SLOT
(
activeUasSet
(
UASInterface
*
)));
}
if
(
controlParameterWidget
&&
controlParameterWidget
->
widget
()){
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
controlParameterWidget
->
widget
(),
SLOT
(
activeUasSet
(
UASInterface
*
)));
}
if
(
controlDockWidget
&&
controlParameterWidget
)
{
connect
(
controlDockWidget
->
widget
(),
SIGNAL
(
changedMode
(
int
)),
controlParameterWidget
->
widget
(),
SLOT
(
changedMode
(
int
)));
}
}
void
MainWindow
::
arrangeCommonCenterStack
()
...
...
@@ -1935,6 +1937,8 @@ void MainWindow::presentView()
// UAS CONTROL
showTheWidget
(
MENU_UAS_CONTROL
,
currentView
);
showTheWidget
(
MENU_UAS_CONTROL_PARAM
,
currentView
);
// UAS LIST
showTheWidget
(
MENU_UAS_LIST
,
currentView
);
...
...
src/ui/MainWindow.h
View file @
c84b1d0e
...
...
@@ -74,7 +74,7 @@ This file is part of the QGROUNDCONTROL project
#include "SlugsHilSim.h"
#include "Slugs
VideoCam
Control.h"
#include "Slugs
PadCamera
Control.h"
#include "UASControlParameters.h"
/**
...
...
src/ui/MapWidget.cc
View file @
c84b1d0e
...
...
@@ -233,8 +233,8 @@ void MapWidget::init()
//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
);
//
camLayer = new qmapcontrol::GeometryLayer("Camera", mapadapter);
//
mc->addLayer(camLayer);
//camLine = new qmapcontrol::LineString(camPoints,"Camera Eje", camBorderPen);
...
...
src/ui/MapWidget.h
View file @
c84b1d0e
...
...
@@ -131,7 +131,7 @@ protected:
qmapcontrol
::
GeometryLayer
*
geomLayer
;
///< Layer for waypoints
qmapcontrol
::
GeometryLayer
*
homePosition
;
///< Layer for station control
//only for experiment
qmapcontrol
::
GeometryLayer
*
camLayer
;
///< Layer for camera indicator
//
qmapcontrol::GeometryLayer* camLayer; ///< Layer for camera indicator
int
zoomLevel
;
int
detailZoom
;
///< Steps zoomed in further than qMapControl allows
...
...
src/ui/SlugsPadCameraControl.cpp
View file @
c84b1d0e
This diff is collapsed.
Click to expand it.
src/ui/SlugsPadCameraControl.h
View file @
c84b1d0e
#ifndef SLUGSPADCAMERACONTROL_H
#define SLUGSPADCAMERACONTROL_H
#include <QWidget>
#include <QGraphicsView>
namespace
Ui
{
class
SlugsPadCameraControl
;
}
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
);
QPointF
getPointBy_BearingDistance
(
double
lat1
,
double
lon1
,
double
rumbo
,
double
distancia
);
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
;
int
xFin
;
int
yFin
;
double
bearingPad
;
double
distancePad
;
QString
directionPad
;
};
#endif // SLUGSPADCAMERACONTROL_H
#ifndef SLUGSPADCAMERACONTROL_H
#define SLUGSPADCAMERACONTROL_H
#include <QtGui/QWidget>
#include <QGraphicsView>
#include <QMouseEvent>
#include <QKeyEvent>
#include <QDebug>
#include <qmath.h>
#include <QPainter>
#include "UASManager.h"
namespace
Ui
{
class
SlugsPadCameraControl
;
}
class
SlugsPadCameraControl
:
public
QWidget
//QGraphicsView//
{
Q_OBJECT
public:
explicit
SlugsPadCameraControl
(
QWidget
*
parent
=
0
);
~
SlugsPadCameraControl
();
enum
MotionCamera
{
UP
,
DOWN
,
LEFT
,
RIGHT
,
RIGHT_UP
,
RIGHT_DOWN
,
LEFT_UP
,
LEFT_DOWN
,
NONE
};
public
slots
:
void
getDeltaPositionPad
(
int
x
,
int
y
);
QPointF
ObtenerMarcacionDistanciaPixel
(
double
lon1
,
double
lat1
,
double
lon2
,
double
lat2
);
void
activeUasSet
(
UASInterface
*
uas
);
signals:
void
changeMotionCamera
(
MotionCamera
);
protected:
void
mousePressEvent
(
QMouseEvent
*
event
);
void
mouseReleaseEvent
(
QMouseEvent
*
event
);
void
mouseMoveEvent
(
QMouseEvent
*
event
);
void
keyPressEvent
(
QKeyEvent
*
event
);
//void paintEvent(QPaintEvent *pe);
private:
Ui
::
SlugsPadCameraControl
*
ui
;
bool
dragging
;
int
x1
;
int
y1
;
int
xFin
;
int
yFin
;
QString
directionPad
;
MotionCamera
motion
;
UASInterface
*
activeUAS
;
QPoint
movePad
;
};
#endif // SLUGSPADCAMERACONTROL_H
src/ui/SlugsPadCameraControl.ui
View file @
c84b1d0e
<?xml version="1.0" encoding="UTF-8"?>
<ui
version=
"4.0"
>
<class>
SlugsPadCameraControl
</class>
<widget
class=
"QWidget"
name=
"SlugsPadCameraControl"
>
<property
name=
"geometry"
>
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
183
</width>
<height>
127
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<property
name=
"styleSheet"
>
<string
notr=
"true"
>
background-color: rgb(255, 170, 0);
</string>
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout"
>
<property
name=
"margin"
>
<number>
1
</number>
</property>
<property
name=
"spacing"
>
<number>
1
</number>
</property>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QFrame"
name=
"frame"
>
<property
name=
"minimumSize"
>
<size>
<width>
181
</width>
<height>
125
</height>
</size>
</property>
<property
name=
"mouseTracking"
>
<bool>
true
</bool>
</property>
<property
name=
"styleSheet"
>
<string
notr=
"true"
>
background-color: rgba(255, 0, 0,50%);
</string>
</property>
<property
name=
"frameShape"
>
<enum>
QFrame::StyledPanel
</enum>
</property>
<property
name=
"frameShadow"
>
<enum>
QFrame::Raised
</enum>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
<?xml version="1.0" encoding="UTF-8"?>
<ui
version=
"4.0"
>
<class>
SlugsPadCameraControl
</class>
<widget
class=
"QWidget"
name=
"SlugsPadCameraControl"
>
<property
name=
"geometry"
>
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
200
</width>
<height>
200
</height>
</rect>
</property>
<property
name=
"minimumSize"
>
<size>
<width>
200
</width>
<height>
200
</height>
</size>
</property>
<property
name=
"windowTitle"
>
<string>
Form
</string>
</property>
<property
name=
"styleSheet"
>
<string
notr=
"true"
>
background-color: rgb(255, 170, 0);
</string>
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout"
>
<property
name=
"margin"
>
<number>
1
</number>
</property>
<property
name=
"spacing"
>
<number>
1
</number>
</property>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QFrame"
name=
"frame"
>
<property
name=
"minimumSize"
>
<size>
<width>
200
</width>
<height>
200
</height>
</size>
</property>
<property
name=
"mouseTracking"
>
<bool>
true
</bool>
</property>
<property
name=
"styleSheet"
>
<string
notr=
"true"
>
background-color: rgba(255, 0, 0,50%);
</string>
</property>
<property
name=
"frameShape"
>
<enum>
QFrame::StyledPanel
</enum>
</property>
<property
name=
"frameShadow"
>
<enum>
QFrame::Raised
</enum>
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout_2"
>
<item
row=
"0"
column=
"0"
>
<spacer
name=
"verticalSpacer"
>
<property
name=
"orientation"
>
<enum>
Qt::Vertical
</enum>
</property>
<property
name=
"sizeHint"
stdset=
"0"
>
<size>
<width>
20
</width>
<height>
156
</height>
</size>
</property>
</spacer>
</item>
<item
row=
"1"
column=
"0"
>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
>
<item>
<widget
class=
"QLabel"
name=
"lbPixel"
>
<property
name=
"text"
>
<string>
----
</string>
</property>
</widget>
</item>
<item>
<widget
class=
"QLabel"
name=
"lbDirection"
>
<property
name=
"text"
>
<string>
----
</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
src/ui/SlugsVideoCamControl.cpp
View file @
c84b1d0e
#include "SlugsVideoCamControl.h"
#include "ui_SlugsVideoCamControl.h"
#include <QGraphicsScene>
#include <QGraphicsTextItem>
#include <QTextStream>
#include <QScrollBar>
#include <QMouseEvent>
#include <QWheelEvent>
#include <QDebug>
#include <qmath.h>
#include <QPainter>
#include <QGridLayout>
#include <QVBoxLayout>
#include <QHBoxLayout>
#include <QPushButton>
#include "SlugsPadCameraControl.h"
SlugsVideoCamControl
::
SlugsVideoCamControl
(
QWidget
*
parent
)
:
QWidget
(
parent
),
ui
(
new
Ui
::
SlugsVideoCamControl
)
{
ui
->
setupUi
(
this
);
// x1= 0;
// y1 = 0;
connect
(
ui
->
viewCamBordeatMap_checkBox
,
SIGNAL
(
clicked
(
bool
)),
this
,
SLOT
(
changeViewCamBorderAtMapStatus
(
bool
)));
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
)));
}
SlugsVideoCamControl
::~
SlugsVideoCamControl
()
{
delete
ui
;
}
//void SlugsVideoCamControl::mouseMoveEvent(QMouseEvent *event)
//{
// Q_UNUSED(event);
//}
//void SlugsVideoCamControl::mousePressEvent(QMouseEvent *evnt)
//{
// Q_UNUSED(evnt);
//}
//void SlugsVideoCamControl::mouseReleaseEvent(QMouseEvent *evnt)
//{
// Q_UNUSED(evnt);
//}
//void SlugsVideoCamControl::mousePadMoveEvent(int x, int y)
//{
//}
//void SlugsVideoCamControl::mousePadPressEvent(int x, int y)
//{
//}
//void SlugsVideoCamControl::mousePadReleaseEvent(int x, int y)
//{
//}
void
SlugsVideoCamControl
::
changeViewCamBorderAtMapStatus
(
bool
status
)
{
emit
viewCamBorderAtMap
(
status
);
}
void
SlugsVideoCamControl
::
getDeltaPositionPad
(
double
bearing
,
double
distance
,
QString
dirText
)
{
ui
->
label_dir
->
setText
(
dirText
);
ui
->
label_x
->
setText
(
"Distancia= "
+
QString
::
number
(
distance
));
ui
->
label_y
->
setText
(
"Bearing= "
+
QString
::
number
(
bearing
));
emit
changeCamPosition
(
20
,
bearing
,
dirText
);
}
#include "SlugsVideoCamControl.h"
#include "ui_SlugsVideoCamControl.h"
#include <QGraphicsScene>
#include <QGraphicsTextItem>
#include <QTextStream>
#include <QScrollBar>
#include <QMouseEvent>
#include <QWheelEvent>
#include <QDebug>
#include <qmath.h>
#include <QPainter>
#include <QGridLayout>
#include <QVBoxLayout>
#include <QHBoxLayout>
#include <QPushButton>
#include "SlugsPadCameraControl.h"
SlugsVideoCamControl
::
SlugsVideoCamControl
(
QWidget
*
parent
)
:
QWidget
(
parent
),
ui
(
new
Ui
::
SlugsVideoCamControl
)
{
ui
->
setupUi
(
this
);
// x1= 0;
// y1 = 0;
connect
(
ui
->
viewCamBordeatMap_checkBox
,
SIGNAL
(
clicked
(
bool
)),
this
,
SLOT
(
changeViewCamBorderAtMapStatus
(
bool
)));
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)));
}
SlugsVideoCamControl
::~
SlugsVideoCamControl
()
{
delete
ui
;
}
//void SlugsVideoCamControl::mouseMoveEvent(QMouseEvent *event)
//{
// Q_UNUSED(event);
//}
//void SlugsVideoCamControl::mousePressEvent(QMouseEvent *evnt)
//{
// Q_UNUSED(evnt);
//}
//void SlugsVideoCamControl::mouseReleaseEvent(QMouseEvent *evnt)
//{
// Q_UNUSED(evnt);
//}
//void SlugsVideoCamControl::mousePadMoveEvent(int x, int y)
//{
//}
//void SlugsVideoCamControl::mousePadPressEvent(int x, int y)
//{
//}
//void SlugsVideoCamControl::mousePadReleaseEvent(int x, int y)
//{
//}
void
SlugsVideoCamControl
::
changeViewCamBorderAtMapStatus
(
bool
status
)
{
emit
viewCamBorderAtMap
(
status
);
}
void
SlugsVideoCamControl
::
getDeltaPositionPad
(
double
bearing
,
double
distance
,
QString
dirText
)
{
ui
->
label_dir
->
setText
(
dirText
);
ui
->
label_x
->
setText
(
"Distancia= "
+
QString
::
number
(
distance
));
ui
->
label_y
->
setText
(
"Bearing= "
+
QString
::
number
(
bearing
));
//emit changeCamPosition(20, bearing, dirText);
}
src/ui/SlugsVideoCamControl.h
deleted
100644 → 0
View file @
3cc8eb8a
#ifndef SLUGSVIDEOCAMCONTROL_H
#define SLUGSVIDEOCAMCONTROL_H
#include <QWidget>
#include <QMouseEvent>
#include <QGraphicsView>
#include <QGraphicsSceneMouseEvent>
#include <QGraphicsScene>
#include "SlugsPadCameraControl.h"
#include <QPushButton>
#define DELTA 1000
namespace
Ui
{
class
SlugsVideoCamControl
;
}
class
SlugsVideoCamControl
:
public
QWidget
{
Q_OBJECT
public:
explicit
SlugsVideoCamControl
(
QWidget
*
parent
=
0
);
~
SlugsVideoCamControl
();
public
slots
:
/**
* @brief status = true: emit signal to draw a border cam over the map
*/
void
changeViewCamBorderAtMapStatus
(
bool
status
);
/**
* @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:
/**
* @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);
private:
Ui
::
SlugsVideoCamControl
*
ui
;
SlugsPadCameraControl
*
padCamera
;
};
#endif // SLUGSVIDEOCAMCONTROL_H
src/ui/SlugsVideoCamControl.ui
deleted
100644 → 0
View file @
3cc8eb8a
<?xml version="1.0" encoding="UTF-8"?>
<ui
version=
"4.0"
>
<class>
SlugsVideoCamControl
</class>
<widget
class=
"QWidget"
name=
"SlugsVideoCamControl"
>
<property
name=
"geometry"
>
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
165
</width>
<height>
191
</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"
>
<item>
<layout
class=
"QGridLayout"
name=
"gridLayout"
>
<item
row=
"0"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_x"
>
<property
name=
"mouseTracking"
>
<bool>
true
</bool>
</property>
<property
name=
"text"
>
<string>
Coord_X
</string>
</property>
</widget>
</item>
<item
row=
"0"
column=
"1"
>
<widget
class=
"QLabel"
name=
"label_y"
>
<property
name=
"mouseTracking"
>
<bool>
true
</bool>
</property>
<property
name=
"text"
>
<string>
Coord_Y
</string>
</property>
</widget>
</item>
<item
row=
"1"
column=
"1"
>
<widget
class=
"QCheckBox"
name=
"viewCamBordeatMap_checkBox"
>
<property
name=
"text"
>
<string>
Camera at Map
</string>
</property>
</widget>
</item>
<item
row=
"1"
column=
"0"
>
<widget
class=
"QLabel"
name=
"label_dir"
>
<property
name=
"text"
>
<string>
Camera Pos
</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
src/ui/uas/UASControlParameters.cpp
View file @
c84b1d0e
...
...
@@ -90,13 +90,16 @@ void UASControlParameters::changedMode(int mode)
void
UASControlParameters
::
activeUasSet
(
UASInterface
*
uas
)
{
connect
(
uas
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateGlobalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateAttitude
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
modeChanged
(
int
,
QString
,
QString
)),
this
,
SLOT
(
updateMode
(
int
,
QString
,
QString
)));
connect
(
uas
,
SIGNAL
(
thrustChanged
(
UASInterface
*
,
double
)),
this
,
SLOT
(
thrustChanged
(
UASInterface
*
,
double
))
);
if
(
uas
)
{
connect
(
uas
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateGlobalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
speedChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateAttitude
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
modeChanged
(
int
,
QString
,
QString
)),
this
,
SLOT
(
updateMode
(
int
,
QString
,
QString
)));
connect
(
uas
,
SIGNAL
(
thrustChanged
(
UASInterface
*
,
double
)),
this
,
SLOT
(
thrustChanged
(
UASInterface
*
,
double
))
);
activeUAS
=
uas
;
activeUAS
=
uas
;
}
}
void
UASControlParameters
::
updateGlobalPosition
(
UASInterface
*
a
,
double
b
,
double
c
,
double
aa
,
quint64
ab
)
...
...
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