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
004183d5
Commit
004183d5
authored
Jul 09, 2011
by
lm
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Stable waypoint drag-and-drop, fixed a number of funky waypoint update methods.
parent
e869bac6
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
53 additions
and
33 deletions
+53
-33
Waypoint.cc
src/Waypoint.cc
+6
-9
configuration.h
src/configuration.h
+4
-4
mapgraphicitem.cpp
src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp
+5
-7
waypointitem.cpp
src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp
+3
-0
WaypointView.cc
src/ui/WaypointView.cc
+21
-9
QGCMapWidget.cc
src/ui/map/QGCMapWidget.cc
+14
-4
No files found.
src/Waypoint.cc
View file @
004183d5
...
...
@@ -108,7 +108,7 @@ void Waypoint::setId(quint16 id)
void
Waypoint
::
setX
(
double
x
)
{
if
(
this
->
x
!=
x
)
{
if
(
this
->
x
!=
x
&&
(
this
->
frame
==
MAV_FRAME_LOCAL
)
)
{
this
->
x
=
x
;
emit
changed
(
this
);
}
...
...
@@ -116,7 +116,7 @@ void Waypoint::setX(double x)
void
Waypoint
::
setY
(
double
y
)
{
if
(
this
->
y
!=
y
)
{
if
(
this
->
y
!=
y
&&
(
this
->
frame
==
MAV_FRAME_LOCAL
)
)
{
this
->
y
=
y
;
emit
changed
(
this
);
}
...
...
@@ -124,7 +124,7 @@ void Waypoint::setY(double y)
void
Waypoint
::
setZ
(
double
z
)
{
if
(
this
->
z
!=
z
)
{
if
(
this
->
z
!=
z
&&
(
this
->
frame
==
MAV_FRAME_LOCAL
)
)
{
this
->
z
=
z
;
emit
changed
(
this
);
}
...
...
@@ -132,27 +132,24 @@ void Waypoint::setZ(double z)
void
Waypoint
::
setLatitude
(
double
lat
)
{
if
(
this
->
x
!=
lat
)
{
if
(
this
->
x
!=
lat
&&
((
this
->
frame
==
MAV_FRAME_GLOBAL
)
||
(
this
->
frame
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
))
)
{
this
->
x
=
lat
;
this
->
frame
=
MAV_FRAME_GLOBAL
;
emit
changed
(
this
);
}
}
void
Waypoint
::
setLongitude
(
double
lon
)
{
if
(
this
->
y
!=
lon
)
{
if
(
this
->
y
!=
lon
&&
((
this
->
frame
==
MAV_FRAME_GLOBAL
)
||
(
this
->
frame
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
))
)
{
this
->
y
=
lon
;
this
->
frame
=
MAV_FRAME_GLOBAL
;
emit
changed
(
this
);
}
}
void
Waypoint
::
setAltitude
(
double
altitude
)
{
if
(
this
->
z
!=
altitude
)
{
if
(
this
->
z
!=
altitude
&&
((
this
->
frame
==
MAV_FRAME_GLOBAL
)
||
(
this
->
frame
==
MAV_FRAME_GLOBAL_RELATIVE_ALT
))
)
{
this
->
z
=
altitude
;
this
->
frame
=
MAV_FRAME_GLOBAL
;
emit
changed
(
this
);
}
}
...
...
src/configuration.h
View file @
004183d5
...
...
@@ -4,7 +4,7 @@
#include <QString>
/** @brief Polling interval in ms */
#define SERIAL_POLL_INTERVAL
7
#define SERIAL_POLL_INTERVAL
9
/** @brief Heartbeat emission rate, in Hertz (times per second) */
#define MAVLINK_HEARTBEAT_DEFAULT_RATE 1
...
...
@@ -12,14 +12,14 @@
#define WITH_TEXT_TO_SPEECH 1
#define QGC_APPLICATION_NAME "QGroundControl"
#define QGC_APPLICATION_VERSION "v. 0.
8.3 (Alpha RC7
)"
#define QGC_APPLICATION_VERSION "v. 0.
9.0 (Alpha RC1
)"
namespace
QGC
{
const
QString
APPNAME
=
"QGROUNDCONTROL"
;
const
QString
COMPANYNAME
=
"
OPENMAV
"
;
const
int
APPLICATIONVERSION
=
83
;
// 0.8
.0
const
QString
COMPANYNAME
=
"
QGROUNDCONTROL
"
;
const
int
APPLICATIONVERSION
=
90
;
// 0.9
.0
}
#endif // QGC_CONFIGURATION_H
src/libs/opmapcontrol/src/mapwidget/mapgraphicitem.cpp
View file @
004183d5
...
...
@@ -455,17 +455,15 @@ namespace mapcontrol
}
internals
::
PointLatLng
MapGraphicItem
::
FromLocalToLatLng
(
int
x
,
int
y
)
{
// It is IMPORTANT here to use full precision during the calculations!
double
lat
,
lon
;
if
(
MapRenderTransform
!=
1
)
{
lat
=
x
+
((
static_cast
<
double
>
(
boundingRect
().
width
())
*
MapRenderTransform
)
-
(
boundingRect
().
width
()))
/
2.0
f
;
lon
=
y
+
((
static_cast
<
double
>
(
boundingRect
().
height
())
*
MapRenderTransform
)
-
(
boundingRect
().
height
()))
/
2.0
f
;
x
=
x
+
((
boundingRect
().
width
()
*
MapRenderTransform
)
-
(
boundingRect
().
width
()))
/
2
;
y
=
y
+
((
boundingRect
().
height
()
*
MapRenderTransform
)
-
(
boundingRect
().
height
()))
/
2
;
lat
=
(
x
/
MapRenderTransform
);
lon
=
(
y
/
MapRenderTransform
);
x
=
(
int
)
(
x
/
MapRenderTransform
);
y
=
(
int
)
(
y
/
MapRenderTransform
);
}
return
core
->
FromLocalToLatLng
(
lat
,
lon
);
return
core
->
FromLocalToLatLng
(
x
,
y
);
}
float
MapGraphicItem
::
metersToPixels
(
double
meters
,
internals
::
PointLatLng
coord
)
{
...
...
src/libs/opmapcontrol/src/mapwidget/waypointitem.cpp
View file @
004183d5
...
...
@@ -103,6 +103,8 @@ namespace mapcontrol
delete
text
;
delete
textBG
;
coord
=
map
->
FromLocalToLatLng
(
this
->
pos
().
x
(),
this
->
pos
().
y
());
QString
coord_str
=
" "
+
QString
::
number
(
coord
.
Lat
(),
'f'
,
6
)
+
" "
+
QString
::
number
(
coord
.
Lng
(),
'f'
,
6
);
qDebug
()
<<
"WP MOVE:"
<<
coord_str
<<
__FILE__
<<
__LINE__
;
isDragging
=
false
;
RefreshToolTip
();
...
...
@@ -118,6 +120,7 @@ namespace mapcontrol
coord
=
map
->
FromLocalToLatLng
(
this
->
pos
().
x
(),
this
->
pos
().
y
());
QString
coord_str
=
" "
+
QString
::
number
(
coord
.
Lat
(),
'f'
,
6
)
+
" "
+
QString
::
number
(
coord
.
Lng
(),
'f'
,
6
);
text
->
setText
(
coord_str
);
qDebug
()
<<
"WP DRAG:"
<<
coord_str
<<
__FILE__
<<
__LINE__
;
textBG
->
setRect
(
text
->
boundingRect
());
emit
WPValuesChanged
(
this
);
...
...
src/ui/WaypointView.cc
View file @
004183d5
...
...
@@ -71,9 +71,9 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
connect
(
m_ui
->
posESpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
setY
(
double
)));
connect
(
m_ui
->
posDSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
setZ
(
double
)));
connect
(
m_ui
->
latSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
set
X
(
double
)));
connect
(
m_ui
->
lonSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
set
Y
(
double
)));
connect
(
m_ui
->
altSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
set
Z
(
double
)));
connect
(
m_ui
->
latSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
set
Latitude
(
double
)));
connect
(
m_ui
->
lonSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
set
Longitude
(
double
)));
connect
(
m_ui
->
altSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
set
Altitude
(
double
)));
connect
(
m_ui
->
yawSpinBox
,
SIGNAL
(
valueChanged
(
int
)),
wp
,
SLOT
(
setYaw
(
int
)));
connect
(
m_ui
->
upButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
moveUp
()));
...
...
@@ -391,14 +391,26 @@ void WaypointView::updateValues()
break
;
case
MAV_FRAME_GLOBAL
:
case
MAV_FRAME_GLOBAL_RELATIVE_ALT
:
{
if
(
m_ui
->
latSpinBox
->
value
()
!=
wp
->
getX
())
{
m_ui
->
latSpinBox
->
setValue
(
wp
->
getX
());
if
(
m_ui
->
latSpinBox
->
value
()
!=
wp
->
getLatitude
())
{
// Rounding might occur, prevent spin box from
// firing back changes
m_ui
->
latSpinBox
->
blockSignals
(
true
);
m_ui
->
latSpinBox
->
setValue
(
wp
->
getLatitude
());
m_ui
->
latSpinBox
->
blockSignals
(
false
);
}
if
(
m_ui
->
lonSpinBox
->
value
()
!=
wp
->
getY
())
{
m_ui
->
lonSpinBox
->
setValue
(
wp
->
getY
());
if
(
m_ui
->
lonSpinBox
->
value
()
!=
wp
->
getLongitude
())
{
// Rounding might occur, prevent spin box from
// firing back changes
m_ui
->
lonSpinBox
->
blockSignals
(
true
);
m_ui
->
lonSpinBox
->
setValue
(
wp
->
getLongitude
());
m_ui
->
lonSpinBox
->
blockSignals
(
false
);
}
if
(
m_ui
->
altSpinBox
->
value
()
!=
wp
->
getZ
())
{
m_ui
->
altSpinBox
->
setValue
(
wp
->
getZ
());
if
(
m_ui
->
altSpinBox
->
value
()
!=
wp
->
getAltitude
())
{
// Rounding might occur, prevent spin box from
// firing back changes
m_ui
->
altSpinBox
->
blockSignals
(
true
);
m_ui
->
altSpinBox
->
setValue
(
wp
->
getAltitude
());
m_ui
->
altSpinBox
->
blockSignals
(
false
);
}
}
break
;
...
...
src/ui/map/QGCMapWidget.cc
View file @
004183d5
...
...
@@ -133,9 +133,9 @@ void QGCMapWidget::loadSettings()
settings
.
endGroup
();
// SET INITIAL POSITION AND ZOOM
SetZoom
(
lastZoom
);
// set map zoom level
internals
::
PointLatLng
pos_lat_lon
=
internals
::
PointLatLng
(
lastLat
,
lastLon
);
SetCurrentPosition
(
pos_lat_lon
);
// set the map position
SetZoom
(
lastZoom
);
// set map zoom level
}
void
QGCMapWidget
::
storeSettings
()
...
...
@@ -152,7 +152,7 @@ void QGCMapWidget::storeSettings()
void
QGCMapWidget
::
mouseDoubleClickEvent
(
QMouseEvent
*
event
)
{
OPMapWidget
::
mouseDoubleClickEvent
(
event
);
//
OPMapWidget::mouseDoubleClickEvent(event);
if
(
currEditMode
==
EDIT_MODE_WAYPOINTS
)
{
// If a waypoint manager is available
...
...
@@ -372,14 +372,24 @@ void QGCMapWidget::handleMapWaypointEdit(mapcontrol::WayPointItem* waypoint)
// Update WP values
internals
::
PointLatLng
pos
=
waypoint
->
Coord
();
// Block waypoint signals
wp
->
blockSignals
(
true
);
wp
->
setLatitude
(
pos
.
Lat
());
wp
->
setLongitude
(
pos
.
Lng
());
wp
->
setAltitude
(
waypoint
->
Altitude
());
wp
->
blockSignals
(
false
);
qDebug
()
<<
"WP: LAT:"
<<
pos
.
Lat
()
<<
"LON:"
<<
pos
.
Lng
();
emit
waypointChanged
(
wp
);
internals
::
PointLatLng
coord
=
waypoint
->
Coord
();
QString
coord_str
=
" "
+
QString
::
number
(
coord
.
Lat
(),
'f'
,
6
)
+
" "
+
QString
::
number
(
coord
.
Lng
(),
'f'
,
6
);
qDebug
()
<<
"MAP WP COORD (MAP):"
<<
coord_str
<<
__FILE__
<<
__LINE__
;
QString
wp_str
=
QString
::
number
(
wp
->
getLatitude
(),
'f'
,
6
)
+
" "
+
QString
::
number
(
wp
->
getLongitude
(),
'f'
,
6
);
qDebug
()
<<
"MAP WP COORD (WP):"
<<
wp_str
<<
__FILE__
<<
__LINE__
;
firingWaypointChange
=
NULL
;
emit
waypointChanged
(
wp
);
}
// WAYPOINT UPDATE FUNCTIONS
...
...
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