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
354438be
Commit
354438be
authored
Feb 11, 2011
by
lm
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fixed waypoint interface to adhere to specs, fixed param name length
parent
b862021a
Changes
8
Hide whitespace changes
Inline
Side-by-side
Showing
8 changed files
with
68 additions
and
23 deletions
+68
-23
Waypoint.cc
src/Waypoint.cc
+27
-0
Waypoint.h
src/Waypoint.h
+6
-0
MAVLinkSimulationMAV.cc
src/comm/MAVLinkSimulationMAV.cc
+5
-5
MAVLinkSimulationWaypointPlanner.cc
src/comm/MAVLinkSimulationWaypointPlanner.cc
+2
-2
UAS.cc
src/uas/UAS.cc
+2
-2
MapWidget.cc
src/ui/MapWidget.cc
+15
-7
WaypointList.cc
src/ui/WaypointList.cc
+1
-1
WaypointView.cc
src/ui/WaypointView.cc
+10
-6
No files found.
src/Waypoint.cc
View file @
354438be
...
...
@@ -124,6 +124,33 @@ void Waypoint::setZ(double z)
}
}
void
Waypoint
::
setLatitude
(
double
lat
)
{
if
(
this
->
x
!=
lat
)
{
this
->
x
=
lat
;
emit
changed
(
this
);
}
}
void
Waypoint
::
setLongitude
(
double
lon
)
{
if
(
this
->
y
!=
lon
)
{
this
->
y
=
lon
;
emit
changed
(
this
);
}
}
void
Waypoint
::
setAltitude
(
double
altitude
)
{
if
(
this
->
z
!=
altitude
)
{
this
->
z
=
altitude
;
emit
changed
(
this
);
}
}
void
Waypoint
::
setYaw
(
double
yaw
)
{
if
(
this
->
yaw
!=
yaw
)
...
...
src/Waypoint.h
View file @
354438be
...
...
@@ -52,6 +52,9 @@ public:
double
getX
()
const
{
return
x
;
}
double
getY
()
const
{
return
y
;
}
double
getZ
()
const
{
return
z
;
}
double
getLatitude
()
const
{
return
x
;
}
double
getLongitude
()
const
{
return
y
;
}
double
getAltitude
()
const
{
return
z
;
}
double
getYaw
()
const
{
return
yaw
;
}
bool
getAutoContinue
()
const
{
return
autocontinue
;
}
bool
getCurrent
()
const
{
return
current
;
}
...
...
@@ -95,6 +98,9 @@ public slots:
void
setX
(
double
x
);
void
setY
(
double
y
);
void
setZ
(
double
z
);
void
setLatitude
(
double
lat
);
void
setLongitude
(
double
lon
);
void
setAltitude
(
double
alt
);
void
setYaw
(
double
yaw
);
/** @brief Set the waypoint action */
void
setAction
(
int
action
);
...
...
src/comm/MAVLinkSimulationMAV.cc
View file @
354438be
...
...
@@ -15,8 +15,8 @@ MAVLinkSimulationMAV::MAVLinkSimulationMAV(MAVLinkSimulationLink *parent, int sy
latitude
(
lat
),
longitude
(
lon
),
altitude
(
0.0
),
x
(
l
on
),
y
(
l
at
),
x
(
l
at
),
y
(
l
on
),
z
(
550
),
roll
(
0.0
),
pitch
(
0.0
),
...
...
@@ -133,8 +133,8 @@ void MAVLinkSimulationMAV::mainloop()
mavlink_message_t
msg
;
mavlink_global_position_int_t
pos
;
pos
.
alt
=
z
*
1000.0
;
pos
.
lat
=
y
*
1E7
;
pos
.
lon
=
x
*
1E7
;
pos
.
lat
=
x
*
1E7
;
pos
.
lon
=
y
*
1E7
;
pos
.
vx
=
10.0
f
*
100.0
f
;
pos
.
vy
=
0
;
pos
.
vz
=
altPer100ms
*
10.0
f
*
100.0
f
*
zsign
*-
1.0
f
;
...
...
@@ -147,7 +147,7 @@ void MAVLinkSimulationMAV::mainloop()
attitude
.
usec
=
0
;
attitude
.
roll
=
0.0
f
;
attitude
.
pitch
=
0.0
f
;
attitude
.
yaw
=
yaw
;
attitude
.
yaw
=
yaw
-
M_PI_2
;
attitude
.
rollspeed
=
0.0
f
;
attitude
.
pitchspeed
=
0.0
f
;
attitude
.
yawspeed
=
0.0
f
;
...
...
src/comm/MAVLinkSimulationWaypointPlanner.cc
View file @
354438be
...
...
@@ -573,8 +573,8 @@ void MAVLinkSimulationWaypointPlanner::mavlink_handler (const mavlink_message_t*
mavlink_global_position_int_t
pos
;
mavlink_msg_global_position_int_decode
(
msg
,
&
pos
);
float
x
=
static_cast
<
double
>
(
pos
.
l
on
)
/
1E7
;
float
y
=
static_cast
<
double
>
(
pos
.
l
at
)
/
1E7
;
float
x
=
static_cast
<
double
>
(
pos
.
l
at
)
/
1E7
;
float
y
=
static_cast
<
double
>
(
pos
.
l
on
)
/
1E7
;
float
z
=
static_cast
<
double
>
(
pos
.
alt
)
/
1000
;
qDebug
()
<<
"Received new position: x:"
<<
x
<<
"| y:"
<<
y
<<
"| z:"
<<
z
;
...
...
src/uas/UAS.cc
View file @
354438be
...
...
@@ -678,8 +678,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
mavlink_param_value_t
value
;
mavlink_msg_param_value_decode
(
&
message
,
&
value
);
QString
parameterName
=
QString
(
(
char
*
)
value
.
param_id
);
QByteArray
bytes
((
char
*
)
value
.
param_id
,
MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN
);
QString
parameterName
=
QString
(
bytes
);
int
component
=
message
.
compid
;
float
val
=
value
.
param_value
;
...
...
src/ui/MapWidget.cc
View file @
354438be
...
...
@@ -417,7 +417,15 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina
if
(
mav
)
{
mav
->
getWaypointManager
()
->
addWaypoint
(
new
Waypoint
(
mav
->
getWaypointManager
()
->
getWaypointList
().
count
(),
coordinate
.
x
(),
coordinate
.
y
(),
0.0
f
,
0.0
f
,
true
));
double
altitude
=
0.0
;
double
yaw
=
0.0
;
int
wpListCount
=
mav
->
getWaypointManager
()
->
getWaypointList
().
count
();
if
(
wpListCount
>
0
)
{
altitude
=
mav
->
getWaypointManager
()
->
getWaypointList
().
at
(
wpListCount
-
1
)
->
getAltitude
();
yaw
=
mav
->
getWaypointManager
()
->
getWaypointList
().
at
(
wpListCount
-
1
)
->
getYaw
();
}
mav
->
getWaypointManager
()
->
addWaypoint
(
new
Waypoint
(
wpListCount
,
coordinate
.
y
(),
coordinate
.
x
(),
altitude
,
yaw
,
true
));
}
else
{
...
...
@@ -472,8 +480,8 @@ void MapWidget::updateWaypoint(int uas, Waypoint* wp, bool updateView)
{
// Waypoint is new, a new icon is created
QPointF
coordinate
;
coordinate
.
setX
(
wp
->
get
X
());
coordinate
.
setY
(
wp
->
get
Y
());
coordinate
.
setX
(
wp
->
get
Longitude
());
coordinate
.
setY
(
wp
->
get
Latitude
());
createWaypointGraphAtMap
(
wpindex
,
coordinate
);
}
else
...
...
@@ -483,8 +491,8 @@ void MapWidget::updateWaypoint(int uas, Waypoint* wp, bool updateView)
if
(
!
waypointIsDrag
)
{
QPointF
coordinate
;
coordinate
.
setX
(
wp
->
get
X
());
coordinate
.
setY
(
wp
->
get
Y
());
coordinate
.
setX
(
wp
->
get
Longitude
());
coordinate
.
setY
(
wp
->
get
Latitude
());
Point
*
waypoint
;
waypoint
=
wps
.
at
(
wpindex
);
...
...
@@ -624,8 +632,8 @@ void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate)
if
(
wps
.
size
()
>
index
)
{
Waypoint
*
wp
=
wps
.
at
(
index
);
wp
->
set
X
(
coordinate
.
x
());
wp
->
set
Y
(
coordinate
.
y
());
wp
->
set
Latitude
(
coordinate
.
y
());
wp
->
set
Longitude
(
coordinate
.
x
());
mav
->
getWaypointManager
()
->
notifyOfChange
(
wp
);
}
}
...
...
src/ui/WaypointList.cc
View file @
354438be
...
...
@@ -188,7 +188,7 @@ void WaypointList::add()
else
{
// Create global frame waypoint per default
wp
=
new
Waypoint
(
0
,
uas
->
getL
ongitude
(),
uas
->
getLat
itude
(),
uas
->
getAltitude
(),
0.0
,
true
,
true
,
0.15
,
0
,
MAV_FRAME_GLOBAL
,
MAV_CMD_NAV_WAYPOINT
);
wp
=
new
Waypoint
(
0
,
uas
->
getL
atitude
(),
uas
->
getLong
itude
(),
uas
->
getAltitude
(),
0.0
,
true
,
true
,
0.15
,
0
,
MAV_FRAME_GLOBAL
,
MAV_CMD_NAV_WAYPOINT
);
uas
->
getWaypointManager
()
->
addWaypoint
(
wp
);
}
}
...
...
src/ui/WaypointView.cc
View file @
354438be
...
...
@@ -76,8 +76,8 @@ 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
->
l
on
SpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
setX
(
double
)));
connect
(
m_ui
->
l
at
SpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
setY
(
double
)));
connect
(
m_ui
->
l
at
SpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
setX
(
double
)));
connect
(
m_ui
->
l
on
SpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
setY
(
double
)));
connect
(
m_ui
->
altSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
setZ
(
double
)));
//hidden degree to radian conversion of the yaw angle
...
...
@@ -267,6 +267,10 @@ void WaypointView::changeViewMode(QGC_WAYPOINTVIEW_MODE mode)
switch
(
mode
)
{
case
QGC_WAYPOINTVIEW_MODE_NAV
:
case
QGC_WAYPOINTVIEW_MODE_CONDITION
:
// Hide everything, show condition widget
// TODO
case
QGC_WAYPOINTVIEW_MODE_DO
:
break
;
case
QGC_WAYPOINTVIEW_MODE_DIRECT_EDITING
:
...
...
@@ -399,13 +403,13 @@ void WaypointView::updateValues()
break
;
case
(
MAV_FRAME_GLOBAL
):
{
if
(
m_ui
->
l
on
SpinBox
->
value
()
!=
wp
->
getX
())
if
(
m_ui
->
l
at
SpinBox
->
value
()
!=
wp
->
getX
())
{
m_ui
->
l
on
SpinBox
->
setValue
(
wp
->
getX
());
m_ui
->
l
at
SpinBox
->
setValue
(
wp
->
getX
());
}
if
(
m_ui
->
l
at
SpinBox
->
value
()
!=
wp
->
getY
())
if
(
m_ui
->
l
on
SpinBox
->
value
()
!=
wp
->
getY
())
{
m_ui
->
l
at
SpinBox
->
setValue
(
wp
->
getY
());
m_ui
->
l
on
SpinBox
->
setValue
(
wp
->
getY
());
}
if
(
m_ui
->
altSpinBox
->
value
()
!=
wp
->
getZ
())
{
...
...
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