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
32e1c529
Commit
32e1c529
authored
Jan 01, 2011
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fixed QMapControl bug
parent
16a68ab5
Changes
15
Show whitespace changes
Inline
Side-by-side
Showing
15 changed files
with
194 additions
and
176 deletions
+194
-176
layermanager.cpp
lib/QMapControl/src/layermanager.cpp
+9
-1
LinkInterface.h
src/comm/LinkInterface.h
+1
-0
MAVLinkSimulationLink.cc
src/comm/MAVLinkSimulationLink.cc
+2
-1
MAVLinkSimulationLink.h
src/comm/MAVLinkSimulationLink.h
+1
-1
MAVLinkSwarmSimulationLink.cc
src/comm/MAVLinkSwarmSimulationLink.cc
+2
-2
MAVLinkSwarmSimulationLink.h
src/comm/MAVLinkSwarmSimulationLink.h
+1
-1
UASManager.cc
src/uas/UASManager.cc
+6
-6
MapWidget.cc
src/ui/MapWidget.cc
+144
-154
AirfoilServoCalibrator.cc
src/ui/RadioCalibration/AirfoilServoCalibrator.cc
+5
-1
RadioCalibrationData.cc
src/ui/RadioCalibration/RadioCalibrationData.cc
+3
-0
RadioCalibrationWindow.cc
src/ui/RadioCalibration/RadioCalibrationWindow.cc
+3
-0
SlugsHilSim.cc
src/ui/SlugsHilSim.cc
+7
-3
WaypointList.cc
src/ui/WaypointList.cc
+3
-1
QGCGoogleEarthView.cc
src/ui/map3D/QGCGoogleEarthView.cc
+3
-3
QOSGWidget.cc
src/ui/map3D/QOSGWidget.cc
+4
-2
No files found.
lib/QMapControl/src/layermanager.cpp
View file @
32e1c529
...
...
@@ -112,7 +112,14 @@ namespace qmapcontrol
void
LayerManager
::
setView
(
const
QPointF
&
coordinate
)
{
QPoint
oldMapPx
=
mapmiddle_px
;
mapmiddle_px
=
layer
()
->
mapadapter
()
->
coordinateToDisplay
(
coordinate
);
scroll
+=
mapmiddle_px
-
oldMapPx
;
zoomImageScroll
+=
mapmiddle_px
-
oldMapPx
;
mapmiddle
=
coordinate
;
//TODO: muss wegen moveTo() raus
...
...
@@ -125,7 +132,8 @@ namespace qmapcontrol
//TODO:
// verschiebung ausrechnen
// oder immer neues offscreenimage
newOffscreenImage
();
//newOffscreenImage();
moveWidgets
();
}
}
...
...
src/comm/LinkInterface.h
View file @
32e1c529
...
...
@@ -42,6 +42,7 @@ along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
class
LinkInterface
:
public
QThread
{
Q_OBJECT
public:
LinkInterface
(
QObject
*
parent
=
0
)
:
QThread
(
parent
)
{}
//virtual ~LinkInterface() = 0;
/* Connection management */
...
...
src/comm/MAVLinkSimulationLink.cc
View file @
32e1c529
...
...
@@ -55,7 +55,7 @@ This file is part of the QGROUNDCONTROL project
* @param writeFile The received messages are written to that file
* @param rate The rate at which the messages are sent (in intervals of milliseconds)
**/
MAVLinkSimulationLink
::
MAVLinkSimulationLink
(
QString
readFile
,
QString
writeFile
,
int
rate
)
:
MAVLinkSimulationLink
::
MAVLinkSimulationLink
(
QString
readFile
,
QString
writeFile
,
int
rate
,
QObject
*
parent
)
:
LinkInterface
(
parent
),
readyBytes
(
0
),
timeOffset
(
0
)
{
...
...
@@ -445,6 +445,7 @@ void MAVLinkSimulationLink::mainloop()
chan
.
chan6_raw
=
(
chan
.
chan3_raw
+
chan
.
chan2_raw
)
/
2.0
f
;
chan
.
chan7_raw
=
(
chan
.
chan4_raw
+
chan
.
chan2_raw
)
/
2.0
f
;
chan
.
chan8_raw
=
(
chan
.
chan6_raw
+
chan
.
chan2_raw
)
/
2.0
f
;
chan
.
rssi
=
100
;
messageSize
=
mavlink_msg_rc_channels_raw_encode
(
systemId
,
componentId
,
&
msg
,
&
chan
);
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
...
...
src/comm/MAVLinkSimulationLink.h
View file @
32e1c529
...
...
@@ -47,7 +47,7 @@ class MAVLinkSimulationLink : public LinkInterface
{
Q_OBJECT
public:
MAVLinkSimulationLink
(
QString
readFile
=
""
,
QString
writeFile
=
""
,
int
rate
=
5
);
MAVLinkSimulationLink
(
QString
readFile
=
""
,
QString
writeFile
=
""
,
int
rate
=
5
,
QObject
*
parent
=
0
);
~
MAVLinkSimulationLink
();
bool
isConnected
();
qint64
bytesAvailable
();
...
...
src/comm/MAVLinkSwarmSimulationLink.cc
View file @
32e1c529
#include "MAVLinkSwarmSimulationLink.h"
MAVLinkSwarmSimulationLink
::
MAVLinkSwarmSimulationLink
(
QObject
*
parent
)
:
MAVLinkSimulationLink
()
MAVLinkSwarmSimulationLink
::
MAVLinkSwarmSimulationLink
(
Q
String
readFile
,
QString
writeFile
,
int
rate
,
Q
Object
*
parent
)
:
MAVLinkSimulationLink
(
readFile
,
writeFile
,
rate
,
parent
)
{
}
...
...
src/comm/MAVLinkSwarmSimulationLink.h
View file @
32e1c529
...
...
@@ -7,7 +7,7 @@ class MAVLinkSwarmSimulationLink : public MAVLinkSimulationLink
{
Q_OBJECT
public:
explicit
MAVLinkSwarmSimulationLink
(
QObject
*
parent
=
0
);
MAVLinkSwarmSimulationLink
(
QString
readFile
=
""
,
QString
writeFile
=
""
,
int
rate
=
5
,
QObject
*
parent
=
0
);
signals:
...
...
src/uas/UASManager.cc
View file @
32e1c529
...
...
@@ -104,12 +104,12 @@ QList<UASInterface*> UASManager::getUASList()
UASInterface
*
UASManager
::
getActiveUAS
()
{
if
(
!
activeUAS
)
{
QMessageBox
msgBox
;
msgBox
.
setText
(
tr
(
"No Micro Air Vehicle connected. Please connect one first."
));
msgBox
.
exec
();
}
//
if(!activeUAS)
//
{
//
QMessageBox msgBox;
//
msgBox.setText(tr("No Micro Air Vehicle connected. Please connect one first."));
//
msgBox.exec();
//
}
return
activeUAS
;
///< Return zero pointer if no UAS has been loaded
}
...
...
src/ui/MapWidget.cc
View file @
32e1c529
/*==================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
...
...
@@ -62,7 +43,7 @@ MapWidget::MapWidget(QWidget *parent) :
mc
=
new
qmapcontrol
::
MapControl
(
QSize
(
320
,
240
));
mc
->
showScale
(
true
);
mc
->
showCoord
(
true
);
mc
->
enablePersistentCache
();
mc
->
enablePersistentCache
(
qApp
->
applicationDirPath
()
);
mc
->
setMouseTracking
(
true
);
// required to update the mouse position for diplay and capture
// create MapAdapter to get maps from
...
...
@@ -194,8 +175,16 @@ MapWidget::MapWidget(QWidget *parent) :
connect
(
zoomout
,
SIGNAL
(
clicked
(
bool
)),
mc
,
SLOT
(
zoomOut
()));
QList
<
UASInterface
*>
systems
=
UASManager
::
instance
()
->
getUASList
();
foreach
(
UASInterface
*
system
,
systems
)
{
addUAS
(
system
);
}
connect
(
UASManager
::
instance
(),
SIGNAL
(
UASCreated
(
UASInterface
*
)),
this
,
SLOT
(
addUAS
(
UASInterface
*
)));
activeUASSet
(
UASManager
::
instance
()
->
getActiveUAS
());
connect
(
UASManager
::
instance
(),
SIGNAL
(
activeUASSet
(
UASInterface
*
)),
this
,
SLOT
(
activeUASSet
(
UASInterface
*
)));
connect
(
mc
,
SIGNAL
(
mouseEventCoordinate
(
const
QMouseEvent
*
,
const
QPointF
)),
...
...
@@ -231,10 +220,6 @@ MapWidget::MapWidget(QWidget *parent) :
drawCamBorder
=
false
;
radioCamera
=
10
;
this
->
setVisible
(
false
);
}
...
...
@@ -520,6 +505,10 @@ MapWidget::~MapWidget()
*/
void
MapWidget
::
addUAS
(
UASInterface
*
uas
)
{
if
(
mav
!=
NULL
)
{
disconnect
(
uas
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateGlobalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
}
connect
(
uas
,
SIGNAL
(
globalPositionChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateGlobalPosition
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
}
...
...
@@ -572,7 +561,7 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
// A QPen also can use transparency
QList
<
qmapcontrol
::
Point
*>
points
;
points
.
append
(
new
qmapcontrol
::
Point
(
lat
,
lon
,
QString
(
"lat: %1 lon: %2"
).
arg
(
lat
,
lon
)
));
points
.
append
(
new
qmapcontrol
::
Point
(
lat
,
lon
,
""
));
QPen
*
linepen
=
new
QPen
(
uasColor
.
darker
());
linepen
->
setWidth
(
2
);
// Add the Points and the QPen to a LineString
...
...
@@ -591,7 +580,7 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon,
p
->
setYaw
(
uas
->
getYaw
());
}
// Extend trail
uasTrails
.
value
(
uas
->
getUASID
())
->
addPoint
(
new
qmapcontrol
::
Point
(
lat
,
lon
,
QString
(
"lat: %1 lon: %2"
).
arg
(
lat
,
lon
)
));
uasTrails
.
value
(
uas
->
getUASID
())
->
addPoint
(
new
qmapcontrol
::
Point
(
lat
,
lon
,
""
));
}
...
...
@@ -723,6 +712,7 @@ void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, floa
void
MapWidget
::
updateCameraPosition
(
double
radio
,
double
bearing
,
QString
dir
)
{
// FIXME Mariano
//camPoints.clear();
QPointF
currentPos
=
mc
->
currentCoordinate
();
// QPointF actualPos = getPointxBearing_Range(currentPos.y(),currentPos.x(),bearing,distance);
...
...
src/ui/RadioCalibration/AirfoilServoCalibrator.cc
View file @
32e1c529
...
...
@@ -10,7 +10,7 @@ AirfoilServoCalibrator::AirfoilServoCalibrator(AirfoilType type, QWidget *parent
/* Add title */
QHBoxLayout
*
titleLayout
=
new
QHBoxLayout
();
QLabel
*
title
;
QLabel
*
title
;
if
(
type
==
AILERON
)
{
title
=
new
QLabel
(
tr
(
"Aileron"
));
...
...
@@ -23,6 +23,10 @@ AirfoilServoCalibrator::AirfoilServoCalibrator(AirfoilType type, QWidget *parent
{
title
=
new
QLabel
(
tr
(
"Rudder"
));
}
else
{
title
=
new
QLabel
(
tr
(
"Unknown"
));
}
titleLayout
->
addWidget
(
title
);
grid
->
addLayout
(
titleLayout
,
0
,
0
,
1
,
3
,
Qt
::
AlignHCenter
);
...
...
src/ui/RadioCalibration/RadioCalibrationData.cc
View file @
32e1c529
...
...
@@ -55,6 +55,9 @@ const QVector<float>& RadioCalibrationData::operator ()(int i) const
return
(
*
data
)[
i
];
}
// FIXME Bryan
// FIXME James
// This is not good. If it is ever used after being returned it will cause a crash
// return QVector<float>();
}
...
...
src/ui/RadioCalibration/RadioCalibrationWindow.cc
View file @
32e1c529
...
...
@@ -84,6 +84,9 @@ void RadioCalibrationWindow::setChannelRaw(int ch, float raw)
void
RadioCalibrationWindow
::
setChannelScaled
(
int
ch
,
float
normalized
)
{
// FIXME James
// FIXME Bryan
// /** this expects a particular channel to function mapping
// \todo allow run-time channel mapping
// */
...
...
src/ui/SlugsHilSim.cc
View file @
32e1c529
...
...
@@ -136,7 +136,9 @@ void SlugsHilSim::activeUasSet(UASInterface* uas){
}
void
SlugsHilSim
::
processHilDatagram
(
const
QByteArray
*
datagram
){
void
SlugsHilSim
::
processHilDatagram
(
const
QByteArray
*
datagram
)
{
#ifdef MAVLINK_ENABLED_SLUGS
unsigned
char
i
=
0
;
mavlink_message_t
msg
;
...
...
@@ -144,7 +146,6 @@ void SlugsHilSim::processHilDatagram(const QByteArray* datagram){
// GPS
mavlink_gps_raw_t
tmpGpsRaw
;
#ifdef MAVLINK_ENABLED_SLUGS
mavlink_gps_date_time_t
tmpGpsTime
;
tmpGpsTime
.
year
=
datagram
->
at
(
i
++
);
...
...
@@ -167,7 +168,6 @@ void SlugsHilSim::processHilDatagram(const QByteArray* datagram){
mavlink_msg_gps_date_time_encode
(
MG
::
SYSTEM
::
ID
,
MG
::
SYSTEM
::
COMPID
,
&
msg
,
&
tmpGpsTime
);
activeUas
->
sendMessage
(
hilLink
,
msg
);
#endif
memset
(
&
msg
,
0
,
sizeof
(
mavlink_message_t
));
...
...
@@ -180,6 +180,9 @@ void SlugsHilSim::processHilDatagram(const QByteArray* datagram){
ui
->
ed_1
->
setText
(
QString
::
number
(
tmpGpsRaw
.
hdg
));
ui
->
ed_2
->
setText
(
QString
::
number
(
tmpGpsRaw
.
v
));
ui
->
ed_3
->
setText
(
QString
::
number
(
tmpGpsRaw
.
eph
));
#else
Q_UNUSED
(
datagram
);
#endif
}
float
SlugsHilSim
::
getFloatFromDatagram
(
const
QByteArray
*
datagram
,
unsigned
char
*
i
){
...
...
@@ -205,4 +208,5 @@ uint16_t SlugsHilSim::getUint16FromDatagram (const QByteArray* datagram, unsigne
void
SlugsHilSim
::
linkSelected
(
int
cbIndex
){
//hilLink = linksAvailable
// FIXME Mariano
}
src/ui/WaypointList.cc
View file @
32e1c529
...
...
@@ -570,5 +570,7 @@ void WaypointList::setIsLoadFileWP()
void
WaypointList
::
setIsReadGlobalWP
(
bool
value
)
{
// FIXME James Check this
Q_UNUSED
(
value
);
// readGlobalWP = value;
}
src/ui/map3D/QGCGoogleEarthView.cc
View file @
32e1c529
...
...
@@ -178,7 +178,7 @@ void QGCGoogleEarthView::showTrail(bool state)
void
QGCGoogleEarthView
::
showWaypoints
(
bool
state
)
{
waypointsEnabled
=
state
;
}
void
QGCGoogleEarthView
::
follow
(
bool
follow
)
...
...
@@ -232,7 +232,7 @@ void QGCGoogleEarthView::showEvent(QShowEvent* event)
// Reloading the webpage, this resets Google Earth
gEarthInitialized
=
false
;
QTimer
::
singleShot
(
2
000
,
this
,
SLOT
(
initializeGoogleEarth
()));
QTimer
::
singleShot
(
3
000
,
this
,
SLOT
(
initializeGoogleEarth
()));
updateTimer
->
start
(
refreshRateMs
);
}
}
...
...
@@ -299,7 +299,7 @@ void QGCGoogleEarthView::initializeGoogleEarth()
qDebug
()
<<
"COULD NOT GET DOCUMENT OBJECT! Aborting"
;
}
#endif
QTimer
::
singleShot
(
2
500
,
this
,
SLOT
(
initializeGoogleEarth
()));
QTimer
::
singleShot
(
3
500
,
this
,
SLOT
(
initializeGoogleEarth
()));
return
;
}
...
...
src/ui/map3D/QOSGWidget.cc
View file @
32e1c529
...
...
@@ -26,7 +26,7 @@ QOSGWidget::QOSGWidget( QWidget * parent, const char * name, WindowFlags f, bool
QWidget
(
parent
,
f
),
_overrideTraits
(
overrideTraits
)
{
createContext
();
Q_UNUSED
(
name
);
setAttribute
(
Qt
::
WA_PaintOnScreen
);
setAttribute
(
Qt
::
WA_NoSystemBackground
);
setFocusPolicy
(
Qt
::
ClickFocus
);
...
...
@@ -95,6 +95,8 @@ void QOSGWidget::createContext()
#ifndef WIN32
void
QOSGWidget
::
destroyEvent
(
bool
destroyWindow
,
bool
destroySubWindows
)
{
Q_UNUSED
(
destroyWindow
);
Q_UNUSED
(
destroySubWindows
);
_gw
->
getEventQueue
()
->
closeWindow
();
}
...
...
@@ -236,7 +238,7 @@ class QViewerTimer : public QWidget
_timer
.
stop
();
}
virtual
void
paintEvent
(
QPaintEvent
*
event
)
{
_viewer
->
frame
();
}
virtual
void
paintEvent
(
QPaintEvent
*
event
)
{
Q_UNUSED
(
event
);
_viewer
->
frame
();
}
osg
::
ref_ptr
<
osgViewer
::
CompositeViewer
>
_viewer
;
QTimer
_timer
;
...
...
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