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
c3c390c2
Commit
c3c390c2
authored
Jun 24, 2010
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
new waypoint fields included
parent
04f32749
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
21 additions
and
15 deletions
+21
-15
UASWaypointManager.cc
src/uas/UASWaypointManager.cc
+3
-2
UASWaypointManager.h
src/uas/UASWaypointManager.h
+1
-1
HSIDisplay.cc
src/ui/HSIDisplay.cc
+1
-1
WaypointList.cc
src/ui/WaypointList.cc
+8
-8
WaypointList.h
src/ui/WaypointList.h
+1
-1
WaypointView.cc
src/ui/WaypointView.cc
+6
-1
WaypointView.ui
src/ui/WaypointView.ui
+1
-1
No files found.
src/uas/UASWaypointManager.cc
View file @
c3c390c2
...
...
@@ -94,7 +94,7 @@ void UASWaypointManager::handleWaypoint(quint8 systemId, quint8 compId, mavlink_
if
(
wp
->
seq
==
current_wp_id
)
{
//update the UI FIXME
emit
waypointUpdated
(
uas
.
getUASID
(),
wp
->
seq
,
wp
->
x
,
wp
->
y
,
wp
->
z
,
wp
->
yaw
,
wp
->
autocontinue
,
wp
->
current
);
emit
waypointUpdated
(
uas
.
getUASID
(),
wp
->
seq
,
wp
->
x
,
wp
->
y
,
wp
->
z
,
wp
->
yaw
,
wp
->
autocontinue
,
wp
->
current
,
wp
->
orbit
,
wp
->
hold_time
);
//get next waypoint
current_wp_id
++
;
...
...
@@ -237,7 +237,8 @@ void UASWaypointManager::sendWaypoints(const QVector<Waypoint*> &list)
cur_d
->
autocontinue
=
cur_s
->
getAutoContinue
();
cur_d
->
current
=
cur_s
->
getCurrent
();
cur_d
->
orbit
=
0.1
f
;
//FIXME
cur_d
->
orbit
=
cur_s
->
getOrbit
();
cur_d
->
hold_time
=
cur_s
->
getHoldTime
();
cur_d
->
type
=
1
;
//FIXME
cur_d
->
seq
=
i
;
cur_d
->
x
=
cur_s
->
getX
();
...
...
src/uas/UASWaypointManager.h
View file @
c3c390c2
...
...
@@ -71,7 +71,7 @@ public slots:
void
sendWaypoints
(
const
QVector
<
Waypoint
*>
&
list
);
signals:
void
waypointUpdated
(
int
,
quint16
,
double
,
double
,
double
,
double
,
bool
,
bool
);
///< Adds a waypoint to the waypoint list widget
void
waypointUpdated
(
int
,
quint16
,
double
,
double
,
double
,
double
,
bool
,
bool
,
double
,
int
);
///< Adds a waypoint to the waypoint list widget
void
currentWaypointChanged
(
quint16
);
///< emits the new current waypoint sequence number
void
updateStatusString
(
const
QString
&
);
///< emits the current status string
...
...
src/ui/HSIDisplay.cc
View file @
c3c390c2
...
...
@@ -450,7 +450,7 @@ void HSIDisplay::updatePositionSetpoints(int uasid, float xDesired, float yDesir
bodyYawSet
=
yawDesired
;
mavInitialized
=
true
;
qDebug
()
<<
"Received setpoint at x: "
<<
x
<<
"metric y:"
<<
y
;
//
qDebug() << "Received setpoint at x: " << x << "metric y:" << y;
// posXSet = xDesired;
// posYSet = yDesired;
// posZSet = zDesired;
...
...
src/ui/WaypointList.cc
View file @
c3c390c2
...
...
@@ -96,7 +96,7 @@ void WaypointList::setUAS(UASInterface* uas)
this
->
uas
=
uas
;
connect
(
&
uas
->
getWaypointManager
(),
SIGNAL
(
updateStatusString
(
const
QString
&
)),
this
,
SLOT
(
updateStatusLabel
(
const
QString
&
)));
connect
(
&
uas
->
getWaypointManager
(),
SIGNAL
(
waypointUpdated
(
int
,
quint16
,
double
,
double
,
double
,
double
,
bool
,
bool
)),
this
,
SLOT
(
setWaypoint
(
int
,
quint16
,
double
,
double
,
double
,
double
,
bool
,
bool
)));
connect
(
&
uas
->
getWaypointManager
(),
SIGNAL
(
waypointUpdated
(
int
,
quint16
,
double
,
double
,
double
,
double
,
bool
,
bool
,
double
,
int
)),
this
,
SLOT
(
setWaypoint
(
int
,
quint16
,
double
,
double
,
double
,
double
,
bool
,
bool
,
double
,
int
)));
connect
(
&
uas
->
getWaypointManager
(),
SIGNAL
(
currentWaypointChanged
(
quint16
)),
this
,
SLOT
(
currentWaypointChanged
(
quint16
)));
connect
(
this
,
SIGNAL
(
sendWaypoints
(
const
QVector
<
Waypoint
*>
&
)),
&
uas
->
getWaypointManager
(),
SLOT
(
sendWaypoints
(
const
QVector
<
Waypoint
*>
&
)));
...
...
@@ -105,11 +105,11 @@ void WaypointList::setUAS(UASInterface* uas)
}
}
void
WaypointList
::
setWaypoint
(
int
uasId
,
quint16
id
,
double
x
,
double
y
,
double
z
,
double
yaw
,
bool
autocontinue
,
bool
current
)
void
WaypointList
::
setWaypoint
(
int
uasId
,
quint16
id
,
double
x
,
double
y
,
double
z
,
double
yaw
,
bool
autocontinue
,
bool
current
,
double
orbit
,
int
holdTime
)
{
if
(
uasId
==
this
->
uas
->
getUASID
())
{
Waypoint
*
wp
=
new
Waypoint
(
id
,
x
,
y
,
z
,
yaw
,
autocontinue
,
current
);
Waypoint
*
wp
=
new
Waypoint
(
id
,
x
,
y
,
z
,
yaw
,
autocontinue
,
current
,
orbit
,
holdTime
);
addWaypoint
(
wp
);
}
}
...
...
@@ -168,11 +168,11 @@ void WaypointList::add()
{
if
(
waypoints
.
size
()
>
0
)
{
addWaypoint
(
new
Waypoint
(
waypoints
.
size
(),
1.1
,
1.1
,
-
0.6
,
0.0
,
true
,
false
));
addWaypoint
(
new
Waypoint
(
waypoints
.
size
(),
1.1
,
1.1
,
-
0.6
,
0.0
,
true
,
false
,
0.1
,
2000
));
}
else
{
addWaypoint
(
new
Waypoint
(
waypoints
.
size
(),
0.0
,
0.0
,
-
0.0
,
0.0
,
true
,
true
));
addWaypoint
(
new
Waypoint
(
waypoints
.
size
(),
1.1
,
1.1
,
-
0.6
,
0.0
,
true
,
true
,
0.1
,
2000
));
}
}
}
...
...
@@ -302,7 +302,7 @@ void WaypointList::saveWaypoints()
for
(
int
i
=
0
;
i
<
waypoints
.
size
();
i
++
)
{
Waypoint
*
wp
=
waypoints
[
i
];
in
<<
"
~"
<<
wp
->
getId
()
<<
"~"
<<
wp
->
getX
()
<<
"~"
<<
wp
->
getY
()
<<
"~"
<<
wp
->
getZ
()
<<
"~"
<<
wp
->
getYaw
()
<<
"~"
<<
wp
->
getAutoContinue
()
<<
"~"
<<
wp
->
getCurrent
()
<<
"
\n
"
;
in
<<
"
\t
"
<<
wp
->
getId
()
<<
"
\t
"
<<
wp
->
getX
()
<<
"
\t
"
<<
wp
->
getY
()
<<
"
\t
"
<<
wp
->
getZ
()
<<
"
\t
"
<<
wp
->
getYaw
()
<<
"
\t
"
<<
wp
->
getAutoContinue
()
<<
"
\t
"
<<
wp
->
getCurrent
()
<<
wp
->
getOrbit
()
<<
"
\t
"
<<
wp
->
getHoldTime
()
<<
"
\n
"
;
in
.
flush
();
}
file
.
close
();
...
...
@@ -323,9 +323,9 @@ void WaypointList::loadWaypoints()
QTextStream
in
(
&
file
);
while
(
!
in
.
atEnd
())
{
QStringList
wpParams
=
in
.
readLine
().
split
(
"
~
"
);
QStringList
wpParams
=
in
.
readLine
().
split
(
"
\t
"
);
if
(
wpParams
.
size
()
==
8
)
addWaypoint
(
new
Waypoint
(
wpParams
[
1
].
toInt
(),
wpParams
[
2
].
toDouble
(),
wpParams
[
3
].
toDouble
(),
wpParams
[
4
].
toDouble
(),
wpParams
[
5
].
toDouble
(),
(
wpParams
[
6
].
toInt
()
==
1
?
true
:
false
),
(
wpParams
[
7
].
toInt
()
==
1
?
true
:
false
)));
addWaypoint
(
new
Waypoint
(
wpParams
[
1
].
toInt
(),
wpParams
[
2
].
toDouble
(),
wpParams
[
3
].
toDouble
(),
wpParams
[
4
].
toDouble
(),
wpParams
[
5
].
toDouble
(),
(
wpParams
[
6
].
toInt
()
==
1
?
true
:
false
),
(
wpParams
[
7
].
toInt
()
==
1
?
true
:
false
)
,
wpParams
[
8
].
toDouble
(),
wpParams
[
9
].
toInt
()
));
}
file
.
close
();
}
...
...
src/ui/WaypointList.h
View file @
c3c390c2
...
...
@@ -72,7 +72,7 @@ public slots:
void
currentWaypointChanged
(
quint16
seq
);
//To be moved to UASWaypointManager (?)
void
setWaypoint
(
int
uasId
,
quint16
id
,
double
x
,
double
y
,
double
z
,
double
yaw
,
bool
autocontinue
,
bool
current
);
void
setWaypoint
(
int
uasId
,
quint16
id
,
double
x
,
double
y
,
double
z
,
double
yaw
,
bool
autocontinue
,
bool
current
,
double
orbit
,
int
holdTime
);
void
addWaypoint
(
Waypoint
*
wp
);
void
removeWaypoint
(
Waypoint
*
wp
);
void
waypointReached
(
UASInterface
*
uas
,
quint16
waypointId
);
...
...
src/ui/WaypointView.cc
View file @
c3c390c2
...
...
@@ -54,7 +54,9 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
m_ui
->
yawSpinBox
->
setValue
(
wp
->
getYaw
()
/
M_PI
*
180.
);
m_ui
->
selectedBox
->
setChecked
(
wp
->
getCurrent
());
m_ui
->
autoContinue
->
setChecked
(
wp
->
getAutoContinue
());
m_ui
->
idLabel
->
setText
(
QString
(
"%1"
).
arg
(
wp
->
getId
()));
m_ui
->
idLabel
->
setText
(
QString
(
"%1"
).
arg
(
wp
->
getId
()));
\
m_ui
->
orbitSpinBox
->
setValue
(
wp
->
getOrbit
());
m_ui
->
holdTimeSpinBox
->
setValue
(
wp
->
getHoldTime
());
connect
(
m_ui
->
xSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
setX
(
double
)));
connect
(
m_ui
->
ySpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
setY
(
double
)));
...
...
@@ -70,6 +72,9 @@ WaypointView::WaypointView(Waypoint* wp, QWidget* parent) :
connect
(
m_ui
->
autoContinue
,
SIGNAL
(
stateChanged
(
int
)),
this
,
SLOT
(
changedAutoContinue
(
int
)));
connect
(
m_ui
->
selectedBox
,
SIGNAL
(
stateChanged
(
int
)),
this
,
SLOT
(
changedCurrent
(
int
)));
connect
(
m_ui
->
orbitSpinBox
,
SIGNAL
(
valueChanged
(
double
)),
wp
,
SLOT
(
setOrbit
(
double
)));
connect
(
m_ui
->
holdTimeSpinBox
,
SIGNAL
(
valueChanged
(
int
)),
wp
,
SLOT
(
setHoldTime
(
int
)));
}
void
WaypointView
::
setYaw
(
int
yawDegree
)
...
...
src/ui/WaypointView.ui
View file @
c3c390c2
...
...
@@ -323,7 +323,7 @@ QProgressBar::chunk#thrustBar {
<number>
500
</number>
</property>
<property
name=
"value"
>
<number>
200
0
</number>
<number>
0
</number>
</property>
</widget>
</item>
...
...
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