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
84dfb69d
Commit
84dfb69d
authored
Dec 09, 2010
by
Mariano Lizarraga
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'dev' of
git://github.com/tecnosapiens/qgroundcontrol
into dev
parents
c3ebb999
20319cba
Changes
8
Hide whitespace changes
Inline
Side-by-side
Showing
8 changed files
with
136 additions
and
93 deletions
+136
-93
SlugsPIDControl.cpp
src/ui/SlugsPIDControl.cpp
+5
-3
SlugsPIDControl.h
src/ui/SlugsPIDControl.h
+2
-2
SlugsPIDControl.ui
src/ui/SlugsPIDControl.ui
+7
-7
SlugsPadCameraControl.cpp
src/ui/SlugsPadCameraControl.cpp
+57
-7
SlugsPadCameraControl.h
src/ui/SlugsPadCameraControl.h
+9
-0
SlugsVideoCamControl.cpp
src/ui/SlugsVideoCamControl.cpp
+22
-61
SlugsVideoCamControl.h
src/ui/SlugsVideoCamControl.h
+31
-10
WaypointList.cc
src/ui/WaypointList.cc
+3
-3
No files found.
src/ui/SlugsPIDControl.cpp
View file @
84dfb69d
...
...
@@ -55,6 +55,7 @@ void SlugsPIDControl::activeUasSet(UASInterface* uas)
connect
(
slugsMav
,
SIGNAL
(
slugsPidValues
(
int
,
mavlink_pid_t
)),
this
,
SLOT
(
receivePidValues
(
int
,
mavlink_pid_t
))
);
connect
(
ui
->
setGeneral_pushButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
slugsTimerStartSet
()));
connect
(
ui
->
getGeneral_pushButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
slugsTimerStartGet
()));
}
#endif // MAVLINK_ENABLED_SLUG
...
...
@@ -462,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
;
...
...
@@ -531,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:
...
...
src/ui/SlugsPIDControl.h
View file @
84dfb69d
...
...
@@ -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
src/ui/SlugsPIDControl.ui
View file @
84dfb69d
...
...
@@ -121,13 +121,6 @@
</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"
>
...
...
@@ -956,6 +949,13 @@
</item>
</layout>
</item>
<item>
<widget
class=
"QLabel"
name=
"recepcion_label"
>
<property
name=
"text"
>
<string>
Recepcion
</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
...
...
src/ui/SlugsPadCameraControl.cpp
View file @
84dfb69d
...
...
@@ -13,6 +13,9 @@ SlugsPadCameraControl::SlugsPadCameraControl(QWidget *parent) :
ui
->
setupUi
(
this
);
x1
=
0
;
y1
=
0
;
bearingPad
=
0
;
distancePad
=
0
;
directionPad
=
"no"
;
}
...
...
@@ -23,13 +26,25 @@ SlugsPadCameraControl::~SlugsPadCameraControl()
void
SlugsPadCameraControl
::
mouseMoveEvent
(
QMouseEvent
*
event
)
{
emit
mouseMoveCoord
(
event
->
x
(),
event
->
y
());
//emit mouseMoveCoord(event->x(),event->y());
if
(
dragging
)
{
if
(
abs
(
x1
-
event
->
x
())
>
20
||
abs
(
y1
-
event
->
y
())
>
20
)
{
getDeltaPositionPad
(
event
->
x
(),
event
->
y
());
x1
=
event
->
x
();
y1
=
event
->
y
();
}
}
}
void
SlugsPadCameraControl
::
mousePressEvent
(
QMouseEvent
*
event
)
{
emit
mousePressCoord
(
event
->
x
(),
event
->
y
());
//emit mousePressCoord(event->x(),event->y());
dragging
=
true
;
x1
=
event
->
x
();
y1
=
event
->
y
();
...
...
@@ -37,8 +52,13 @@ void SlugsPadCameraControl::mousePressEvent(QMouseEvent *event)
void
SlugsPadCameraControl
::
mouseReleaseEvent
(
QMouseEvent
*
event
)
{
emit
mouseReleaseCoord
(
event
->
x
(),
event
->
y
());
getDeltaPositionPad
(
event
->
x
(),
event
->
y
());
dragging
=
false
;
//emit mouseReleaseCoord(event->x(),event->y());
//getDeltaPositionPad(event->x(), event->y());
xFin
=
event
->
x
();
yFin
=
event
->
y
();
}
...
...
@@ -59,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);
...
...
@@ -92,7 +119,7 @@ void SlugsPadCameraControl::getDeltaPositionPad(int x2, int y2)
{
emit
dirCursorText
(
"right up"
);
//bearing = 315;
dir
=
"riht up"
;
dir
=
"ri
g
ht up"
;
}
else
{
...
...
@@ -100,7 +127,7 @@ void SlugsPadCameraControl::getDeltaPositionPad(int x2, int y2)
{
emit
dirCursorText
(
"right"
);
//bearing = 315;
dir
=
"riht"
;
dir
=
"ri
g
ht"
;
}
else
{
...
...
@@ -108,7 +135,7 @@ void SlugsPadCameraControl::getDeltaPositionPad(int x2, int y2)
{
emit
dirCursorText
(
"right down"
);
//bearing = 315;
dir
=
"riht down"
;
dir
=
"ri
g
ht down"
;
}
else
{
...
...
@@ -158,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
)
...
...
@@ -229,3 +263,19 @@ QPointF SlugsPadCameraControl::ObtenerMarcacionDistanciaPixel(double lon1, doubl
return
QPointF
(
marcacion
,
distancia
);
}
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
);
}
src/ui/SlugsPadCameraControl.h
View file @
84dfb69d
...
...
@@ -21,6 +21,9 @@ 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
);
...
...
@@ -36,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
;
};
...
...
src/ui/SlugsVideoCamControl.cpp
View file @
84dfb69d
...
...
@@ -20,29 +20,12 @@
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();
//ui->padCamContro_frame->setVisible(true);
// // 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
//test = new QPushButton(QIcon(":/images/actions/list-add.svg"), "", this);
//test->setMaximumWidth(50);
//ui->gridLayout->addWidget(test, 0,0);
connect
(
ui
->
viewCamBordeatMap_checkBox
,
SIGNAL
(
clicked
(
bool
)),
this
,
SLOT
(
changeViewCamBorderAtMapStatus
(
bool
)));
padCamera
=
new
SlugsPadCameraControl
(
this
);
ui
->
gridLayout
->
addWidget
(
padCamera
);
...
...
@@ -53,28 +36,6 @@ SlugsVideoCamControl::SlugsVideoCamControl(QWidget *parent) :
connect
(
padCamera
,
SIGNAL
(
changeCursorPosition
(
double
,
double
,
QString
)),
this
,
SLOT
(
getDeltaPositionPad
(
double
,
double
,
QString
)));
//padCamera->setVisible(true);
// padCameraLayout->addWidget(padCamera);
// QGraphicsScene *scene = new QGraphicsScene(ui->CamControlPanel_graphicsView);
// scene->setItemIndexMethod(QGraphicsScene::NoIndex);
// scene->setSceneRect(-200, -200, 400, 400);
// setScene(scene);
// setCacheMode(CacheBackground);
// setViewportUpdateMode(BoundingRectViewportUpdate);
// setRenderHint(QPainter::Antialiasing);
// setTransformationAnchor(AnchorUnderMouse);
// setResizeAnchor(AnchorViewCenter);
// ui->CamControlPanel_graphicsView->installEventFilter(this);
// ui->label_x->installEventFilter(this);
}
SlugsVideoCamControl
::~
SlugsVideoCamControl
()
...
...
@@ -82,41 +43,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
)
{
...
...
src/ui/SlugsVideoCamControl.h
View file @
84dfb69d
...
...
@@ -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);
...
...
src/ui/WaypointList.cc
View file @
84dfb69d
...
...
@@ -153,7 +153,7 @@ void WaypointList::loadWaypoints()
QString
fileName
=
QFileDialog
::
getOpenFileName
(
this
,
tr
(
"Load File"
),
"."
,
tr
(
"Waypoint File (*.txt)"
));
uas
->
getWaypointManager
().
loadWaypoints
(
fileName
);
}
}
}
void
WaypointList
::
transmit
()
...
...
@@ -474,14 +474,14 @@ void WaypointList::on_clearWPListButton_clicked()
if
(
uas
)
{
emit
clearPathclicked
();
emit
clearPathclicked
();
const
QVector
<
Waypoint
*>
&
waypoints
=
uas
->
getWaypointManager
().
getWaypointList
();
while
(
!
waypoints
.
isEmpty
())
//for(int i = 0; i <= waypoints.size(); i++)
{
WaypointView
*
widget
=
wpViews
.
find
(
waypoints
[
0
]).
value
();
widget
->
remove
();
}
}
}
else
{
// if(isGlobalWP)
...
...
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