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
37dfd9c1
Commit
37dfd9c1
authored
Oct 18, 2015
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #2026 from DonLakeFlyer/MoreEditing
More editor changes
parents
a0680746
0911ffed
Changes
7
Show whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
291 additions
and
125 deletions
+291
-125
qgroundcontrol.qrc
qgroundcontrol.qrc
+1
-0
MissionEditor.qml
src/MissionEditor/MissionEditor.qml
+145
-102
MissionEditorController.cc
src/MissionEditor/MissionEditorController.cc
+115
-9
MissionEditorController.h
src/MissionEditor/MissionEditorController.h
+18
-6
MissionItem.cc
src/MissionItem.cc
+8
-4
MissionItemEditor.qml
src/QmlControls/MissionItemEditor.qml
+1
-1
MainToolBar.qml
src/ui/toolbar/MainToolBar.qml
+3
-3
No files found.
qgroundcontrol.qrc
View file @
37dfd9c1
...
...
@@ -65,6 +65,7 @@
<file alias="airplaneOpaque.svg">src/FlightMap/Images/airplaneOpaque.svg</file>
<file alias="ZoomPlus.svg">src/FlightMap/Images/ZoomPlus.svg</file>
<file alias="ZoomMinus.svg">src/FlightMap/Images/ZoomMinus.svg</file>
<file alias="TrashDelete.svg">src/FlightMap/Images/TrashDelete.svg</file>
<!-- Map Buttons -->
<file alias="Help.svg">src/FlightMap/Images/Help.svg</file>
...
...
src/MissionEditor/MissionEditor.qml
View file @
37dfd9c1
...
...
@@ -43,7 +43,7 @@ QGCView {
// zOrder comes from the Loader in MainWindow.qml
z
:
zOrder
readonly
property
int
_decimalPlaces
:
7
readonly
property
int
_decimalPlaces
:
8
readonly
property
real
_horizontalMargin
:
ScreenTools
.
defaultFontPixelWidth
/
2
readonly
property
real
_margin
:
ScreenTools
.
defaultFontPixelHeight
/
2
readonly
property
var
_activeVehicle
:
multiVehicleManager
.
activeVehicle
...
...
@@ -51,21 +51,33 @@ QGCView {
readonly
property
real
_rightPanelWidth
:
ScreenTools
.
defaultFontPixelWidth
*
30
readonly
property
real
_rightPanelOpacity
:
0.8
readonly
property
int
_toolButtonCount
:
6
readonly
property
string
_autoSyncKey
:
"
AutoSync
"
readonly
property
int
_addMissionItemsButtonAutoOffTimeout
:
10000
property
var
_missionItems
:
_
controller
.
missionItems
property
var
_missionItems
:
controller
.
missionItems
property
var
_homePositionManager
:
QGroundControl
.
homePositionManager
property
string
_homePositionName
:
_homePositionManager
.
homePositions
.
get
(
0
).
name
property
var
offlineHomePosition
:
_homePositionManager
.
homePositions
.
get
(
0
).
coordinate
property
var
liveHomePosition
:
_
controller
.
liveHomePosition
property
var
liveHomePositionAvailable
:
_
controller
.
liveHomePositionAvailable
property
var
liveHomePosition
:
controller
.
liveHomePosition
property
var
liveHomePositionAvailable
:
controller
.
liveHomePositionAvailable
property
var
homePosition
:
offlineHomePosition
// live or offline depending on state
property
bool
_syncNeeded
:
_controller
.
missionItems
.
dirty
property
bool
_syncNeeded
:
controller
.
missionItems
.
dirty
property
bool
_syncInProgress
:
_activeVehicle
?
_activeVehicle
.
missionManager
.
inProgress
:
false
MissionEditorController
{
id
:
_controller
}
MissionEditorController
{
id
:
controller
autoSync
:
QGroundControl
.
flightMapSettings
.
loadMapSetting
(
editorMap
.
mapName
,
_autoSyncKey
,
true
)
onAutoSyncChanged
:
QGroundControl
.
flightMapSettings
.
saveMapSetting
(
editorMap
.
mapName
,
_autoSyncKey
,
autoSync
)
onMissionItemsChanged
:
{
updateHomePosition
()
itemEditor
.
clearItem
()
}
}
QGCPalette
{
id
:
qgcPal
;
colorGroupEnabled
:
enabled
}
...
...
@@ -85,10 +97,7 @@ QGCView {
function
updateHomePosition
()
{
homePosition
=
liveHomePositionAvailable
?
liveHomePosition
:
offlineHomePosition
// Changing the coordinate will set the dirty bit, so we save and reset it
var
dirtyBit
=
_missionItems
.
dirty
_missionItems
.
get
(
0
).
coordinate
=
homePosition
_missionItems
.
dirty
=
dirtyBit
}
Component.onCompleted
:
updateHomePosition
()
...
...
@@ -96,13 +105,6 @@ QGCView {
onLiveHomePositionAvailableChanged
:
updateHomePosition
()
onLiveHomePositionChanged
:
updateHomePosition
()
Connections
{
target
:
_controller
// When the mission items change _missionsItems[0] changes as well so we need to reset it to home
onMissionItemsChanged
:
updateHomePosition
}
QGCViewPanel
{
id
:
panel
anchors.fill
:
parent
...
...
@@ -154,7 +156,7 @@ QGCView {
if
(
homePositionManagerButton
.
checked
)
{
offlineHomePosition
=
coordinate
}
else
if
(
addMissionItemsButton
.
checked
)
{
var
index
=
_
controller
.
addMissionItem
(
coordinate
)
var
index
=
controller
.
addMissionItem
(
coordinate
)
addMissionItemsButtonAutoOffTimer
.
start
()
setCurrentItem
(
index
)
}
else
{
...
...
@@ -177,6 +179,12 @@ QGCView {
property
var
missionItemIndicator
property
real
heading
:
missionItem
?
missionItem
.
heading
:
0
function
clearItem
()
{
itemEditor
.
visible
=
false
itemEditor
.
missionItem
=
undefined
itemEditor
.
missionItemIndicator
=
undefined
}
Drag.active
:
itemDrag
.
drag
.
active
Drag.hotSpot.x
:
width
/
2
Drag.hotSpot.y
:
height
/
2
...
...
@@ -206,7 +214,7 @@ QGCView {
// Add the mission items to the map
MapItemView
{
model
:
_
controller
.
missionItems
model
:
controller
.
missionItems
delegate
:
MissionItemIndicator
{
...
...
@@ -230,9 +238,7 @@ QGCView {
itemEditor
.
missionItem
=
Qt
.
binding
(
function
()
{
return
object
})
itemEditor
.
missionItemIndicator
=
Qt
.
binding
(
function
()
{
return
itemIndicator
})
}
else
{
itemEditor
.
visible
=
false
itemEditor
.
missionItem
=
undefined
itemEditor
.
missionItemIndicator
=
undefined
itemEditor
.
clearItem
()
}
// Zoom the map and move to the new position
...
...
@@ -270,7 +276,7 @@ QGCView {
// Add lines between waypoints
MapItemView
{
model
:
_
controller
.
waypointLines
model
:
controller
.
waypointLines
delegate
:
MapPolyline
{
...
...
@@ -301,7 +307,7 @@ QGCView {
anchors.fill
:
parent
spacing
:
_margin
/
2
orientation
:
ListView
.
Vertical
model
:
_controller
.
canEdit
?
_
controller
.
missionItems
:
0
model
:
controller
.
canEdit
?
controller
.
missionItems
:
0
property
real
_maxItemHeight
:
0
...
...
@@ -315,7 +321,7 @@ QGCView {
onRemove
:
{
var
newCurrentItem
=
object
.
sequenceNumber
-
1
_
controller
.
removeMissionItem
(
object
.
sequenceNumber
)
controller
.
removeMissionItem
(
object
.
sequenceNumber
)
if
(
_missionItems
.
count
>
1
)
{
newCurrentItem
=
Math
.
min
(
_missionItems
.
count
-
1
,
newCurrentItem
)
setCurrentItem
(
newCurrentItem
)
...
...
@@ -326,7 +332,7 @@ QGCView {
QGCLabel
{
anchors.fill
:
parent
visible
:
!
_
controller
.
canEdit
visible
:
!
controller
.
canEdit
wrapMode
:
Text
.
WordWrap
text
:
"
The set of mission items you have loaded cannot be edited by QGroundControl.
"
+
"
You will only be able to save these to a file, or send them to a vehicle.
"
...
...
@@ -756,6 +762,7 @@ QGCView {
y
:
(
parent
.
height
-
(
_toolButtonCount
*
height
)
-
((
_toolButtonCount
-
1
)
*
_margin
))
/
2
buttonImage
:
"
/qmlimages/MapAddMission.svg
"
exclusiveGroup
:
_dropButtonsExclusiveGroup
z
:
editorMap
.
zOrderWidgets
onCheckedChanged
:
{
if
(
checked
)
{
...
...
@@ -775,10 +782,26 @@ QGCView {
}
RoundButton
{
id
:
homePositionManager
Button
id
:
deleteMissionItem
Button
anchors.margins
:
_margin
anchors.left
:
parent
.
left
anchors.top
:
addMissionItemsButton
.
bottom
buttonImage
:
"
/qmlimages/TrashDelete.svg
"
exclusiveGroup
:
_dropButtonsExclusiveGroup
z
:
editorMap
.
zOrderWidgets
onClicked
:
{
itemEditor
.
clearItem
()
controller
.
deleteCurrentMissionItem
()
checked
=
false
}
}
RoundButton
{
id
:
homePositionManagerButton
anchors.margins
:
_margin
anchors.left
:
parent
.
left
anchors.top
:
deleteMissionItemButton
.
bottom
buttonImage
:
"
/qmlimages/MapHome.svg
"
exclusiveGroup
:
_dropButtonsExclusiveGroup
z
:
editorMap
.
zOrderWidgets
...
...
@@ -838,8 +861,65 @@ QGCView {
viewportMargins
:
ScreenTools
.
defaultFontPixelWidth
/
2
exclusiveGroup
:
_dropButtonsExclusiveGroup
z
:
editorMap
.
zOrderWidgets
dropDownComponent
:
syncDropDownComponent
enabled
:
!
_syncInProgress
}
DropButton
{
id
:
mapTypeButton
anchors.margins
:
_margin
anchors.left
:
parent
.
left
anchors.top
:
syncButton
.
bottom
dropDirection
:
dropRight
buttonImage
:
"
/qmlimages/MapType.svg
"
viewportMargins
:
ScreenTools
.
defaultFontPixelWidth
/
2
exclusiveGroup
:
_dropButtonsExclusiveGroup
z
:
editorMap
.
zOrderWidgets
dropDownComponent
:
Component
{
Column
{
QGCLabel
{
text
:
"
Map type:
"
}
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
Repeater
{
model
:
QGroundControl
.
flightMapSettings
.
mapTypes
QGCButton
{
checkable
:
true
checked
:
editorMap
.
mapType
==
text
text
:
modelData
exclusiveGroup
:
_mapTypeButtonsExclusiveGroup
onClicked
:
{
editorMap
.
mapType
=
text
checked
=
true
mapTypeButton
.
hideDropDown
()
}
}
}
}
}
}
}
RoundButton
{
id
:
helpButton
anchors.margins
:
_margin
anchors.left
:
parent
.
left
anchors.top
:
mapTypeButton
.
bottom
buttonImage
:
"
/qmlimages/Help.svg
"
exclusiveGroup
:
_dropButtonsExclusiveGroup
z
:
editorMap
.
zOrderWidgets
}
}
// FlightMap
}
// Item - split view container
}
// QGCViewPanel
Component
{
id
:
syncDropDownComponent
Column
{
id
:
columnHolder
spacing
:
_margin
...
...
@@ -847,12 +927,13 @@ QGCView {
QGCLabel
{
width
:
columnHolder
.
width
wrapMode
:
Text
.
WordWrap
text
:
_syncNeeded
?
text
:
_syncNeeded
&&
!
controller
.
autoSync
?
"
You have unsaved changed to you mission. You should send to your vehicle, or save to a file:
"
:
"
Sync:
"
}
Row
{
visible
:
autoSyncCheckBox
.
enabled
&&
autoSyncCheckBox
.
checked
spacing
:
ScreenTools
.
defaultFontPixelWidth
QGCButton
{
...
...
@@ -861,7 +942,7 @@ QGCView {
onClicked
:
{
syncButton
.
hideDropDown
()
_controller
.
set
MissionItems
()
controller
.
send
MissionItems
()
}
}
...
...
@@ -871,7 +952,7 @@ QGCView {
onClicked
:
{
syncButton
.
hideDropDown
()
_
controller
.
getMissionItems
()
controller
.
getMissionItems
()
}
}
}
...
...
@@ -884,7 +965,7 @@ QGCView {
onClicked
:
{
syncButton
.
hideDropDown
()
_
controller
.
saveMissionToFile
()
controller
.
saveMissionToFile
()
}
}
...
...
@@ -893,63 +974,25 @@ QGCView {
onClicked
:
{
syncButton
.
hideDropDown
()
_controller
.
loadMissionFromFile
()
}
}
controller
.
loadMissionFromFile
()
}
}
}
}
DropButton
{
id
:
mapTypeButton
anchors.margins
:
_margin
anchors.left
:
parent
.
left
anchors.top
:
syncButton
.
bottom
dropDirection
:
dropRight
buttonImage
:
"
/qmlimages/MapType.svg
"
viewportMargins
:
ScreenTools
.
defaultFontPixelWidth
/
2
exclusiveGroup
:
_dropButtonsExclusiveGroup
z
:
editorMap
.
zOrderWidgets
dropDownComponent
:
Component
{
Column
{
QGCLabel
{
text
:
"
Map type:
"
}
Row
{
spacing
:
ScreenTools
.
defaultFontPixelWidth
QGCLabel
{
id
:
autoSyncDisallowedLabel
visible
:
_activeVehicle
&&
_activeVehicle
.
armed
text
:
"
AutoSync is not allowed whie vehicle is armed
"
}
Repeater
{
model
:
QGroundControl
.
flightMapSettings
.
mapTypes
QGCCheckBox
{
id
:
autoSyncCheckBox
checked
:
controller
.
autoSync
text
:
"
Automatically sync changes with vehicle
"
enabled
:
_activeVehicle
?
!
_activeVehicle
.
armed
:
false
QGCButton
{
checkable
:
true
checked
:
editorMap
.
mapType
==
text
text
:
modelData
exclusiveGroup
:
_mapTypeButtonsExclusiveGroup
onClicked
:
{
editorMap
.
mapType
=
text
checked
=
true
mapTypeButton
.
hideDropDown
()
}
onClicked
:
controller
.
autoSync
=
checked
}
}
}
}
}
}
RoundButton
{
id
:
helpButton
anchors.margins
:
_margin
anchors.left
:
parent
.
left
anchors.top
:
mapTypeButton
.
bottom
buttonImage
:
"
/qmlimages/Help.svg
"
exclusiveGroup
:
_dropButtonsExclusiveGroup
z
:
editorMap
.
zOrderWidgets
}
}
// FlightMap
}
// Item - split view container
}
// QGCViewPanel
}
// QGCVIew
src/MissionEditor/MissionEditorController.cc
View file @
37dfd9c1
...
...
@@ -27,6 +27,7 @@ This file is part of the QGROUNDCONTROL project
#include "MissionManager.h"
#include "QGCFileDialog.h"
#include "CoordinateVector.h"
#include "QGCMessageBox.h"
#include <QQmlContext>
#include <QQmlEngine>
...
...
@@ -40,6 +41,9 @@ MissionEditorController::MissionEditorController(QWidget *parent)
,
_canEdit
(
true
)
,
_activeVehicle
(
NULL
)
,
_liveHomePositionAvailable
(
false
)
,
_autoSync
(
false
)
,
_firstMissionItemSync
(
false
)
,
_expectingNewMissionItems
(
false
)
{
MultiVehicleManager
*
multiVehicleMgr
=
MultiVehicleManager
::
instance
();
...
...
@@ -47,9 +51,6 @@ MissionEditorController::MissionEditorController(QWidget *parent)
Vehicle
*
activeVehicle
=
multiVehicleMgr
->
activeVehicle
();
if
(
activeVehicle
)
{
MissionManager
*
missionManager
=
activeVehicle
->
missionManager
();
connect
(
missionManager
,
&
MissionManager
::
newMissionItemsAvailable
,
this
,
&
MissionEditorController
::
_newMissionItemsAvailable
);
_newMissionItemsAvailable
();
_activeVehicleChanged
(
activeVehicle
);
}
else
{
_missionItems
=
new
QmlObjectListModel
(
this
);
...
...
@@ -63,6 +64,29 @@ MissionEditorController::~MissionEditorController()
void
MissionEditorController
::
_newMissionItemsAvailable
(
void
)
{
if
(
_firstMissionItemSync
||
!
_expectingNewMissionItems
)
{
// This is the first time the vehicle is seeing items. We have to be careful of transitioning from offline
// to online. Other case is an unexpected set of new items from the vehicle.
_firstMissionItemSync
=
false
;
if
(
_missionItems
&&
_missionItems
->
count
()
>
1
)
{
QGCMessageBox
::
StandardButton
button
=
QGCMessageBox
::
warning
(
"Mission Editing"
,
"The vehicle has sent a new set of Mission Items. "
"Do you want to discard your current set of unsaved items and use the ones from the vehicle instead?"
,
QGCMessageBox
::
Yes
|
QGCMessageBox
::
No
,
QGCMessageBox
::
No
);
if
(
button
==
QGCMessageBox
::
No
)
{
return
;
}
}
}
else
if
(
_autoSync
)
{
// When we are running autoSync we assume the MissionManager is notifying us about the
// items we just sent to it. We keep our own edit list, instead of resetting.
return
;
}
_expectingNewMissionItems
=
false
;
if
(
_missionItems
)
{
_deinitAllMissionItems
();
_missionItems
->
deleteLater
();
...
...
@@ -81,15 +105,15 @@ void MissionEditorController::getMissionItems(void)
Vehicle
*
activeVehicle
=
MultiVehicleManager
::
instance
()
->
activeVehicle
();
if
(
activeVehicle
)
{
_expectingNewMissionItems
=
true
;
MissionManager
*
missionManager
=
activeVehicle
->
missionManager
();
connect
(
missionManager
,
&
MissionManager
::
newMissionItemsAvailable
,
this
,
&
MissionEditorController
::
_newMissionItemsAvailable
);
activeVehicle
->
missionManager
()
->
requestMissionItems
();
}
}
void
MissionEditorController
::
se
t
MissionItems
(
void
)
void
MissionEditorController
::
se
nd
MissionItems
(
void
)
{
// FIXME: Need to pull out home position
Vehicle
*
activeVehicle
=
MultiVehicleManager
::
instance
()
->
activeVehicle
();
if
(
activeVehicle
)
{
...
...
@@ -131,6 +155,16 @@ void MissionEditorController::removeMissionItem(int index)
_deinitMissionItem
(
item
);
_recalcAll
();
// Set the new current item
if
(
index
>=
_missionItems
->
count
())
{
index
--
;
}
for
(
int
i
=
0
;
i
<
_missionItems
->
count
();
i
++
)
{
MissionItem
*
item
=
qobject_cast
<
MissionItem
*>
(
_missionItems
->
get
(
i
));
item
->
setIsCurrentItem
(
i
==
index
);
}
}
void
MissionEditorController
::
loadMissionFromFile
(
void
)
...
...
@@ -306,6 +340,8 @@ void MissionEditorController::_initAllMissionItems(void)
emit
canEditChanged
(
_canEdit
);
_missionItems
->
setDirty
(
false
);
connect
(
_missionItems
,
&
QmlObjectListModel
::
dirtyChanged
,
this
,
&
MissionEditorController
::
_dirtyChanged
);
}
void
MissionEditorController
::
_deinitAllMissionItems
(
void
)
...
...
@@ -313,6 +349,8 @@ void MissionEditorController::_deinitAllMissionItems(void)
for
(
int
i
=
0
;
i
<
_missionItems
->
count
();
i
++
)
{
_deinitMissionItem
(
qobject_cast
<
MissionItem
*>
(
_missionItems
->
get
(
i
)));
}
connect
(
_missionItems
,
&
QmlObjectListModel
::
dirtyChanged
,
this
,
&
MissionEditorController
::
_dirtyChanged
);
}
void
MissionEditorController
::
_initMissionItem
(
MissionItem
*
item
)
...
...
@@ -345,6 +383,10 @@ void MissionEditorController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_C
void
MissionEditorController
::
_activeVehicleChanged
(
Vehicle
*
activeVehicle
)
{
if
(
_activeVehicle
)
{
MissionManager
*
missionManager
=
_activeVehicle
->
missionManager
();
disconnect
(
missionManager
,
&
MissionManager
::
newMissionItemsAvailable
,
this
,
&
MissionEditorController
::
_newMissionItemsAvailable
);
disconnect
(
missionManager
,
&
MissionManager
::
inProgressChanged
,
this
,
&
MissionEditorController
::
_inProgressChanged
);
disconnect
(
_activeVehicle
,
&
Vehicle
::
homePositionAvailableChanged
,
this
,
&
MissionEditorController
::
_activeVehicleHomePositionAvailableChanged
);
disconnect
(
_activeVehicle
,
&
Vehicle
::
homePositionChanged
,
this
,
&
MissionEditorController
::
_activeVehicleHomePositionChanged
);
_activeVehicle
=
NULL
;
...
...
@@ -354,10 +396,23 @@ void MissionEditorController::_activeVehicleChanged(Vehicle* activeVehicle)
_activeVehicle
=
activeVehicle
;
if
(
_activeVehicle
)
{
MissionManager
*
missionManager
=
activeVehicle
->
missionManager
();
connect
(
missionManager
,
&
MissionManager
::
newMissionItemsAvailable
,
this
,
&
MissionEditorController
::
_newMissionItemsAvailable
);
connect
(
missionManager
,
&
MissionManager
::
inProgressChanged
,
this
,
&
MissionEditorController
::
_inProgressChanged
);
connect
(
_activeVehicle
,
&
Vehicle
::
homePositionAvailableChanged
,
this
,
&
MissionEditorController
::
_activeVehicleHomePositionAvailableChanged
);
connect
(
_activeVehicle
,
&
Vehicle
::
homePositionChanged
,
this
,
&
MissionEditorController
::
_activeVehicleHomePositionChanged
);
_activeVehicleHomePositionChanged
(
_activeVehicle
->
homePosition
());
_activeVehicleHomePositionAvailableChanged
(
_activeVehicle
->
homePositionAvailable
());
if
(
missionManager
->
inProgress
())
{
// Vehicle is still in process of requesting mission items
_firstMissionItemSync
=
true
;
}
else
{
// Vehicle already has mission items
_firstMissionItemSync
=
false
;
_newMissionItemsAvailable
();
}
}
}
...
...
@@ -372,3 +427,54 @@ void MissionEditorController::_activeVehicleHomePositionChanged(const QGeoCoordi
_liveHomePosition
=
homePosition
;
emit
liveHomePositionChanged
(
_liveHomePosition
);
}
void
MissionEditorController
::
deleteCurrentMissionItem
(
void
)
{
for
(
int
i
=
0
;
i
<
_missionItems
->
count
();
i
++
)
{
MissionItem
*
item
=
qobject_cast
<
MissionItem
*>
(
_missionItems
->
get
(
i
));
if
(
item
->
isCurrentItem
()
&&
i
!=
0
)
{
removeMissionItem
(
i
);
return
;
}
}
}
void
MissionEditorController
::
setAutoSync
(
bool
autoSync
)
{
_autoSync
=
autoSync
;
emit
autoSyncChanged
(
_autoSync
);
if
(
_autoSync
)
{
_dirtyChanged
(
true
);
}
}
void
MissionEditorController
::
_dirtyChanged
(
bool
dirty
)
{
if
(
dirty
&&
_autoSync
)
{
Vehicle
*
activeVehicle
=
MultiVehicleManager
::
instance
()
->
activeVehicle
();
if
(
activeVehicle
&&
!
activeVehicle
->
armed
())
{
if
(
_activeVehicle
->
missionManager
()
->
inProgress
())
{
_queuedSend
=
true
;
}
else
{
_autoSyncSend
();
}
}
}
}
void
MissionEditorController
::
_autoSyncSend
(
void
)
{
qDebug
()
<<
"Auto-syncing with vehicle"
;
_queuedSend
=
false
;
sendMissionItems
();
_missionItems
->
setDirty
(
false
);
}
void
MissionEditorController
::
_inProgressChanged
(
bool
inProgress
)
{
if
(
!
inProgress
&&
_queuedSend
)
{
_autoSyncSend
();
}
}
src/MissionEditor/MissionEditorController.h
View file @
37dfd9c1
...
...
@@ -42,13 +42,15 @@ public:
Q_PROPERTY
(
bool
canEdit
READ
canEdit
NOTIFY
canEditChanged
)
Q_PROPERTY
(
bool
liveHomePositionAvailable
READ
liveHomePositionAvailable
NOTIFY
liveHomePositionAvailableChanged
)
Q_PROPERTY
(
QGeoCoordinate
liveHomePosition
READ
liveHomePosition
NOTIFY
liveHomePositionChanged
)
Q_PROPERTY
(
bool
autoSync
READ
autoSync
WRITE
setAutoSync
NOTIFY
autoSyncChanged
)
Q_INVOKABLE
int
addMissionItem
(
QGeoCoordinate
coordinate
);
Q_INVOKABLE
void
getMissionItems
(
void
);
Q_INVOKABLE
void
se
t
MissionItems
(
void
);
Q_INVOKABLE
void
se
nd
MissionItems
(
void
);
Q_INVOKABLE
void
loadMissionFromFile
(
void
);
Q_INVOKABLE
void
saveMissionToFile
(
void
);
Q_INVOKABLE
void
removeMissionItem
(
int
index
);
Q_INVOKABLE
void
deleteCurrentMissionItem
(
void
);
// Property accessors
...
...
@@ -57,6 +59,8 @@ public:
bool
canEdit
(
void
)
{
return
_canEdit
;
}
bool
liveHomePositionAvailable
(
void
)
{
return
_liveHomePositionAvailable
;
}
QGeoCoordinate
liveHomePosition
(
void
)
{
return
_liveHomePosition
;
}
bool
autoSync
(
void
)
{
return
_autoSync
;
}
void
setAutoSync
(
bool
autoSync
);
signals:
void
missionItemsChanged
(
void
);
...
...
@@ -64,6 +68,7 @@ signals:
void
waypointLinesChanged
(
void
);
void
liveHomePositionAvailableChanged
(
bool
homePositionAvailable
);
void
liveHomePositionChanged
(
const
QGeoCoordinate
&
homePosition
);
void
autoSyncChanged
(
bool
autoSync
);
private
slots
:
void
_newMissionItemsAvailable
();
...
...
@@ -72,6 +77,8 @@ private slots:
void
_activeVehicleChanged
(
Vehicle
*
activeVehicle
);
void
_activeVehicleHomePositionAvailableChanged
(
bool
homePositionAvailable
);
void
_activeVehicleHomePositionChanged
(
const
QGeoCoordinate
&
homePosition
);
void
_dirtyChanged
(
bool
dirty
);
void
_inProgressChanged
(
bool
inProgress
);
private:
void
_recalcSequence
(
void
);
...
...
@@ -82,6 +89,7 @@ private:
void
_deinitAllMissionItems
(
void
);
void
_initMissionItem
(
MissionItem
*
item
);
void
_deinitMissionItem
(
MissionItem
*
item
);
void
_autoSyncSend
(
void
);
private:
QmlObjectListModel
*
_missionItems
;
...
...
@@ -90,6 +98,10 @@ private:
Vehicle
*
_activeVehicle
;
bool
_liveHomePositionAvailable
;
QGeoCoordinate
_liveHomePosition
;
bool
_autoSync
;
bool
_firstMissionItemSync
;
bool
_expectingNewMissionItems
;
bool
_queuedSend
;
static
const
char
*
_settingsGroup
;
};
...
...
src/MissionItem.cc
View file @
37dfd9c1
...
...
@@ -878,10 +878,14 @@ bool MissionItem::canEdit(void)
void
MissionItem
::
setDirty
(
bool
dirty
)
{
if
(
!
_homePositionSpecialCase
||
!
dirty
)
{
// Home position never affects dirty bit
_dirty
=
dirty
;
// We want to emit dirtyChanged even if _dirty didn't change. This can be handy signal for
// any value within the item changing.
emit
dirtyChanged
(
_dirty
);
}
}
void
MissionItem
::
_factValueChanged
(
QVariant
value
)
...
...
src/QmlControls/MissionItemEditor.qml
View file @
37dfd9c1
...
...
@@ -19,7 +19,7 @@ Rectangle {
signal
clicked
signal
remove
height
:
innerItem
.
height
+
(
_margin
*
2
)
height
:
innerItem
.
height
+
(
_margin
*
3
)
color
:
missionItem
.
isCurrentItem
?
qgcPal
.
buttonHighlight
:
qgcPal
.
windowShade
radius
:
_radius
...
...
src/ui/toolbar/MainToolBar.qml
View file @
37dfd9c1
...
...
@@ -69,9 +69,9 @@ Item {
function
showToolbarMessage
(
message
)
{
toolBarMessage
.
text
=
message
if
(
toolBarMessage
.
contentHeight
>
toolBarMessageCloseButton
.
height
)
{
mainToolBa
r
.
height
=
toolBarHeight
+
toolBarMessage
.
contentHeight
+
(
verticalMargins
*
2
)
toolBarHolde
r
.
height
=
toolBarHeight
+
toolBarMessage
.
contentHeight
+
(
verticalMargins
*
2
)
}
else
{
mainToolBa
r
.
height
=
toolBarHeight
+
toolBarMessageCloseButton
.
height
+
(
verticalMargins
*
2
)
toolBarHolde
r
.
height
=
toolBarHeight
+
toolBarMessageCloseButton
.
height
+
(
verticalMargins
*
2
)
}
toolBarMessageArea
.
visible
=
true
}
...
...
@@ -873,7 +873,7 @@ Item {
onClicked
:
{
parent
.
visible
=
false
_controll
er
.
height
=
toolBarHeight
toolBarHold
er
.
height
=
toolBarHeight
_controller
.
onToolBarMessageClosed
()
}
}
...
...
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