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
2bb0b1e6
Commit
2bb0b1e6
authored
Jan 13, 2012
by
QGroundControl
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #101 from Trof/offline-wplist
Offline wplist
parents
2f7de027
aa5d5043
Changes
9
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
9 changed files
with
694 additions
and
61 deletions
+694
-61
Waypoint.cc
src/Waypoint.cc
+1
-2
Waypoint.h
src/Waypoint.h
+1
-1
UASWaypointManager.cc
src/uas/UASWaypointManager.cc
+23
-7
WaypointEditableView.cc
src/ui/WaypointEditableView.cc
+55
-3
WaypointEditableView.h
src/ui/WaypointEditableView.h
+2
-1
WaypointEditableView.ui
src/ui/WaypointEditableView.ui
+36
-11
WaypointViewOnlyView.cc
src/ui/WaypointViewOnlyView.cc
+160
-36
WaypointViewOnlyView.h
src/ui/WaypointViewOnlyView.h
+1
-0
WaypointViewOnlyView.ui
src/ui/WaypointViewOnlyView.ui
+415
-0
No files found.
src/Waypoint.cc
View file @
2bb0b1e6
...
...
@@ -55,8 +55,7 @@ Waypoint::Waypoint(quint16 _id, double _x, double _y, double _z, double _param1,
}
Waypoint
::~
Waypoint
()
{
{
}
bool
Waypoint
::
isNavigationType
()
...
...
src/Waypoint.h
View file @
2bb0b1e6
...
...
@@ -188,7 +188,7 @@ public slots:
signals:
/** @brief Announces a change to the waypoint data */
void
changed
(
Waypoint
*
wp
);
void
changed
(
Waypoint
*
wp
);
};
#endif // WAYPOINT_H
src/uas/UASWaypointManager.cc
View file @
2bb0b1e6
...
...
@@ -133,11 +133,20 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui
// // qDebug() << "got waypoint count (" << count << ") from ID " << systemId;
//Clear the old edit-list before receiving the new one
if
(
read_to_edit
==
true
){
while
(
waypointsEditable
.
size
()
>
0
)
{
Waypoint
*
t
=
waypointsEditable
[
0
];
waypointsEditable
.
remove
(
0
);
delete
t
;
}
emit
waypointEditableListChanged
();
}
if
(
count
>
0
)
{
current_count
=
count
;
current_wp_id
=
0
;
current_state
=
WP_GETLIST_GETWPS
;
sendWaypointRequest
(
current_wp_id
);
}
else
{
protocol_timer
.
stop
();
...
...
@@ -149,6 +158,8 @@ void UASWaypointManager::handleWaypointCount(quint8 systemId, quint8 compId, qui
current_partner_systemid
=
0
;
current_partner_compid
=
0
;
}
}
else
{
qDebug
(
"Rejecting message, check mismatch: current_state: %d == %d, system id %d == %d, comp id %d == %d"
,
current_state
,
WP_GETLIST
,
current_partner_systemid
,
systemId
,
current_partner_compid
,
compId
);
}
...
...
@@ -766,20 +777,25 @@ void UASWaypointManager::readWaypoints(bool readToEdit)
emit
readGlobalWPFromUAS
(
true
);
if
(
current_state
==
WP_IDLE
)
{
//Clear the old view-list before receiving the new one
while
(
waypointsViewOnly
.
size
()
>
0
)
{
delete
waypointsViewOnly
.
back
();
waypointsViewOnly
.
pop_back
();
Waypoint
*
t
=
waypointsViewOnly
[
0
];
waypointsViewOnly
.
remove
(
0
);
delete
t
;
}
emit
waypointViewOnlyListChanged
();
/* THIS PART WAS MOVED TO handleWaypointCount. THE EDIT-LIST SHOULD NOT BE CLEARED UNLESS THERE IS A RESPONSE FROM UAV.
//Clear the old edit-list before receiving the new one
if (read_to_edit == true){
while(waypointsEditable.size()>0) {
delete
waypointsEditable
.
back
();
waypointsEditable
.
pop_back
();
Waypoint *t = waypointsEditable[0];
waypointsEditable.remove(0);
delete t;
}
emit waypointEditableListChanged();
}
*/
protocol_timer
.
start
(
PROTOCOL_TIMEOUT_MS
);
current_retries
=
PROTOCOL_MAX_RETRIES
;
...
...
src/ui/WaypointEditableView.cc
View file @
2bb0b1e6
...
...
@@ -20,10 +20,12 @@
#include "WaypointEditableView.h"
#include "ui_WaypointEditableView.h"
#include "ui_QGCCustomWaypointAction.h"
#include "ui_QGCMissionDoWidget.h"
WaypointEditableView
::
WaypointEditableView
(
Waypoint
*
wp
,
QWidget
*
parent
)
:
QWidget
(
parent
),
customCommand
(
new
Ui_QGCCustomWaypointAction
),
doCommand
(
new
Ui_QGCMissionDoWidget
),
viewMode
(
QGC_WAYPOINTEDITABLEVIEW_MODE_NAV
),
m_ui
(
new
Ui
::
WaypointEditableView
)
{
...
...
@@ -34,6 +36,9 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
// CUSTOM COMMAND WIDGET
customCommand
->
setupUi
(
m_ui
->
customActionWidget
);
// DO COMMAND WIDGET
//doCommand->setupUi(m_ui->customActionWidget);
// add actions
m_ui
->
comboBox_action
->
addItem
(
tr
(
"NAV: Waypoint"
),
MAV_CMD_NAV_WAYPOINT
);
...
...
@@ -43,7 +48,7 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
m_ui
->
comboBox_action
->
addItem
(
tr
(
"NAV: Loiter Turns"
),
MAV_CMD_NAV_LOITER_TURNS
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"NAV: Ret. to Launch"
),
MAV_CMD_NAV_RETURN_TO_LAUNCH
);
m_ui
->
comboBox_action
->
addItem
(
tr
(
"NAV: Land"
),
MAV_CMD_NAV_LAND
);
//
m_ui->comboBox_action->addItem(tr("NAV: Target"),MAV_CMD_NAV_TARGET);
//
m_ui->comboBox_action->addItem(tr("NAV: Target"),MAV_CMD_NAV_TARGET);
//m_ui->comboBox_action->addItem(tr("IF: Delay over"),MAV_CMD_CONDITION_DELAY);
//m_ui->comboBox_action->addItem(tr("IF: Yaw angle is"),MAV_CMD_CONDITION_YAW);
//m_ui->comboBox_action->addItem(tr("DO: Jump to Index"),MAV_CMD_DO_JUMP);
...
...
@@ -143,6 +148,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui
->
holdTimeSpinBox
->
hide
();
m_ui
->
acceptanceSpinBox
->
hide
();
m_ui
->
customActionWidget
->
hide
();
m_ui
->
missionDoWidgetSlot
->
hide
();
m_ui
->
missionConditionWidgetSlot
->
hide
();
m_ui
->
horizontalLayout
->
insertStretch
(
17
,
82
);
m_ui
->
takeOffAngleSpinBox
->
show
();
break
;
...
...
@@ -155,6 +162,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui
->
holdTimeSpinBox
->
hide
();
m_ui
->
acceptanceSpinBox
->
hide
();
m_ui
->
customActionWidget
->
hide
();
m_ui
->
missionDoWidgetSlot
->
hide
();
m_ui
->
missionConditionWidgetSlot
->
hide
();
m_ui
->
horizontalLayout
->
insertStretch
(
17
,
26
);
break
;
case
MAV_CMD_NAV_RETURN_TO_LAUNCH
:
...
...
@@ -166,6 +175,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui
->
holdTimeSpinBox
->
hide
();
m_ui
->
acceptanceSpinBox
->
hide
();
m_ui
->
customActionWidget
->
hide
();
m_ui
->
missionDoWidgetSlot
->
hide
();
m_ui
->
missionConditionWidgetSlot
->
hide
();
m_ui
->
horizontalLayout
->
insertStretch
(
17
,
26
);
break
;
case
MAV_CMD_NAV_WAYPOINT
:
...
...
@@ -174,6 +185,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui
->
turnsSpinBox
->
hide
();
m_ui
->
holdTimeSpinBox
->
show
();
m_ui
->
customActionWidget
->
hide
();
m_ui
->
missionDoWidgetSlot
->
hide
();
m_ui
->
missionConditionWidgetSlot
->
hide
();
m_ui
->
horizontalLayout
->
insertStretch
(
17
,
1
);
m_ui
->
autoContinue
->
show
();
...
...
@@ -188,6 +201,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui
->
holdTimeSpinBox
->
hide
();
m_ui
->
acceptanceSpinBox
->
hide
();
m_ui
->
customActionWidget
->
hide
();
m_ui
->
missionDoWidgetSlot
->
hide
();
m_ui
->
missionConditionWidgetSlot
->
hide
();
m_ui
->
horizontalLayout
->
insertStretch
(
17
,
25
);
m_ui
->
orbitSpinBox
->
show
();
break
;
...
...
@@ -198,6 +213,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui
->
holdTimeSpinBox
->
hide
();
m_ui
->
acceptanceSpinBox
->
hide
();
m_ui
->
customActionWidget
->
hide
();
m_ui
->
missionDoWidgetSlot
->
hide
();
m_ui
->
missionConditionWidgetSlot
->
hide
();
m_ui
->
horizontalLayout
->
insertStretch
(
17
,
20
);
m_ui
->
orbitSpinBox
->
show
();
m_ui
->
turnsSpinBox
->
show
();
...
...
@@ -209,6 +226,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui
->
autoContinue
->
hide
();
m_ui
->
acceptanceSpinBox
->
hide
();
m_ui
->
customActionWidget
->
hide
();
m_ui
->
missionDoWidgetSlot
->
hide
();
m_ui
->
missionConditionWidgetSlot
->
hide
();
m_ui
->
horizontalLayout
->
insertStretch
(
17
,
20
);
m_ui
->
orbitSpinBox
->
show
();
m_ui
->
holdTimeSpinBox
->
show
();
...
...
@@ -219,7 +238,8 @@ void WaypointEditableView::updateActionView(int action)
// m_ui->turnsSpinBox->hide();
// m_ui->holdTimeSpinBox->show();
// m_ui->customActionWidget->hide();
// m_ui->missionDoWidgetSlot->hide();
// m_ui->missionConditionWidgetSlot->hide();
// m_ui->autoContinue->show();
// m_ui->acceptanceSpinBox->hide();
// m_ui->yawSpinBox->hide();
...
...
@@ -260,6 +280,11 @@ void WaypointEditableView::changedAction(int index)
// Update view
updateActionView
(
actionIndex
);
break
;
case
MAV_CMD_DO_JUMP
:
{
changeViewMode
(
QGC_WAYPOINTEDITABLEVIEW_MODE_DO
);
break
;
}
case
MAV_CMD_ENUM_END
:
default:
// Switch to mission frame
...
...
@@ -276,9 +301,32 @@ void WaypointEditableView::changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE mode)
case
QGC_WAYPOINTEDITABLEVIEW_MODE_CONDITION
:
// Hide everything, show condition widget
// TODO
break
;
case
QGC_WAYPOINTEDITABLEVIEW_MODE_DO
:
{
// Hide almost everything
m_ui
->
orbitSpinBox
->
hide
();
m_ui
->
takeOffAngleSpinBox
->
hide
();
m_ui
->
yawSpinBox
->
hide
();
m_ui
->
turnsSpinBox
->
hide
();
m_ui
->
holdTimeSpinBox
->
hide
();
m_ui
->
acceptanceSpinBox
->
hide
();
m_ui
->
posDSpinBox
->
hide
();
m_ui
->
posESpinBox
->
hide
();
m_ui
->
posNSpinBox
->
hide
();
m_ui
->
latSpinBox
->
hide
();
m_ui
->
lonSpinBox
->
hide
();
m_ui
->
altSpinBox
->
hide
();
// Show action widget
if
(
!
m_ui
->
missionDoWidgetSlot
->
isVisible
())
{
m_ui
->
missionDoWidgetSlot
->
show
();
}
if
(
!
m_ui
->
autoContinue
->
isVisible
())
{
m_ui
->
autoContinue
->
show
();
}
break
;
}
case
QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING
:
// Hide almost everything
m_ui
->
orbitSpinBox
->
hide
();
...
...
@@ -325,6 +373,8 @@ void WaypointEditableView::updateFrameView(int frame)
// Coordinate frame
m_ui
->
comboBox_frame
->
show
();
m_ui
->
customActionWidget
->
hide
();
m_ui
->
missionDoWidgetSlot
->
hide
();
m_ui
->
missionConditionWidgetSlot
->
hide
();
}
else
// do not hide customActionWidget if Command is set to "Other"
{
...
...
@@ -343,6 +393,8 @@ void WaypointEditableView::updateFrameView(int frame)
// Coordinate frame
m_ui
->
comboBox_frame
->
show
();
m_ui
->
customActionWidget
->
hide
();
m_ui
->
missionDoWidgetSlot
->
hide
();
m_ui
->
missionConditionWidgetSlot
->
hide
();
}
else
// do not hide customActionWidget if Command is set to "Other"
{
...
...
@@ -493,7 +545,7 @@ void WaypointEditableView::updateValues()
if
(
m_ui
->
posDSpinBox
->
value
()
!=
wp
->
getZ
())
{
m_ui
->
posDSpinBox
->
setValue
(
wp
->
getZ
());
}
}
}
break
;
case
MAV_FRAME_GLOBAL
:
case
MAV_FRAME_GLOBAL_RELATIVE_ALT
:
{
...
...
src/ui/WaypointEditableView.h
View file @
2bb0b1e6
...
...
@@ -49,7 +49,7 @@ namespace Ui
class
WaypointEditableView
;
}
class
Ui_QGCCustomWaypointAction
;
class
Ui_QGCMissionDoWidget
;
class
WaypointEditableView
:
public
QWidget
{
Q_OBJECT
...
...
@@ -84,6 +84,7 @@ protected:
// Special widgets extendending the
// waypoint view to mission capabilities
Ui_QGCCustomWaypointAction
*
customCommand
;
Ui_QGCMissionDoWidget
*
doCommand
;
QGC_WAYPOINTEDITABLEVIEW_MODE
viewMode
;
private:
...
...
src/ui/WaypointEditableView.ui
View file @
2bb0b1e6
...
...
@@ -7,7 +7,7 @@
<x>
0
</x>
<y>
0
</y>
<width>
2208
</width>
<height>
3
9
</height>
<height>
3
7
</height>
</rect>
</property>
<property
name=
"sizePolicy"
>
...
...
@@ -96,7 +96,7 @@ QPushButton:pressed {
<property
name=
"title"
>
<string/>
</property>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
stretch=
"5,5,5,5,50,50,50,50,50,50,5,20,20,5,10,10,
1
0,20,5,5,5,5"
>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
stretch=
"5,5,5,5,50,50,50,50,50,50,5,20,20,5,10,10,
0,0,
0,20,5,5,5,5"
>
<property
name=
"spacing"
>
<number>
2
</number>
</property>
...
...
@@ -121,10 +121,10 @@ QPushButton:pressed {
<enum>
Qt::TabFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Currently selected waypoin
t
</string>
<string>
Mission Star
t
</string>
</property>
<property
name=
"statusTip"
>
<string>
Currently selected waypoin
t
</string>
<string>
Mission Star
t
</string>
</property>
<property
name=
"text"
>
<string/>
...
...
@@ -465,16 +465,16 @@ QPushButton:pressed {
<enum>
Qt::StrongFocus
</enum>
</property>
<property
name=
"toolTip"
>
<string>
Loiter radius
</string>
<string>
Loiter radius
. Negative for counter-clockwise
</string>
</property>
<property
name=
"statusTip"
>
<string>
Loiter radius
</string>
<string>
Loiter radius
. Negative for counter-clockwise
</string>
</property>
<property
name=
"suffix"
>
<string>
m
</string>
</property>
<property
name=
"minimum"
>
<double>
0.05
0000000000000
</double>
<double>
-5000.00
0000000000000
</double>
</property>
<property
name=
"maximum"
>
<double>
5000.000000000000000
</double>
...
...
@@ -519,11 +519,10 @@ where to accept this waypoint as reached</string>
</sizepolicy>
</property>
<property
name=
"toolTip"
>
<string>
Rotaty wing and ground vehicles only:
Time to stay at this position before advancing
</string>
<string>
Time to stay/loiter at this position before advancing
</string>
</property>
<property
name=
"statusTip"
>
<string>
Rotaty wing and ground vehicles only: Time to stay
at this position before advancing
</string>
<string>
Time to stay/loiter
at this position before advancing
</string>
</property>
<property
name=
"suffix"
>
<string>
s
</string>
...
...
@@ -595,7 +594,33 @@ Time to stay at this position before advancing</string>
<item>
<widget
class=
"QWidget"
name=
"customActionWidget"
native=
"true"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"Expanding"
vsizetype=
"Preferred"
>
<sizepolicy
hsizetype=
"MinimumExpanding"
vsizetype=
"Preferred"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
<property
name=
"minimumSize"
>
<size>
<width>
0
</width>
<height>
0
</height>
</size>
</property>
</widget>
</item>
<item>
<widget
class=
"QWidget"
name=
"missionDoWidgetSlot"
native=
"true"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"MinimumExpanding"
vsizetype=
"Preferred"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
</property>
</widget>
</item>
<item>
<widget
class=
"QWidget"
name=
"missionConditionWidgetSlot"
native=
"true"
>
<property
name=
"sizePolicy"
>
<sizepolicy
hsizetype=
"MinimumExpanding"
vsizetype=
"Preferred"
>
<horstretch>
0
</horstretch>
<verstretch>
0
</verstretch>
</sizepolicy>
...
...
src/ui/WaypointViewOnlyView.cc
View file @
2bb0b1e6
This diff is collapsed.
Click to expand it.
src/ui/WaypointViewOnlyView.h
View file @
2bb0b1e6
...
...
@@ -31,6 +31,7 @@ protected:
Waypoint
*
wp
;
private:
void
hightlightDesiredCurrent
(
bool
hightlight_on
);
Ui
::
WaypointViewOnlyView
*
m_ui
;
};
...
...
src/ui/WaypointViewOnlyView.ui
View file @
2bb0b1e6
This diff is collapsed.
Click to expand it.
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