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
0adf8caa
Commit
0adf8caa
authored
Oct 16, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Mission Editor usability changes
parent
92cc42a1
Changes
10
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
805 additions
and
681 deletions
+805
-681
qgroundcontrol.qrc
qgroundcontrol.qrc
+1
-0
FlightDisplayView.qml
src/FlightDisplay/FlightDisplayView.qml
+26
-22
FlightMap.qml
src/FlightMap/FlightMap.qml
+7
-11
MissionEditor.qml
src/MissionEditor/MissionEditor.qml
+565
-494
MissionEditorController.cc
src/MissionEditor/MissionEditorController.cc
+3
-2
MissionItem.cc
src/MissionItem.cc
+145
-88
MissionItem.h
src/MissionItem.h
+29
-13
DropButton.qml
src/QmlControls/DropButton.qml
+1
-1
MissionItemEditor.qml
src/QmlControls/MissionItemEditor.qml
+26
-49
MissionItemIndexLabel.qml
src/QmlControls/MissionItemIndexLabel.qml
+2
-1
No files found.
qgroundcontrol.qrc
View file @
0adf8caa
...
@@ -70,6 +70,7 @@
...
@@ -70,6 +70,7 @@
<file alias="Help.svg">src/FlightMap/Images/Help.svg</file>
<file alias="Help.svg">src/FlightMap/Images/Help.svg</file>
<file alias="MapCenter.svg">src/FlightMap/Images/MapCenter.svg</file>
<file alias="MapCenter.svg">src/FlightMap/Images/MapCenter.svg</file>
<file alias="MapSync.svg">src/FlightMap/Images/MapSync.svg</file>
<file alias="MapSync.svg">src/FlightMap/Images/MapSync.svg</file>
<file alias="MapSyncChanged.svg">src/FlightMap/Images/MapSyncChanged.svg</file>
<file alias="MapType.svg">src/FlightMap/Images/MapType.svg</file>
<file alias="MapType.svg">src/FlightMap/Images/MapType.svg</file>
<file alias="MapHome.svg">src/FlightMap/Images/MapHome.svg</file>
<file alias="MapHome.svg">src/FlightMap/Images/MapHome.svg</file>
<file alias="MapAddMission.svg">src/FlightMap/Images/MapAddMission.svg</file>
<file alias="MapAddMission.svg">src/FlightMap/Images/MapAddMission.svg</file>
...
...
src/FlightDisplay/FlightDisplayView.qml
View file @
0adf8caa
...
@@ -55,15 +55,14 @@ Item {
...
@@ -55,15 +55,14 @@ Item {
property
var
_activeVehicle
:
multiVehicleManager
.
activeVehicle
property
var
_activeVehicle
:
multiVehicleManager
.
activeVehicle
readonly
property
real
_defaultLatitude
:
37.803784
readonly
property
var
_defaultVehicleCoordinate
:
QtPositioning
.
coordinate
(
37.803784
,
-
122.462276
)
readonly
property
real
_defaultLongitude
:
-
122.462276
readonly
property
real
_defaultRoll
:
0
readonly
property
real
_defaultRoll
:
0
readonly
property
real
_defaultPitch
:
0
readonly
property
real
_defaultPitch
:
0
readonly
property
real
_defaultHeading
:
0
readonly
property
real
_defaultHeading
:
0
readonly
property
real
_defaultAltitudeWGS84
:
0
readonly
property
real
_defaultAltitudeWGS84
:
0
readonly
property
real
_defaultGroundSpeed
:
0
readonly
property
real
_defaultGroundSpeed
:
0
readonly
property
real
_defaultAirSpeed
:
0
readonly
property
real
_defaultAirSpeed
:
0
readonly
property
real
_defaultClimbRate
:
0
readonly
property
real
_defaultClimbRate
:
0
readonly
property
string
_mapName
:
"
FlightDisplayView
"
readonly
property
string
_mapName
:
"
FlightDisplayView
"
readonly
property
string
_showMapBackgroundKey
:
"
/showMapBackground
"
readonly
property
string
_showMapBackgroundKey
:
"
/showMapBackground
"
...
@@ -72,8 +71,7 @@ Item {
...
@@ -72,8 +71,7 @@ Item {
property
real
_pitch
:
_activeVehicle
?
(
isNaN
(
_activeVehicle
.
pitch
)
?
_defaultPitch
:
_activeVehicle
.
pitch
)
:
_defaultPitch
property
real
_pitch
:
_activeVehicle
?
(
isNaN
(
_activeVehicle
.
pitch
)
?
_defaultPitch
:
_activeVehicle
.
pitch
)
:
_defaultPitch
property
real
_heading
:
_activeVehicle
?
(
isNaN
(
_activeVehicle
.
heading
)
?
_defaultHeading
:
_activeVehicle
.
heading
)
:
_defaultHeading
property
real
_heading
:
_activeVehicle
?
(
isNaN
(
_activeVehicle
.
heading
)
?
_defaultHeading
:
_activeVehicle
.
heading
)
:
_defaultHeading
property
real
_latitude
:
_activeVehicle
?
((
_activeVehicle
.
latitude
===
0
)
?
_defaultLatitude
:
_activeVehicle
.
latitude
)
:
_defaultLatitude
property
var
_vehicleCoordinate
:
_activeVehicle
?
_activeVehicle
.
coordinate
:
_defaultVehicleCoordinate
property
real
_longitude
:
_activeVehicle
?
((
_activeVehicle
.
longitude
===
0
)
?
_defaultLongitude
:
_activeVehicle
.
longitude
)
:
_defaultLongitude
property
real
_altitudeWGS84
:
_activeVehicle
?
_activeVehicle
.
altitudeWGS84
:
_defaultAltitudeWGS84
property
real
_altitudeWGS84
:
_activeVehicle
?
_activeVehicle
.
altitudeWGS84
:
_defaultAltitudeWGS84
property
real
_groundSpeed
:
_activeVehicle
?
_activeVehicle
.
groundSpeed
:
_defaultGroundSpeed
property
real
_groundSpeed
:
_activeVehicle
?
_activeVehicle
.
groundSpeed
:
_defaultGroundSpeed
...
@@ -82,14 +80,20 @@ Item {
...
@@ -82,14 +80,20 @@ Item {
property
bool
_showMap
:
getBool
(
QGroundControl
.
flightMapSettings
.
loadMapSetting
(
flightMap
.
mapName
,
_showMapBackgroundKey
,
"
1
"
))
property
bool
_showMap
:
getBool
(
QGroundControl
.
flightMapSettings
.
loadMapSetting
(
flightMap
.
mapName
,
_showMapBackgroundKey
,
"
1
"
))
FlightDisplayViewController
{
id
:
_controller
;
}
FlightDisplayViewController
{
id
:
_controller
}
ExclusiveGroup
{
ExclusiveGroup
{
id
:
_dropButtonsExclusiveGroup
id
:
_dropButtonsExclusiveGroup
}
}
// Validate _showMap setting
// Validate _showMap setting
Component.onCompleted
:
_setShowMap
(
_showMap
)
Component.onCompleted
:
{
// We have to be careful to not reference root properties in a function which is in a subcomponent
// until the root component has completed loading. Otherwise you get undefined references.
flightMap
.
rootLoadCompleted
=
true
flightMap
.
updateMapPosition
(
true
/* force */
)
_setShowMap
(
_showMap
)
}
function
getBool
(
value
)
{
function
getBool
(
value
)
{
return
value
===
'
0
'
?
false
:
true
;
return
value
===
'
0
'
?
false
:
true
;
...
@@ -104,24 +108,24 @@ Item {
...
@@ -104,24 +108,24 @@ Item {
QGroundControl
.
flightMapSettings
.
saveMapSetting
(
flightMap
.
mapName
,
_showMapBackgroundKey
,
setBool
(
_showMap
))
QGroundControl
.
flightMapSettings
.
saveMapSetting
(
flightMap
.
mapName
,
_showMapBackgroundKey
,
setBool
(
_showMap
))
}
}
FlightMap
{
FlightMap
{
id
:
flightMap
id
:
flightMap
anchors.fill
:
parent
anchors.fill
:
parent
mapName
:
_mapName
mapName
:
_mapName
visible
:
_showMap
visible
:
_showMap
latitude
:
root
.
_defaultCoordinate
.
latitude
longitude
:
root
.
_defaultCoordinate
.
longitude
property
real
rootLatitude
:
root
.
_latitude
property
var
rootVehicleCoordinate
:
_vehicleCoordinate
property
real
rootLongitude
:
root
.
_longitude
property
bool
rootLoadCompleted
:
false
Component.onCompleted
:
updateMapPosition
(
true
/* force */
)
onRootLatitudeChanged
:
updateMapPosition
(
false
/* force */
)
onRootVehicleCoordinateChanged
:
updateMapPosition
(
false
/* force */
)
onRootLongitudeChanged
:
updateMapPosition
(
false
/* force */
)
function
updateMapPosition
(
force
)
{
function
updateMapPosition
(
force
)
{
if
(
_followVehicle
||
force
)
{
if
(
(
_followVehicle
||
force
)
&&
rootLoadCompleted
)
{
latitude
=
root
.
_
latitude
flightMap
.
latitude
=
root
.
_vehicleCoordinate
.
latitude
longitude
=
root
.
_
longitude
flightMap
.
longitude
=
root
.
_vehicleCoordinate
.
longitude
}
}
}
}
...
...
src/FlightMap/FlightMap.qml
View file @
0adf8caa
...
@@ -59,10 +59,13 @@ Map {
...
@@ -59,10 +59,13 @@ Map {
readonly
property
real
zOrderWidgets
:
100
///< z order value to widgets, for example: zoom controls, hud widgetss
readonly
property
real
zOrderWidgets
:
100
///< z order value to widgets, for example: zoom controls, hud widgetss
readonly
property
real
zOrderMapItems
:
50
///< z order value for map items, for example: mission item indicators
readonly
property
real
zOrderMapItems
:
50
///< z order value for map items, for example: mission item indicators
zoomLevel
:
18
readonly
property
real
maxZoomLevel
:
20
center
:
QtPositioning
.
coordinate
(
lat
,
lon
)
gesture.flickDeceleration
:
3000
zoomLevel
:
18
gesture.enabled
:
interactive
center
:
QtPositioning
.
coordinate
(
lat
,
lon
)
gesture.flickDeceleration
:
3000
gesture.enabled
:
interactive
gesture.activeGestures
:
MapGestureArea
.
ZoomGesture
|
MapGestureArea
.
PanGesture
|
MapGestureArea
.
FlickGesture
plugin
:
Plugin
{
name
:
"
QGroundControl
"
}
plugin
:
Plugin
{
name
:
"
QGroundControl
"
}
...
@@ -295,11 +298,4 @@ Map {
...
@@ -295,11 +298,4 @@ Map {
}
}
}
}
*/
*/
MouseArea
{
//-- TODO: Check if this is still needed when we switch to 5.5.1
//-- Workaround for QTBUG-46388 (Pinch zoom doesn't work without it on mobile)
anchors.fill
:
parent
}
}
// Map
}
// Map
src/MissionEditor/MissionEditor.qml
View file @
0adf8caa
This diff is collapsed.
Click to expand it.
src/MissionEditor/MissionEditorController.cc
View file @
0adf8caa
...
@@ -103,14 +103,15 @@ int MissionEditorController::addMissionItem(QGeoCoordinate coordinate)
...
@@ -103,14 +103,15 @@ int MissionEditorController::addMissionItem(QGeoCoordinate coordinate)
if
(
!
_canEdit
)
{
if
(
!
_canEdit
)
{
qWarning
()
<<
"addMissionItem called with _canEdit == false"
;
qWarning
()
<<
"addMissionItem called with _canEdit == false"
;
}
}
// Coordinate will come through without altitude
coordinate
.
setAltitude
(
MissionItem
::
defaultAltitude
);
MissionItem
*
newItem
=
new
MissionItem
(
this
,
_missionItems
->
count
(),
coordinate
,
MAV_CMD_NAV_WAYPOINT
);
MissionItem
*
newItem
=
new
MissionItem
(
this
,
_missionItems
->
count
(),
coordinate
,
MAV_CMD_NAV_WAYPOINT
);
_initMissionItem
(
newItem
);
_initMissionItem
(
newItem
);
newItem
->
setAltitude
(
30
);
if
(
_missionItems
->
count
()
==
1
)
{
if
(
_missionItems
->
count
()
==
1
)
{
newItem
->
setCommand
(
MavlinkQmlSingleton
::
MAV_CMD_NAV_TAKEOFF
);
newItem
->
setCommand
(
MavlinkQmlSingleton
::
MAV_CMD_NAV_TAKEOFF
);
}
}
qDebug
()
<<
"MissionItem"
<<
newItem
->
coordinate
();
_missionItems
->
append
(
newItem
);
_missionItems
->
append
(
newItem
);
_recalcAll
();
_recalcAll
();
...
...
src/MissionItem.cc
View file @
0adf8caa
This diff is collapsed.
Click to expand it.
src/MissionItem.h
View file @
0adf8caa
...
@@ -50,9 +50,9 @@ public:
...
@@ -50,9 +50,9 @@ public:
QGeoCoordinate
coordiante
=
QGeoCoordinate
(),
QGeoCoordinate
coordiante
=
QGeoCoordinate
(),
int
action
=
MAV_CMD_NAV_WAYPOINT
,
int
action
=
MAV_CMD_NAV_WAYPOINT
,
double
param1
=
0
.
0
,
double
param1
=
0
.
0
,
double
param2
=
0
.
0
,
double
param2
=
defaultAcceptanceRadius
,
double
param3
=
0
.
0
,
double
param3
=
defaultLoiterOrbitRadius
,
double
param4
=
0
.
0
,
double
param4
=
defaultHeading
,
bool
autocontinue
=
true
,
bool
autocontinue
=
true
,
bool
isCurrentItem
=
false
,
bool
isCurrentItem
=
false
,
int
frame
=
MAV_FRAME_GLOBAL_RELATIVE_ALT
);
int
frame
=
MAV_FRAME_GLOBAL_RELATIVE_ALT
);
...
@@ -67,10 +67,16 @@ public:
...
@@ -67,10 +67,16 @@ public:
Q_PROPERTY
(
int
sequenceNumber
READ
sequenceNumber
WRITE
setSequenceNumber
NOTIFY
sequenceNumberChanged
)
Q_PROPERTY
(
int
sequenceNumber
READ
sequenceNumber
WRITE
setSequenceNumber
NOTIFY
sequenceNumberChanged
)
Q_PROPERTY
(
bool
isCurrentItem
READ
isCurrentItem
WRITE
setIsCurrentItem
NOTIFY
isCurrentItemChanged
)
Q_PROPERTY
(
bool
isCurrentItem
READ
isCurrentItem
WRITE
setIsCurrentItem
NOTIFY
isCurrentItemChanged
)
Q_PROPERTY
(
bool
specifiesCoordinate
READ
specifiesCoordinate
NOTIFY
commandChanged
)
Q_PROPERTY
(
bool
specifiesCoordinate
READ
specifiesCoordinate
NOTIFY
commandChanged
)
Q_PROPERTY
(
QGeoCoordinate
coordinate
READ
coordinate
WRITE
setCoordinate
NOTIFY
coordinateChanged
)
Q_PROPERTY
(
QGeoCoordinate
coordinate
READ
coordinate
WRITE
setCoordinate
NOTIFY
coordinateChanged
)
Q_PROPERTY
(
bool
specifiesHeading
READ
specifiesHeading
NOTIFY
commandChanged
)
Q_PROPERTY
(
double
heading
READ
headingDegrees
WRITE
setHeadingDegrees
NOTIFY
headingDegreesChanged
)
Q_PROPERTY
(
QStringList
commandNames
READ
commandNames
CONSTANT
)
Q_PROPERTY
(
QStringList
commandNames
READ
commandNames
CONSTANT
)
Q_PROPERTY
(
QString
commandName
READ
commandName
NOTIFY
commandChanged
)
Q_PROPERTY
(
QString
commandName
READ
commandName
NOTIFY
commandChanged
)
Q_PROPERTY
(
QString
commandDescription
READ
commandDescription
NOTIFY
commandChanged
)
Q_PROPERTY
(
QStringList
valueLabels
READ
valueLabels
NOTIFY
commandChanged
)
Q_PROPERTY
(
QStringList
valueLabels
READ
valueLabels
NOTIFY
commandChanged
)
Q_PROPERTY
(
QStringList
valueStrings
READ
valueStrings
NOTIFY
valueStringsChanged
)
Q_PROPERTY
(
QStringList
valueStrings
READ
valueStrings
NOTIFY
valueStringsChanged
)
Q_PROPERTY
(
int
commandByIndex
READ
commandByIndex
WRITE
setCommandByIndex
NOTIFY
commandChanged
)
Q_PROPERTY
(
int
commandByIndex
READ
commandByIndex
WRITE
setCommandByIndex
NOTIFY
commandChanged
)
...
@@ -88,12 +94,16 @@ public:
...
@@ -88,12 +94,16 @@ public:
void
setIsCurrentItem
(
bool
isCurrentItem
);
void
setIsCurrentItem
(
bool
isCurrentItem
);
bool
specifiesCoordinate
(
void
)
const
;
bool
specifiesCoordinate
(
void
)
const
;
QGeoCoordinate
coordinate
(
void
)
const
;
QGeoCoordinate
coordinate
(
void
)
const
;
void
setCoordinate
(
const
QGeoCoordinate
&
coordinate
);
void
setCoordinate
(
const
QGeoCoordinate
&
coordinate
);
bool
specifiesHeading
(
void
)
const
;
double
headingDegrees
(
void
)
const
;
void
setHeadingDegrees
(
double
headingDegrees
);
QStringList
commandNames
(
void
);
QStringList
commandNames
(
void
);
QString
commandName
(
void
);
QString
commandName
(
void
);
QString
commandDescription
(
void
);
int
commandByIndex
(
void
);
int
commandByIndex
(
void
);
void
setCommandByIndex
(
int
index
);
void
setCommandByIndex
(
int
index
);
...
@@ -107,9 +117,6 @@ public:
...
@@ -107,9 +117,6 @@ public:
QmlObjectListModel
*
textFieldFacts
(
void
);
QmlObjectListModel
*
textFieldFacts
(
void
);
QmlObjectListModel
*
checkboxFacts
(
void
);
QmlObjectListModel
*
checkboxFacts
(
void
);
double
yawDegrees
(
void
)
const
;
void
setYawDegrees
(
double
yaw
);
bool
dirty
(
void
)
{
return
_dirty
;
}
bool
dirty
(
void
)
{
return
_dirty
;
}
void
setDirty
(
bool
dirty
);
void
setDirty
(
bool
dirty
);
...
@@ -136,9 +143,6 @@ public:
...
@@ -136,9 +143,6 @@ public:
void
setY
(
double
y
);
void
setY
(
double
y
);
void
setZ
(
double
z
);
void
setZ
(
double
z
);
double
yawRadians
(
void
)
const
;
void
setYawRadians
(
double
yaw
);
bool
autoContinue
()
const
{
bool
autoContinue
()
const
{
return
_autocontinue
;
return
_autocontinue
;
}
}
...
@@ -161,7 +165,7 @@ public:
...
@@ -161,7 +165,7 @@ public:
return
loiterOrbitRadius
();
return
loiterOrbitRadius
();
}
}
double
param4
()
const
{
double
param4
()
const
{
return
yawRadians
();
return
_
yawRadians
();
}
}
double
param5
()
const
{
double
param5
()
const
{
return
latitude
();
return
latitude
();
...
@@ -189,11 +193,19 @@ public:
...
@@ -189,11 +193,19 @@ public:
bool
load
(
QTextStream
&
loadStream
);
bool
load
(
QTextStream
&
loadStream
);
void
setHomePositionSpecialCase
(
bool
homePositionSpecialCase
)
{
_homePositionSpecialCase
=
homePositionSpecialCase
;
}
void
setHomePositionSpecialCase
(
bool
homePositionSpecialCase
)
{
_homePositionSpecialCase
=
homePositionSpecialCase
;
}
static
const
double
defaultPitch
;
static
const
double
defaultHeading
;
static
const
double
defaultAltitude
;
static
const
double
defaultAcceptanceRadius
;
static
const
double
defaultLoiterOrbitRadius
;
static
const
double
defaultLoiterTurns
;
signals:
signals:
void
sequenceNumberChanged
(
int
sequenceNumber
);
void
sequenceNumberChanged
(
int
sequenceNumber
);
void
isCurrentItemChanged
(
bool
isCurrentItem
);
void
isCurrentItemChanged
(
bool
isCurrentItem
);
void
coordinateChanged
(
const
QGeoCoordinate
&
coordinate
);
void
coordinateChanged
(
const
QGeoCoordinate
&
coordinate
);
void
headingDegreesChanged
(
double
heading
);
void
dirtyChanged
(
bool
dirty
);
void
dirtyChanged
(
bool
dirty
);
/** @brief Announces a change to the waypoint data */
/** @brief Announces a change to the waypoint data */
...
@@ -234,9 +246,13 @@ public:
...
@@ -234,9 +246,13 @@ public:
private
slots
:
private
slots
:
void
_factValueChanged
(
QVariant
value
);
void
_factValueChanged
(
QVariant
value
);
void
_coordinateFactChanged
(
QVariant
value
);
void
_coordinateFactChanged
(
QVariant
value
);
void
_headingDegreesFactChanged
(
QVariant
value
);
private:
private:
QString
_oneDecimalString
(
double
value
);
QString
_oneDecimalString
(
double
value
);
void
_connectSignals
(
void
);
double
_yawRadians
(
void
)
const
;
void
_setYawRadians
(
double
yawRadians
);
private:
private:
typedef
struct
{
typedef
struct
{
...
@@ -254,7 +270,7 @@ private:
...
@@ -254,7 +270,7 @@ private:
Fact
*
_latitudeFact
;
Fact
*
_latitudeFact
;
Fact
*
_longitudeFact
;
Fact
*
_longitudeFact
;
Fact
*
_altitudeFact
;
Fact
*
_altitudeFact
;
Fact
*
_
yawRadian
sFact
;
Fact
*
_
headingDegree
sFact
;
Fact
*
_loiterOrbitRadiusFact
;
Fact
*
_loiterOrbitRadiusFact
;
Fact
*
_param1Fact
;
Fact
*
_param1Fact
;
Fact
*
_param2Fact
;
Fact
*
_param2Fact
;
...
...
src/QmlControls/DropButton.qml
View file @
0adf8caa
...
@@ -224,7 +224,7 @@ Item {
...
@@ -224,7 +224,7 @@ Item {
context
.
lineTo
(
dropItemHolderRect
.
x
,
dropItemHolderRect
.
y
)
context
.
lineTo
(
dropItemHolderRect
.
x
,
dropItemHolderRect
.
y
)
context
.
closePath
()
context
.
closePath
()
context
.
fillStyle
=
qgcPal
.
button
context
.
fillStyle
=
qgcPal
.
windowShade
context
.
fill
()
context
.
fill
()
}
}
}
// Canvas - arrowCanvas
}
// Canvas - arrowCanvas
...
...
src/QmlControls/MissionItemEditor.qml
View file @
0adf8caa
...
@@ -19,34 +19,26 @@ Rectangle {
...
@@ -19,34 +19,26 @@ Rectangle {
signal
clicked
signal
clicked
signal
remove
signal
remove
height
:
missionItem
.
isCurrentItem
?
height
:
innerItem
.
height
+
(
_margin
*
2
)
(
missionItem
.
textFieldFacts
.
count
*
(
measureTextField
.
height
+
_margin
))
+
(
missionItem
.
checkboxFacts
.
count
*
(
measureCheckbox
.
height
+
_margin
))
+
commandPicker
.
height
+
(
deleteButton
.
visible
?
deleteButton
.
height
:
0
)
+
(
_margin
*
9
)
:
commandPicker
.
height
+
(
_margin
*
2
)
color
:
missionItem
.
isCurrentItem
?
qgcPal
.
buttonHighlight
:
qgcPal
.
windowShade
color
:
missionItem
.
isCurrentItem
?
qgcPal
.
buttonHighlight
:
qgcPal
.
windowShade
radius
:
_radius
readonly
property
real
_editFieldWidth
:
ScreenTools
.
defaultFontPixelWidth
*
16
readonly
property
real
_editFieldWidth
:
ScreenTools
.
defaultFontPixelWidth
*
16
readonly
property
real
_margin
:
ScreenTools
.
defaultFontPixelWidth
/
3
readonly
property
real
_margin
:
ScreenTools
.
defaultFontPixelWidth
/
2
readonly
property
real
_radius
:
ScreenTools
.
defaultFontPixelWidth
/
2
QGCPalette
{
QGCPalette
{
id
:
qgcPal
id
:
qgcPal
colorGroupEnabled
:
enabled
colorGroupEnabled
:
enabled
}
}
QGCTextField
{
id
:
measureTextField
visible
:
false
}
QGCCheckBox
{
id
:
measureCheckbox
visible
:
false
}
Item
{
Item
{
id
:
innerItem
anchors.margins
:
_margin
anchors.margins
:
_margin
anchors.fill
:
parent
anchors.top
:
parent
.
top
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
height
:
valuesRect
.
visible
?
valuesRect
.
y
+
valuesRect
.
height
:
valuesRect
.
y
MissionItemIndexLabel
{
MissionItemIndexLabel
{
id
:
label
id
:
label
...
@@ -69,7 +61,7 @@ Rectangle {
...
@@ -69,7 +61,7 @@ Rectangle {
anchors.right
:
parent
.
right
anchors.right
:
parent
.
right
currentIndex
:
missionItem
.
commandByIndex
currentIndex
:
missionItem
.
commandByIndex
model
:
missionItem
.
commandNames
model
:
missionItem
.
commandNames
visible
:
missionItem
.
sequenceNumber
!=
0
// Item 0 is home position, can't change item type
visible
:
missionItem
.
sequenceNumber
!=
0
&&
missionItem
.
isCurrentItem
onActivated
:
missionItem
.
commandByIndex
=
index
onActivated
:
missionItem
.
commandByIndex
=
index
}
}
...
@@ -77,30 +69,36 @@ Rectangle {
...
@@ -77,30 +69,36 @@ Rectangle {
Rectangle
{
Rectangle
{
anchors.fill
:
commandPicker
anchors.fill
:
commandPicker
color
:
qgcPal
.
button
color
:
qgcPal
.
button
visible
:
missionItem
.
sequenceNumber
==
0
// Item 0 is home position, can't change item typ
e
visible
:
!
commandPicker
.
visibl
e
QGCLabel
{
QGCLabel
{
id
:
homeLabel
id
:
homeLabel
anchors.leftMargin
:
ScreenTools
.
defaultFontPixelWidth
anchors.leftMargin
:
ScreenTools
.
defaultFontPixelWidth
anchors.fill
:
parent
anchors.fill
:
parent
verticalAlignment
:
Text
.
AlignVCenter
verticalAlignment
:
Text
.
AlignVCenter
text
:
"
Home
"
text
:
missionItem
.
sequenceNumber
==
0
?
"
Home
"
:
missionItem
.
commandName
color
:
qgcPal
.
buttonText
color
:
qgcPal
.
buttonText
}
}
}
}
Rectangle
{
Rectangle
{
id
:
valuesRect
anchors.topMargin
:
_margin
anchors.topMargin
:
_margin
anchors.top
:
commandPicker
.
bottom
anchors.top
:
commandPicker
.
bottom
anchors.bottom
:
parent
.
bottom
anchors.left
:
parent
.
left
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.right
:
parent
.
right
height
:
valuesItem
.
height
color
:
qgcPal
.
windowShadeDark
color
:
qgcPal
.
windowShadeDark
visible
:
missionItem
.
isCurrentItem
visible
:
missionItem
.
isCurrentItem
radius
:
_radius
Item
{
Item
{
id
:
valuesItem
anchors.margins
:
_margin
anchors.margins
:
_margin
anchors.fill
:
parent
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.top
:
parent
.
top
height
:
valuesColumn
.
height
+
_margin
Column
{
Column
{
id
:
valuesColumn
id
:
valuesColumn
...
@@ -109,6 +107,12 @@ Rectangle {
...
@@ -109,6 +107,12 @@ Rectangle {
anchors.top
:
parent
.
top
anchors.top
:
parent
.
top
spacing
:
_margin
spacing
:
_margin
QGCLabel
{
width
:
parent
.
width
wrapMode
:
Text
.
WordWrap
text
:
missionItem
.
commandDescription
}
Repeater
{
Repeater
{
model
:
missionItem
.
textFieldFacts
model
:
missionItem
.
textFieldFacts
...
@@ -140,11 +144,6 @@ Rectangle {
...
@@ -140,11 +144,6 @@ Rectangle {
}
}
}
}
Item
{
width
:
10
height
:
missionItem
.
textFieldFacts
.
count
?
_margin
:
0
}
Repeater
{
Repeater
{
model
:
missionItem
.
checkboxFacts
model
:
missionItem
.
checkboxFacts
...
@@ -154,28 +153,6 @@ Rectangle {
...
@@ -154,28 +153,6 @@ Rectangle {
fact
:
object
fact
:
object
}
}
}
}
Item
{
width
:
10
height
:
missionItem
.
checkboxFacts
.
count
?
_margin
:
0
}
Row
{
width
:
parent
.
width
spacing
:
_margin
readonly
property
real
buttonWidth
:
(
width
-
(
_margin
*
2
))
/
3
QGCButton
{
id
:
deleteButton
width
:
parent
.
buttonWidth
text
:
"
Delete
"
visible
:
!
readOnly
onClicked
:
_root
.
remove
()
}
}
}
// Column
}
// Column
}
// Item
}
// Item
}
// Rectangle
}
// Rectangle
...
...
src/QmlControls/MissionItemIndexLabel.qml
View file @
0adf8caa
...
@@ -13,7 +13,7 @@ Rectangle {
...
@@ -13,7 +13,7 @@ Rectangle {
QGCPalette
{
id
:
qgcPal
}
QGCPalette
{
id
:
qgcPal
}
width
:
ScreenTools
.
defaultFontPixelHeight
*
1.5
width
:
ScreenTools
.
mediumFontPixelSize
*
1.5
height
:
width
height
:
width
radius
:
width
/
2
radius
:
width
/
2
border.width
:
2
border.width
:
2
...
@@ -32,5 +32,6 @@ Rectangle {
...
@@ -32,5 +32,6 @@ Rectangle {
horizontalAlignment
:
Text
.
AlignHCenter
horizontalAlignment
:
Text
.
AlignHCenter
verticalAlignment
:
Text
.
AlignVCenter
verticalAlignment
:
Text
.
AlignVCenter
color
:
"
white
"
color
:
"
white
"
font.pixelSize
:
ScreenTools
.
mediumFontPixelSize
}
}
}
}
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