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
76223522
Commit
76223522
authored
Jul 03, 2010
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Added waypoint visualization
parent
cac8880f
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
60 additions
and
21 deletions
+60
-21
HSIDisplay.cc
src/ui/HSIDisplay.cc
+59
-20
HSIDisplay.h
src/ui/HSIDisplay.h
+1
-1
No files found.
src/ui/HSIDisplay.cc
View file @
76223522
...
...
@@ -36,6 +36,7 @@ This file is part of the PIXHAWK project
#include "HSIDisplay.h"
#include "MG.h"
#include "QGC.h"
#include "Waypoint.h"
#include <QDebug>
...
...
@@ -79,7 +80,7 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
uiYSetCoordinate
(
0.0
f
),
uiZSetCoordinate
(
0.0
f
),
uiYawSet
(
0.0
f
),
metricWidth
(
2
.0
f
),
metricWidth
(
4
.0
f
),
positionLock
(
false
),
attControlEnabled
(
false
),
xyControlEnabled
(
false
),
...
...
@@ -207,9 +208,12 @@ void HSIDisplay::paintDisplay()
drawLine
(
s
.
x
(),
s
.
y
(),
xCenterPos
,
yCenterPos
,
1.5
f
,
QGC
::
colorCyan
,
&
painter
);
}
// Draw waypoints
drawWaypoints
(
painter
);
// Labels on outer part and bottom
//
if (localAvailable > 0)
if
(
localAvailable
>
0
)
{
// Position
QString
str
;
...
...
@@ -628,25 +632,60 @@ void HSIDisplay::drawSetpointXY(float x, float y, float yaw, const QColor &color
void
HSIDisplay
::
drawWaypoints
(
QPainter
&
painter
)
{
QColor
color
=
uas
->
getColor
();
float
x
=
1.1
;
float
y
=
1.1
;
float
radius
=
vwidth
/
20.0
f
;
QPen
pen
(
color
);
pen
.
setWidthF
(
refLineWidthToPen
(
0.4
f
));
pen
.
setColor
(
color
);
painter
.
setPen
(
pen
);
QVector
<
Waypoint
*>
list
=
QVector
<
Waypoint
*>
();
list
.
append
(
new
Waypoint
(
0
,
x
,
y
,
z
,
yaw
,
false
,
false
,
0.5
f
,
2000
));
list
.
append
(
new
Waypoint
(
0
,
x
+
0.1
,
y
+
0.1
,
z
,
yaw
,
true
,
true
,
0.5
f
,
2000
));
QColor
color
;
painter
.
setBrush
(
Qt
::
NoBrush
);
QPointF
in
(
x
,
y
);
// Transform from body to world coordinates
in
=
metricWorldToBody
(
in
);
// Scale from metric to screen reference coordinates
QPointF
p
=
metricBodyToRef
(
in
);
drawCircle
(
p
.
x
(),
p
.
y
(),
radius
,
0.4
f
,
color
,
&
painter
);
radius
*=
0.8
;
drawLine
(
p
.
x
(),
p
.
y
(),
p
.
x
()
+
sin
(
yaw
)
*
radius
,
p
.
y
()
-
cos
(
yaw
)
*
radius
,
refLineWidthToPen
(
0.4
f
),
color
,
&
painter
);
painter
.
setBrush
(
color
);
drawCircle
(
p
.
x
(),
p
.
y
(),
radius
*
0.1
f
,
0.1
f
,
color
,
&
painter
);
QPointF
lastWaypoint
;
for
(
int
i
=
0
;
i
<
list
.
size
();
i
++
)
{
QPointF
in
(
list
.
at
(
i
)
->
getX
(),
list
.
at
(
i
)
->
getY
());
// Transform from world to body coordinates
in
=
metricWorldToBody
(
in
);
// Scale from metric to screen reference coordinates
QPointF
p
=
metricBodyToRef
(
in
);
// Select color based on if this is the current waypoint
if
(
list
.
at
(
i
)
->
getCurrent
())
{
color
=
uas
->
getColor
().
lighter
().
lighter
();
}
else
{
color
=
uas
->
getColor
();
}
// Setup pen
QPen
pen
(
color
);
pen
.
setWidthF
(
refLineWidthToPen
(
0.4
f
));
painter
.
setPen
(
pen
);
// Draw line from last waypoint to this one
if
(
!
lastWaypoint
.
isNull
())
{
drawLine
(
lastWaypoint
.
x
(),
lastWaypoint
.
y
(),
p
.
x
(),
p
.
y
(),
refLineWidthToPen
(
0.4
f
),
color
,
&
painter
);
}
lastWaypoint
=
p
;
//drawCircle(p.x(), p.y(), radius, 0.4f, color, &painter);
float
waypointSize
=
vwidth
/
20.0
f
*
2.0
f
;
QPolygonF
poly
(
4
);
// Top point
poly
.
replace
(
0
,
QPointF
(
p
.
x
(),
p
.
y
()
-
waypointSize
/
2.0
f
));
// Right point
poly
.
replace
(
1
,
QPointF
(
p
.
x
()
+
waypointSize
/
2.0
f
,
p
.
y
()));
// Bottom point
poly
.
replace
(
2
,
QPointF
(
p
.
x
(),
p
.
y
()
+
waypointSize
/
2.0
f
));
poly
.
replace
(
3
,
QPointF
(
p
.
x
()
-
waypointSize
/
2.0
f
,
p
.
y
()));
drawPolygon
(
poly
,
&
painter
);
float
radius
=
(
waypointSize
/
2.0
f
)
*
0.8
*
(
1
/
sqrt
(
2.0
f
));
drawLine
(
p
.
x
(),
p
.
y
(),
p
.
x
()
+
sin
(
yaw
)
*
radius
,
p
.
y
()
-
cos
(
yaw
)
*
radius
,
refLineWidthToPen
(
0.4
f
),
color
,
&
painter
);
painter
.
setBrush
(
color
);
}
}
void
HSIDisplay
::
drawSafetyArea
(
const
QPointF
&
topLeft
,
const
QPointF
&
bottomRight
,
const
QColor
&
color
,
QPainter
&
painter
)
...
...
src/ui/HSIDisplay.h
View file @
76223522
...
...
@@ -99,7 +99,7 @@ protected slots:
void
drawWaypoints
(
QPainter
&
painter
);
/** @brief Draw the limiting safety area */
void
drawSafetyArea
(
const
QPointF
&
topLeft
,
const
QPointF
&
bottomRight
,
const
QColor
&
color
,
QPainter
&
painter
);
/** @brief Receive mouse clicks */
void
mouseDoubleClickEvent
(
QMouseEvent
*
event
);
protected:
...
...
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