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
6f445903
Commit
6f445903
authored
Feb 10, 2011
by
lm
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'experimental' of github.com:pixhawk/qgroundcontrol into experimental
parents
80404c9c
a6ca7c45
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
32 additions
and
44 deletions
+32
-44
QGC.cc
src/QGC.cc
+4
-4
MAVLinkSimulationMAV.cc
src/comm/MAVLinkSimulationMAV.cc
+1
-1
HSIDisplay.cc
src/ui/HSIDisplay.cc
+26
-26
QGCGoogleEarthView.cc
src/ui/map3D/QGCGoogleEarthView.cc
+1
-13
No files found.
src/QGC.cc
View file @
6f445903
...
...
@@ -39,14 +39,14 @@ quint64 groundTimeUsecs()
float
limitAngleToPMPIf
(
float
angle
)
{
while
(
angle
>
(
M_PI
+
FLT_EPSILON
))
while
(
angle
>
(
(
float
)
M_PI
+
FLT_EPSILON
))
{
angle
-=
2
*
M_PI
;
angle
-=
2
.0
f
*
(
float
)
M_PI
;
}
while
(
angle
<=
-
(
M_PI
+
FLT_EPSILON
))
while
(
angle
<=
-
(
(
float
)
M_PI
+
FLT_EPSILON
))
{
angle
+=
2
*
M_PI
;
angle
+=
2
.0
f
*
(
float
)
M_PI
;
}
return
angle
;
...
...
src/comm/MAVLinkSimulationMAV.cc
View file @
6f445903
...
...
@@ -169,7 +169,7 @@ void MAVLinkSimulationMAV::mainloop()
hud
.
groundspeed
=
9
;
hud
.
alt
=
123
;
hud
.
heading
=
90
;
hud
.
climb
=
0.1
;
hud
.
climb
=
0.1
f
;
hud
.
throttle
=
90
;
mavlink_msg_vfr_hud_encode
(
systemid
,
MAV_COMP_ID_IMU
,
&
msg
,
&
hud
);
link
->
sendMAVLinkMessage
(
&
msg
);
...
...
src/ui/HSIDisplay.cc
View file @
6f445903
...
...
@@ -49,30 +49,30 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
HDDisplay
(
NULL
,
"HSI"
,
parent
),
gpsSatellites
(),
satellitesUsed
(
0
),
attXSet
(
0
),
attYSet
(
0
),
attYawSet
(
0
),
altitudeSet
(
1.0
),
posXSet
(
0
),
posYSet
(
0
),
posZSet
(
0
),
attXSet
(
0
.0
f
),
attYSet
(
0
.0
f
),
attYawSet
(
0
.0
f
),
altitudeSet
(
1.0
f
),
posXSet
(
0
.0
f
),
posYSet
(
0
.0
f
),
posZSet
(
0
.0
f
),
attXSaturation
(
0.5
f
),
attYSaturation
(
0.5
f
),
attYawSaturation
(
0.5
f
),
posXSaturation
(
0.05
),
posYSaturation
(
0.05
),
altitudeSaturation
(
1.0
),
lat
(
0
),
lon
(
0
),
alt
(
0
),
posXSaturation
(
0.05
f
),
posYSaturation
(
0.05
f
),
altitudeSaturation
(
1.0
f
),
lat
(
0
.0
f
),
lon
(
0
.0
f
),
alt
(
0
.0
f
),
globalAvailable
(
0
),
x
(
0
),
y
(
0
),
z
(
0
),
vx
(
0
),
vy
(
0
),
vz
(
0
),
speed
(
0
),
x
(
0
.0
f
),
y
(
0
.0
f
),
z
(
0
.0
f
),
vx
(
0
.0
f
),
vy
(
0
.0
f
),
vz
(
0
.0
f
),
speed
(
0
.0
f
),
localAvailable
(
0
),
roll
(
0.0
f
),
pitch
(
0.0
f
),
...
...
@@ -85,7 +85,7 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
uiYSetCoordinate
(
0.0
f
),
uiZSetCoordinate
(
0.0
f
),
uiYawSet
(
0.0
f
),
metricWidth
(
4.0
f
),
metricWidth
(
4.0
),
positionLock
(
false
),
attControlEnabled
(
false
),
xyControlEnabled
(
false
),
...
...
@@ -105,8 +105,8 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
columns
=
1
;
this
->
setAutoFillBackground
(
true
);
vwidth
=
80
;
vheight
=
80
;
vwidth
=
80
.0
f
;
vheight
=
80
.0
f
;
xCenterPos
=
vwidth
/
2.0
f
;
yCenterPos
=
vheight
/
2.0
f
+
topMargin
-
bottomMargin
;
...
...
@@ -797,7 +797,7 @@ void HSIDisplay::drawSetpointXY(float x, float y, float yaw, const QColor &color
// 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
;
radius
*=
0.8
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
);
drawCircle
(
p
.
x
(),
p
.
y
(),
radius
*
0.1
f
,
0.1
f
,
color
,
&
painter
);
...
...
@@ -984,7 +984,7 @@ void HSIDisplay::drawPositionDirection(float xRef, float yRef, float radius, con
const
float
minWidth
=
maxWidth
*
0.3
f
;
float
angle
=
atan2
(
posXSet
,
-
posYSet
);
angle
-=
M_PI
/
2.0
f
;
angle
-=
(
float
)
M_PI
/
2.0
f
;
QPolygonF
p
(
6
);
...
...
@@ -1022,7 +1022,7 @@ void HSIDisplay::drawAttitudeDirection(float xRef, float yRef, float radius, con
const
float
minWidth
=
maxWidth
*
0.3
f
;
float
angle
=
atan2
(
attXSet
,
attYSet
);
angle
-=
M_PI
/
2.0
f
;
angle
-=
(
float
)
M_PI
/
2.0
f
;
radius
*=
sqrt
(
pow
(
attXSet
,
2
)
+
pow
(
attYSet
,
2
))
/
sqrt
(
attXSaturation
+
attYSaturation
);
...
...
src/ui/map3D/QGCGoogleEarthView.cc
View file @
6f445903
...
...
@@ -183,18 +183,6 @@ void QGCGoogleEarthView::updateWaypoint(int uas, Waypoint* wp)
{
javaScript
(
QString
(
"updateWaypoint(%1,%2,%3,%4,%5,%6);"
).
arg
(
uas
).
arg
(
wpindex
).
arg
(
wp
->
getY
()).
arg
(
wp
->
getX
()).
arg
(
wp
->
getZ
()).
arg
(
wp
->
getAction
()));
}
}
else
{
// Check if the index of this waypoint is larger than the global
// waypoint list. This implies that the coordinate frame of this
// waypoint was changed and the list containing only global
// waypoints was shortened. Thus update the whole list
// if (waypointPath->points().count() > UASManager::instance()->getUASForId(uas)->getWaypointManager()->getGlobalFrameCount())
// {
// updateWaypointList(uas);
// }
}
}
...
...
@@ -355,7 +343,7 @@ void QGCGoogleEarthView::initializeGoogleEarth()
#endif
#ifdef _MSC_VER
QAxObject
*
doc
=
webViewWin
->
querySubObject
(
"Document()"
);
IDispatch
*
Disp
;
//
IDispatch* Disp;
IDispatch
*
winDoc
=
NULL
;
//332C4425-26CB-11D0-B483-00C04FD90119 IHTMLDocument2
...
...
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