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
25e35803
Commit
25e35803
authored
Jan 03, 2012
by
oberion
Committed by
LM
Jan 11, 2012
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fixed windows build bug and div. compile warnings
parent
ce0bd4d2
Changes
10
Hide whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
24 additions
and
9 deletions
+24
-9
QGC.cc
src/QGC.cc
+1
-1
QGC.h
src/QGC.h
+1
-1
MAVLinkSimulationMAV.cc
src/comm/MAVLinkSimulationMAV.cc
+4
-4
UASWaypointManager.cc
src/uas/UASWaypointManager.cc
+4
-0
HSIDisplay.cc
src/ui/HSIDisplay.cc
+5
-0
QGCMAVLinkInspector.cc
src/ui/QGCMAVLinkInspector.cc
+3
-0
QGCMAVLinkInspector.h
src/ui/QGCMAVLinkInspector.h
+2
-2
QGCRGBDView.cc
src/ui/QGCRGBDView.cc
+2
-0
QGCMapWidget.cc
src/ui/map/QGCMapWidget.cc
+1
-1
UASListWidget.cc
src/ui/uas/UASListWidget.cc
+1
-0
No files found.
src/QGC.cc
View file @
25e35803
...
...
@@ -64,7 +64,7 @@ float limitAngleToPMPIf(float angle)
else
{
// Approximate
angle
=
fmodf
(
angle
,
M_PI
);
angle
=
fmodf
(
angle
,
(
float
)
M_PI
);
}
return
angle
;
...
...
src/QGC.h
View file @
25e35803
...
...
@@ -47,7 +47,7 @@ inline bool isnan(T value)
template
<
typename
T
>
inline
bool
isinf
(
T
value
)
{
return
std
::
numeric_limits
<
T
>::
has_infinity
&&
(
value
==
std
::
numeric_limits
<
T
>::
infinity
()
||
(
-
1
*
value
)
==
std
::
numeric_limits
<
T
>::
infinity
())
;
return
(
value
==
std
::
numeric_limits
<
T
>::
infinity
()
||
(
-
1
*
value
)
==
std
::
numeric_limits
<
T
>::
infinity
())
&&
std
::
numeric_limits
<
T
>::
has_infinity
;
}
#else
#include <cmath>
...
...
src/comm/MAVLinkSimulationMAV.cc
View file @
25e35803
...
...
@@ -221,10 +221,10 @@ void MAVLinkSimulationMAV::mainloop()
if
(
sys_mode
&
MAV_MODE_FLAG_DECODE_POSITION_HIL
)
{
mavlink_hil_controls_t
hil
;
hil
.
roll_ailerons
=
0.0
;
hil
.
pitch_elevator
=
0.05
;
hil
.
yaw_rudder
=
0.05
;
hil
.
throttle
=
0.6
;
hil
.
roll_ailerons
=
0.0
f
;
hil
.
pitch_elevator
=
0.05
f
;
hil
.
yaw_rudder
=
0.05
f
;
hil
.
throttle
=
0.6
f
;
// Encode the data (adding header and checksums, etc.)
mavlink_msg_hil_controls_encode
(
systemid
,
MAV_COMP_ID_IMU
,
&
ret
,
&
hil
);
// And send it
...
...
src/uas/UASWaypointManager.cc
View file @
25e35803
...
...
@@ -114,6 +114,9 @@ void UASWaypointManager::handleGlobalPositionChanged(UASInterface* mav, double l
{
Q_UNUSED
(
mav
);
Q_UNUSED
(
time
);
Q_UNUSED
(
alt
);
Q_UNUSED
(
lon
);
Q_UNUSED
(
lat
);
if
(
waypointsEditable
.
count
()
>
0
&&
currentWaypointEditable
&&
(
currentWaypointEditable
->
getFrame
()
==
MAV_FRAME_GLOBAL
||
currentWaypointEditable
->
getFrame
()
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
))
{
// TODO FIXME Calculate distance
...
...
@@ -239,6 +242,7 @@ void UASWaypointManager::handleWaypointRequest(quint8 systemId, quint8 compId, m
void
UASWaypointManager
::
handleWaypointReached
(
quint8
systemId
,
quint8
compId
,
mavlink_mission_item_reached_t
*
wpr
)
{
Q_UNUSED
(
compId
);
if
(
!
uas
)
return
;
if
(
systemId
==
uasid
)
{
emit
updateStatusString
(
QString
(
"Reached waypoint %1"
).
arg
(
wpr
->
seq
));
...
...
src/ui/HSIDisplay.cc
View file @
25e35803
...
...
@@ -486,6 +486,11 @@ void HSIDisplay::updatePositionZControllerEnabled(bool enabled)
void
HSIDisplay
::
updateObjectPosition
(
unsigned
int
time
,
int
id
,
int
type
,
const
QString
&
name
,
int
quality
,
float
bearing
,
float
distance
)
{
Q_UNUSED
(
quality
);
Q_UNUSED
(
name
);
Q_UNUSED
(
type
);
Q_UNUSED
(
id
);
Q_UNUSED
(
time
);
// FIXME add multi-object support
QPainter
painter
(
this
);
QColor
color
(
Qt
::
yellow
);
...
...
src/ui/QGCMAVLinkInspector.cc
View file @
25e35803
...
...
@@ -6,6 +6,9 @@
#include <QDebug>
const
float
QGCMAVLinkInspector
::
updateHzLowpass
=
0.2
f
;
const
unsigned
int
QGCMAVLinkInspector
::
updateInterval
=
1000U
;
QGCMAVLinkInspector
::
QGCMAVLinkInspector
(
MAVLinkProtocol
*
protocol
,
QWidget
*
parent
)
:
QWidget
(
parent
),
ui
(
new
Ui
::
QGCMAVLinkInspector
)
...
...
src/ui/QGCMAVLinkInspector.h
View file @
25e35803
...
...
@@ -37,8 +37,8 @@ protected:
// Update one message field
void
updateField
(
int
msgid
,
int
fieldid
,
QTreeWidgetItem
*
item
);
static
const
unsigned
int
updateInterval
=
1000
;
static
const
float
updateHzLowpass
=
0
.
2
f
;
static
const
unsigned
int
updateInterval
;
static
const
float
updateHzLowpass
;
private:
Ui
::
QGCMAVLinkInspector
*
ui
;
...
...
src/ui/QGCRGBDView.cc
View file @
25e35803
...
...
@@ -265,5 +265,7 @@ void QGCRGBDView::updateData(UASInterface *uas)
}
glImage
=
QGLWidget
::
convertToGLFormat
(
fill
);
#else
Q_UNUSED
(
uas
);
#endif
}
src/ui/map/QGCMapWidget.cc
View file @
25e35803
...
...
@@ -10,7 +10,7 @@ QGCMapWidget::QGCMapWidget(QWidget *parent) :
mapcontrol
::
OPMapWidget
(
parent
),
currWPManager
(
NULL
),
firingWaypointChange
(
NULL
),
maxUpdateInterval
(
2.1
),
// 2 seconds
maxUpdateInterval
(
2.1
f
),
// 2 seconds
followUAVEnabled
(
false
),
trailType
(
mapcontrol
::
UAVTrailType
::
ByTimeElapsed
),
trailInterval
(
2.0
f
),
...
...
src/ui/uas/UASListWidget.cc
View file @
25e35803
...
...
@@ -114,6 +114,7 @@ void UASListWidget::activeUAS(UASInterface* uas)
void
UASListWidget
::
removeUAS
(
UASInterface
*
uas
)
{
Q_UNUSED
(
uas
);
// uasViews.remove(uas);
// listLayout->removeWidget(uasViews.value(uas));
// uasViews.value(uas)->deleteLater();
...
...
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