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
db719606
Commit
db719606
authored
Feb 17, 2014
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Plain Diff
Merge branch 'master' of github.com:mavlink/qgroundcontrol
parents
4e81ee8c
906c3f21
Changes
15
Hide whitespace changes
Inline
Side-by-side
Showing
15 changed files
with
144 additions
and
42 deletions
+144
-42
QGCExternalLibs.pri
QGCExternalLibs.pri
+0
-20
lks94projection.cpp
...pmapcontrol/src/internals/projections/lks94projection.cpp
+10
-0
mercatorprojectionyandex.cpp
...ol/src/internals/projections/mercatorprojectionyandex.cpp
+15
-0
qwt_plot_spectrogram.cpp
libs/qwt/qwt_plot_spectrogram.cpp
+13
-0
qwt_plot_zoomer.h
libs/qwt/qwt_plot_zoomer.h
+11
-0
qserialport.pri
libs/serialport/qserialport.pri
+1
-1
qgroundcontrol.pro
qgroundcontrol.pro
+10
-3
MAVLinkProtocol.cc
src/comm/MAVLinkProtocol.cc
+1
-9
MockUAS.h
src/qgcunittest/MockUAS.h
+3
-0
UAS.cc
src/uas/UAS.cc
+27
-1
UAS.h
src/uas/UAS.h
+3
-0
UASInterface.h
src/uas/UASInterface.h
+8
-1
UASWaypointManager.cc
src/uas/UASWaypointManager.cc
+27
-4
WaypointList.cc
src/ui/WaypointList.cc
+3
-3
Q3DWidget.h
src/ui/map3D/Q3DWidget.h
+12
-0
No files found.
QGCExternalLibs.pri
View file @
db719606
...
...
@@ -258,26 +258,6 @@ LinuxBuild : contains(MAVLINK_CONF, pixhawk) {
message("Skipping support for Protocol Buffers")
}
#
# libfreenect Kinect support
#
MacBuild | LinuxBuild {
exists(/opt/local/include/libfreenect) | exists(/usr/local/include/libfreenect) {
message("Including support for libfreenect")
#INCLUDEPATH += /usr/include/libusb-1.0
DEFINES += QGC_LIBFREENECT_ENABLED
LIBS += -lfreenect
HEADERS += src/input/Freenect.h
SOURCES += src/input/Freenect.cc
} else {
message("Skipping support for libfreenect")
}
} else {
message("Skipping support for libfreenect")
}
#
# EIGEN matrix library (NOMINMAX needed to make internal min/max work)
#
...
...
libs/opmapcontrol/src/internals/projections/lks94projection.cpp
View file @
db719606
...
...
@@ -28,6 +28,11 @@
#include <qmath.h>
// These pragmas are local modifications to this third party library to silence warnings
#ifdef Q_OS_LINUX
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-but-set-variable"
#endif
namespace
projections
{
LKS94Projection
::
LKS94Projection
()
:
MinLatitude
(
53.33
),
MaxLatitude
(
56.55
),
MinLongitude
(
20.22
),
...
...
@@ -787,3 +792,8 @@ Size LKS94Projection::GetTileMatrixMaxXY(int const& zoom)
}
}
#ifdef Q_OS_LINUX
#pragma GCC diagnostic pop
#endif
libs/opmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp
View file @
db719606
...
...
@@ -57,6 +57,16 @@ Point MercatorProjectionYandex::FromLatLngToPixel(double lat, double lng, const
return
ret
;
}
// These pragmas are local modifications to this third party library to silence warnings
#ifdef Q_OS_LINUX
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-but-set-variable"
#elif defined(Q_OS_MAC)
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-variable"
#endif
internals
::
PointLatLng
MercatorProjectionYandex
::
FromPixelToLatLng
(
const
int
&
x
,
const
int
&
y
,
const
int
&
zoom
)
{
Size
s
=
GetTileMatrixSizePixel
(
zoom
);
...
...
@@ -82,6 +92,11 @@ internals::PointLatLng MercatorProjectionYandex::FromPixelToLatLng(const int &x,
return
ret
;
}
#ifndef Q_OS_WIN
#pragma GCC diagnostic pop
#endif
double
MercatorProjectionYandex
::
Clip
(
const
double
&
n
,
const
double
&
minValue
,
const
double
&
maxValue
)
const
{
return
qMin
(
qMax
(
n
,
minValue
),
maxValue
);
...
...
libs/qwt/qwt_plot_spectrogram.cpp
View file @
db719606
...
...
@@ -533,6 +533,15 @@ QwtRasterData::ContourLines QwtPlotSpectrogram::renderContourLines(
d_data
->
contourLevels
,
d_data
->
conrecAttributes
);
}
// These pragmas are local modifications to this third party library to silence warnings
#ifdef Q_OS_LINUX
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-but-set-variable"
#elif defined(Q_OS_MAC)
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-variable"
#endif
/*!
Paint the contour lines
...
...
@@ -578,6 +587,10 @@ void QwtPlotSpectrogram::drawContourLines(QPainter *painter,
}
}
#ifndef Q_OS_WIN
#pragma GCC diagnostic pop
#endif
/*!
\brief Draw the spectrogram
...
...
libs/qwt/qwt_plot_zoomer.h
View file @
db719606
...
...
@@ -85,8 +85,19 @@ public:
public
slots
:
void
moveBy
(
double
x
,
double
y
);
// These pragmas are local modifications to this third party library to silence warnings
#ifndef Q_OS_WIN
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Woverloaded-virtual"
#endif
virtual
void
move
(
double
x
,
double
y
);
#ifndef Q_OS_WIN
#pragma GCC diagnostic pop
#endif
virtual
void
zoom
(
const
QwtDoubleRect
&
);
virtual
void
zoom
(
int
up
);
...
...
libs/serialport/qserialport.pri
View file @
db719606
...
...
@@ -55,4 +55,4 @@ unix:!symbian {
}
}
HEADERS
+
= $$PUBLIC_HEADERS $$PRIVATE_HEADERS
HEADERS
*
= $$PUBLIC_HEADERS $$PRIVATE_HEADERS
qgroundcontrol.pro
View file @
db719606
...
...
@@ -117,16 +117,23 @@ WindowsBuild {
}
#
#
Warnings
cleanup
.
Plan
of
attack
is
to
turn
on
warnings
as
error
once
all
warnings
are
fixed
.
Please
#
do
no
change
the
warning
level
from
what
they
are
currently
set
to
below
.
#
We
treat
all
warnings
as
errors
which
must
be
fixed
before
proceeding
.
If
you
run
into
a
problem
you
can't fix
# you can always use local pragmas to work around the warning. This should be used sparingly and only in cases where
# the problem absolultey can't
be
fixed
.
#
MacBuild
|
LinuxBuild
{
QMAKE_CXXFLAGS_WARN_ON
+=
-
Wall
}
MacBuild
{
QMAKE_CXXFLAGS_WARN_ON
+=
-
Werror
}
WindowsBuild
{
QMAKE_CXXFLAGS_WARN_ON
+=
/
W3
QMAKE_CXXFLAGS_WARN_ON
+=
/
W3
\
/
wd4996
\
#
silence
warnings
about
deprecated
strcpy
and
whatnot
/
wd4290
#
ignore
exception
specifications
}
#
...
...
src/comm/MAVLinkProtocol.cc
View file @
db719606
...
...
@@ -196,15 +196,7 @@ void MAVLinkProtocol::linkStatusChanged(bool connected)
// Start NSH
const
char
init
[]
=
{
0x0d
,
0x0d
,
0x0d
};
link
->
writeBytes
(
init
,
sizeof
(
init
));
// Stop any running mavlink instance
const
char
*
cmd
=
"mavlink stop
\n
"
;
link
->
writeBytes
(
cmd
,
strlen
(
cmd
));
link
->
writeBytes
(
init
,
2
);
cmd
=
"uorb start"
;
link
->
writeBytes
(
cmd
,
strlen
(
cmd
));
link
->
writeBytes
(
init
,
2
);
cmd
=
"sh /etc/init.d/rc.usb
\n
"
;
const
char
*
cmd
=
"sh /etc/init.d/rc.usb
\n
"
;
link
->
writeBytes
(
cmd
,
strlen
(
cmd
));
link
->
writeBytes
(
init
,
4
);
}
...
...
src/qgcunittest/MockUAS.h
View file @
db719606
...
...
@@ -168,6 +168,9 @@ public slots:
virtual
void
sendHilGps
(
quint64
time_us
,
double
lat
,
double
lon
,
double
alt
,
int
fix_type
,
float
eph
,
float
epv
,
float
vel
,
float
vn
,
float
ve
,
float
vd
,
float
cog
,
int
satellites
)
{
Q_UNUSED
(
time_us
);
Q_UNUSED
(
lat
);
Q_UNUSED
(
lon
);
Q_UNUSED
(
alt
);
Q_UNUSED
(
fix_type
);
Q_UNUSED
(
eph
);
Q_UNUSED
(
epv
);
Q_UNUSED
(
vel
);
Q_UNUSED
(
vn
);
Q_UNUSED
(
ve
);
Q_UNUSED
(
vd
);
Q_UNUSED
(
cog
);
Q_UNUSED
(
satellites
);
Q_ASSERT
(
false
);
};
virtual
bool
isRotaryWing
()
{
Q_ASSERT
(
false
);
return
false
;
}
virtual
bool
isFixedWing
()
{
Q_ASSERT
(
false
);
return
false
;
}
private:
int
_systemType
;
int
_systemId
;
...
...
src/uas/UAS.cc
View file @
db719606
...
...
@@ -2115,7 +2115,7 @@ void UAS::requestImage()
if
(
imagePacketsArrived
==
0
)
{
mavlink_message_t
msg
;
mavlink_msg_data_transmission_handshake_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
DATA_TYPE_JPEG_IMAGE
,
0
,
0
,
0
,
0
,
0
,
50
);
mavlink_msg_data_transmission_handshake_pack
(
mavlink
->
getSystemId
(),
mavlink
->
getComponentId
(),
&
msg
,
MAVLINK_DATA_STREAM_IMG_JPEG
,
0
,
0
,
0
,
0
,
0
,
50
);
sendMessage
(
msg
);
}
}
...
...
@@ -2170,6 +2170,32 @@ void UAS::readParametersFromStorage()
sendMessage
(
msg
);
}
bool
UAS
::
isRotaryWing
()
{
switch
(
type
)
{
case
MAV_TYPE_QUADROTOR
:
/* fallthrough */
case
MAV_TYPE_COAXIAL
:
case
MAV_TYPE_HELICOPTER
:
case
MAV_TYPE_HEXAROTOR
:
case
MAV_TYPE_OCTOROTOR
:
case
MAV_TYPE_TRICOPTER
:
return
true
;
default:
return
false
;
}
}
bool
UAS
::
isFixedWing
()
{
switch
(
type
)
{
case
MAV_TYPE_FIXED_WING
:
return
true
;
default:
return
false
;
}
}
/**
* @param rate The update rate in Hz the message should be sent
*/
...
...
src/uas/UAS.h
View file @
db719606
...
...
@@ -306,6 +306,9 @@ public:
return
nedAttGlobalOffset
;
}
bool
isRotaryWing
();
bool
isFixedWing
();
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
px
::
GLOverlay
getOverlay
()
{
...
...
src/uas/UASInterface.h
View file @
db719606
...
...
@@ -267,6 +267,9 @@ public:
*/
virtual
QList
<
QAction
*>
getActions
()
const
=
0
;
static
const
unsigned
int
WAYPOINT_RADIUS_DEFAULT_FIXED_WING
=
25
;
static
const
unsigned
int
WAYPOINT_RADIUS_DEFAULT_ROTARY_WING
=
5
;
public
slots
:
/** @brief Set a new name for the system */
...
...
@@ -376,6 +379,11 @@ public slots:
virtual
void
startGyroscopeCalibration
()
=
0
;
virtual
void
startPressureCalibration
()
=
0
;
/** @brief Return if this a rotary wing */
virtual
bool
isRotaryWing
()
=
0
;
/** @brief Return if this is a fixed wing */
virtual
bool
isFixedWing
()
=
0
;
/** @brief Set the current battery type and voltages */
virtual
void
setBatterySpecs
(
const
QString
&
specs
)
=
0
;
/** @brief Get the current battery type and specs */
...
...
@@ -393,7 +401,6 @@ public slots:
/** @brief Send raw GPS for sensor HIL */
virtual
void
sendHilGps
(
quint64
time_us
,
double
lat
,
double
lon
,
double
alt
,
int
fix_type
,
float
eph
,
float
epv
,
float
vel
,
float
vn
,
float
ve
,
float
vd
,
float
cog
,
int
satellites
)
=
0
;
protected:
QColor
color
;
...
...
src/uas/UASWaypointManager.cc
View file @
db719606
...
...
@@ -225,6 +225,17 @@ void UASWaypointManager::handleWaypointAck(quint8 systemId, quint8 compId, mavli
current_state
=
WP_IDLE
;
readWaypoints
(
false
);
//Update "Onboard Waypoints"-tab immidiately after the waypoint list has been sent.
emit
updateStatusString
(
"done."
);
}
else
if
((
current_state
==
WP_SENDLIST
||
current_state
==
WP_SENDLIST_SENDWPS
)
&&
wpa
->
type
!=
0
)
{
//give up transmitting if a WP is rejected
if
(
wpa
->
type
==
1
)
{
emit
updateStatusString
(
"upload failed: general error"
);
}
else
if
(
wpa
->
type
==
2
)
{
emit
updateStatusString
(
"upload failed: coordinate frame unsupported."
);
}
else
{
emit
updateStatusString
(
"upload failed: other error."
);
}
protocol_timer
.
stop
();
current_state
=
WP_IDLE
;
}
else
if
(
current_state
==
WP_CLEARLIST
)
{
protocol_timer
.
stop
();
current_state
=
WP_IDLE
;
...
...
@@ -905,7 +916,7 @@ void UASWaypointManager::writeWaypoints()
sendWaypointCount
();
}
else
if
(
waypointsEditable
.
count
()
==
0
)
{
sendWaypointClearAll
();
clearWaypointList
();
}
}
else
...
...
@@ -1063,11 +1074,23 @@ int UASWaypointManager::getFrameRecommendation()
float
UASWaypointManager
::
getAcceptanceRadiusRecommendation
()
{
if
(
waypointsEditable
.
count
()
>
0
)
{
if
(
waypointsEditable
.
count
()
>
0
)
{
return
waypointsEditable
.
last
()
->
getAcceptanceRadius
();
}
else
{
return
10.0
f
;
}
else
{
if
(
uas
->
isRotaryWing
())
{
return
UASInterface
::
WAYPOINT_RADIUS_DEFAULT_ROTARY_WING
;
}
else
if
(
uas
->
isFixedWing
())
{
return
UASInterface
::
WAYPOINT_RADIUS_DEFAULT_FIXED_WING
;
}
}
return
10.0
f
;
}
float
UASWaypointManager
::
getHomeAltitudeOffsetDefault
()
...
...
src/ui/WaypointList.cc
View file @
db719606
...
...
@@ -283,9 +283,9 @@ void WaypointList::addEditable(bool onCurrentPosition)
wp
->
setZ
(
last
->
getZ
());
}
wp
->
setParam1
(
last
->
getParam1
());
wp
->
setParam
1
(
last
->
getParam2
());
wp
->
setParam
1
(
last
->
getParam3
());
wp
->
setParam
1
(
last
->
getParam4
());
wp
->
setParam
2
(
last
->
getParam2
());
wp
->
setParam
3
(
last
->
getParam3
());
wp
->
setParam
4
(
last
->
getParam4
());
wp
->
setAutocontinue
(
last
->
getAutoContinue
());
// wp->blockSignals(false);
wp
->
setAction
(
last
->
getAction
());
...
...
src/ui/map3D/Q3DWidget.h
View file @
db719606
...
...
@@ -39,8 +39,20 @@ This file is part of the QGROUNDCONTROL project
#include <osg/PositionAttitudeTransform>
#include <osgGA/TrackballManipulator>
#include <osgText/Font>
// OpenSceneGraph has overloaded virtuals defined, since third party code we silence the warnings when the
// headers are used.
#ifndef Q_OS_WIN
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Woverloaded-virtual"
#endif
#include <osgViewer/Viewer>
#ifndef Q_OS_WIN
#pragma GCC diagnostic pop
#endif
#include "CameraParams.h"
#include "GCManipulator.h"
#include "SystemGroupNode.h"
...
...
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