Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
851d2c9c
Commit
851d2c9c
authored
Jan 30, 2017
by
jaxxzer
Committed by
GitHub
Jan 30, 2017
Browse files
Merge branch 'master' into video-recording
parents
5ce9d168
2a016a3d
Changes
45
Hide whitespace changes
Inline
Side-by-side
deploy/qgroundcontrol_installer.nsi
View file @
851d2c9c
...
...
@@ -41,6 +41,8 @@ Var StartMenuFolder
InstallDir $PROGRAMFILES\qgroundcontrol
SetCompressor /SOLID /FINAL lzma
!define MUI_HEADERIMAGE
!define MUI_HEADERIMAGE_BITMAP "installheader.bmp";
...
...
qgroundcontrol.qrc
View file @
851d2c9c
...
...
@@ -48,6 +48,7 @@
<file alias="QGroundControl/Controls/ExclusiveGroupItem.qml">src/QmlControls/ExclusiveGroupItem.qml</file>
<file alias="QGroundControl/Controls/FactSliderPanel.qml">src/QmlControls/FactSliderPanel.qml</file>
<file alias="QGroundControl/Controls/FlightModeDropdown.qml">src/QmlControls/FlightModeDropdown.qml</file>
<file alias="QGroundControl/Controls/FlightModeMenu.qml">src/QmlControls/FlightModeMenu.qml</file>
<file alias="QGroundControl/Controls/GuidedBar.qml">src/QmlControls/GuidedBar.qml</file>
<file alias="QGroundControl/Controls/IndicatorButton.qml">src/QmlControls/IndicatorButton.qml</file>
<file alias="QGroundControl/Controls/JoystickThumbPad.qml">src/QmlControls/JoystickThumbPad.qml</file>
...
...
@@ -167,6 +168,7 @@
<file alias="QGroundControlQmlGlobal.json">src/QmlControls/QGroundControlQmlGlobal.json</file>
<file alias="RallyPoint.FactMetaData.json">src/MissionManager/RallyPoint.FactMetaData.json</file>
<file alias="Survey.FactMetaData.json">src/MissionManager/Survey.FactMetaData.json</file>
<file alias="USBBoardInfo.json">src/comm/USBBoardInfo.json</file>
</qresource>
<qresource prefix="/MockLink">
<file alias="APMArduCopterMockLink.params">src/comm/APMArduCopterMockLink.params</file>
...
...
src/AnalyzeView/ExifParser.cc
View file @
851d2c9c
...
...
@@ -178,17 +178,17 @@ bool ExifParser::write(QByteArray &buf, QGeoCoordinate coordinate)
// Filling up the additional information that does not fit into the fields
gpsData
.
readable
.
extendedData
.
gpsLat
[
0
]
=
abs
(
static_cast
<
int
>
(
coordinate
.
latitude
()));
gpsData
.
readable
.
extendedData
.
gpsLat
[
1
]
=
1
;
gpsData
.
readable
.
extendedData
.
gpsLat
[
2
]
=
static_cast
<
int
>
((
fabs
(
coordinate
.
latitude
())
-
floor
(
fabs
(
coordinate
.
latitude
())))
*
60
000
.0
);
gpsData
.
readable
.
extendedData
.
gpsLat
[
3
]
=
1
000
;
gpsData
.
readable
.
extendedData
.
gpsLat
[
4
]
=
0
;
gpsData
.
readable
.
extendedData
.
gpsLat
[
5
]
=
1
;
gpsData
.
readable
.
extendedData
.
gpsLat
[
2
]
=
static_cast
<
int
>
((
fabs
(
coordinate
.
latitude
())
-
floor
(
fabs
(
coordinate
.
latitude
())))
*
60.0
);
gpsData
.
readable
.
extendedData
.
gpsLat
[
3
]
=
1
;
gpsData
.
readable
.
extendedData
.
gpsLat
[
4
]
=
static_cast
<
int
>
((
fabs
(
coordinate
.
latitude
())
*
60.0
-
floor
(
fabs
(
coordinate
.
latitude
())
*
60.0
))
*
60000.0
)
;
gpsData
.
readable
.
extendedData
.
gpsLat
[
5
]
=
1
000
;
gpsData
.
readable
.
extendedData
.
gpsLon
[
0
]
=
abs
(
static_cast
<
int
>
(
coordinate
.
longitude
()));
gpsData
.
readable
.
extendedData
.
gpsLon
[
1
]
=
1
;
gpsData
.
readable
.
extendedData
.
gpsLon
[
2
]
=
static_cast
<
int
>
((
fabs
(
coordinate
.
longitude
())
-
floor
(
fabs
(
coordinate
.
longitude
())))
*
60
000
.0
);
gpsData
.
readable
.
extendedData
.
gpsLon
[
3
]
=
1
000
;
gpsData
.
readable
.
extendedData
.
gpsLon
[
4
]
=
0
;
gpsData
.
readable
.
extendedData
.
gpsLon
[
5
]
=
1
;
gpsData
.
readable
.
extendedData
.
gpsLon
[
2
]
=
static_cast
<
int
>
((
fabs
(
coordinate
.
longitude
())
-
floor
(
fabs
(
coordinate
.
longitude
())))
*
60.0
);
gpsData
.
readable
.
extendedData
.
gpsLon
[
3
]
=
1
;
gpsData
.
readable
.
extendedData
.
gpsLon
[
4
]
=
static_cast
<
int
>
((
fabs
(
coordinate
.
longitude
())
*
60.0
-
floor
(
fabs
(
coordinate
.
longitude
())
*
60.0
))
*
60000.0
)
;
gpsData
.
readable
.
extendedData
.
gpsLon
[
5
]
=
1
000
;
gpsData
.
readable
.
extendedData
.
gpsAlt
[
0
]
=
coordinate
.
altitude
()
*
100
;
gpsData
.
readable
.
extendedData
.
gpsAlt
[
1
]
=
100
;
...
...
src/FirmwarePlugin/FirmwarePluginManager.cc
View file @
851d2c9c
...
...
@@ -30,14 +30,11 @@ QList<MAV_AUTOPILOT> FirmwarePluginManager::knownFirmwareTypes(void)
{
if
(
_knownFirmwareTypes
.
isEmpty
())
{
QList
<
FirmwarePluginFactory
*>
factoryList
=
FirmwarePluginFactoryRegister
::
instance
()
->
pluginFactories
();
for
(
int
i
=
0
;
i
<
factoryList
.
count
();
i
++
)
{
for
(
int
i
=
0
;
i
<
factoryList
.
count
();
i
++
)
{
_knownFirmwareTypes
.
append
(
factoryList
[
i
]
->
knownFirmwareTypes
());
}
_knownFirmwareTypes
.
append
(
MAV_AUTOPILOT_GENERIC
);
}
_knownFirmwareTypes
.
append
(
MAV_AUTOPILOT_GENERIC
);
return
_knownFirmwareTypes
;
}
...
...
src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json
View file @
851d2c9c
...
...
@@ -7,7 +7,13 @@
{
"id"
:
21
,
"comment"
:
"MAV_CMD_NAV_LAND"
,
"paramRemove"
:
"1,4"
"paramRemove"
:
"1,4"
,
"param7"
:
{
"label"
:
"Altitude:"
,
"units"
:
"m"
,
"default"
:
0
,
"decimalPlaces"
:
1
}
},
{
"id"
:
22
,
...
...
src/FlightDisplay/MultiVehicleList.qml
View file @
851d2c9c
...
...
@@ -77,10 +77,10 @@ QGCListView {
color
:
_textColor
}
QGCLabel
{
text
:
_vehicle
.
flightMod
e
font.pointSize
:
ScreenTools
.
largeFontPointSize
color
:
_textColor
FlightModeMenu
{
font.pointSize
:
ScreenTools
.
largeFontPointSiz
e
color
:
_textColor
activeVehicle
:
_vehicle
}
}
...
...
src/Joystick/JoystickManager.cc
View file @
851d2c9c
...
...
@@ -53,7 +53,10 @@ void JoystickManager::setToolbox(QGCToolbox *toolbox)
_multiVehicleManager
=
_toolbox
->
multiVehicleManager
();
QQmlEngine
::
setObjectOwnership
(
this
,
QQmlEngine
::
CppOwnership
);
}
void
JoystickManager
::
discoverJoysticks
()
{
#ifdef __sdljoystick__
_name2JoystickMap
=
JoystickSDL
::
discover
(
_multiVehicleManager
);
#elif defined(__android__)
...
...
src/Joystick/JoystickManager.h
View file @
851d2c9c
...
...
@@ -48,6 +48,9 @@ public:
// Override from QGCTool
virtual
void
setToolbox
(
QGCToolbox
*
toolbox
);
public
slots
:
void
discoverJoysticks
();
signals:
void
activeJoystickChanged
(
Joystick
*
joystick
);
void
activeJoystickNameChanged
(
const
QString
&
name
);
...
...
src/Joystick/JoystickSDL.cc
View file @
851d2c9c
...
...
@@ -15,7 +15,7 @@ JoystickSDL::JoystickSDL(const QString& name, int axisCount, int buttonCount, in
QMap
<
QString
,
Joystick
*>
JoystickSDL
::
discover
(
MultiVehicleManager
*
_multiVehicleManager
)
{
static
QMap
<
QString
,
Joystick
*>
ret
;
if
(
SDL_InitSubSystem
(
SDL_INIT_GAMECONTROLLER
|
SDL_INIT_NOPARACHUTE
)
<
0
)
{
if
(
SDL_InitSubSystem
(
SDL_INIT_GAMECONTROLLER
|
SDL_INIT_JOYSTICK
|
SDL_INIT_NOPARACHUTE
)
<
0
)
{
qWarning
()
<<
"Couldn't initialize SimpleDirectMediaLayer:"
<<
SDL_GetError
();
return
ret
;
}
...
...
@@ -33,7 +33,7 @@ QMap<QString, Joystick*> JoystickSDL::discover(MultiVehicleManager* _multiVehicl
int
axisCount
,
buttonCount
,
hatCount
;
bool
isGameController
;
SDL_Joystick
*
sdlJoystick
=
SDL_JoystickOpen
(
i
);
if
(
SDL_IsGameController
(
i
))
{
isGameController
=
true
;
axisCount
=
SDL_CONTROLLER_AXIS_MAX
;
...
...
@@ -41,15 +41,23 @@ QMap<QString, Joystick*> JoystickSDL::discover(MultiVehicleManager* _multiVehicl
hatCount
=
0
;
}
else
{
isGameController
=
false
;
axisCount
=
SDL_JoystickNumAxes
(
sdlJoystick
);
buttonCount
=
SDL_JoystickNumButtons
(
sdlJoystick
);
hatCount
=
SDL_JoystickNumHats
(
sdlJoystick
);
if
(
SDL_Joystick
*
sdlJoystick
=
SDL_JoystickOpen
(
i
))
{
SDL_ClearError
();
axisCount
=
SDL_JoystickNumAxes
(
sdlJoystick
);
buttonCount
=
SDL_JoystickNumButtons
(
sdlJoystick
);
hatCount
=
SDL_JoystickNumHats
(
sdlJoystick
);
if
(
axisCount
<
0
||
buttonCount
<
0
||
hatCount
<
0
)
{
qCWarning
(
JoystickLog
)
<<
"
\t
libsdl error parsing joystick features:"
<<
SDL_GetError
();
}
SDL_JoystickClose
(
sdlJoystick
);
}
else
{
qCWarning
(
JoystickLog
)
<<
"
\t
libsdl failed opening joystick"
<<
qPrintable
(
name
)
<<
"error:"
<<
SDL_GetError
();
continue
;
}
}
SDL_JoystickClose
(
sdlJoystick
);
qCDebug
(
JoystickLog
)
<<
"
\t
"
<<
name
<<
"axes:"
<<
axisCount
<<
"buttons:"
<<
buttonCount
<<
"hats:"
<<
hatCount
<<
"isGC:"
<<
isGameController
;
ret
[
name
]
=
new
JoystickSDL
(
name
,
axisCount
,
buttonCount
,
hatCount
,
i
,
isGameController
,
_multiVehicleManager
);
ret
[
name
]
=
new
JoystickSDL
(
name
,
qMax
(
0
,
axisCount
)
,
qMax
(
0
,
buttonCount
)
,
qMax
(
0
,
hatCount
)
,
i
,
isGameController
,
_multiVehicleManager
);
}
else
{
qCDebug
(
JoystickLog
)
<<
"
\t
Skipping duplicate"
<<
name
;
}
...
...
src/MissionEditor/MissionEditor.qml
View file @
851d2c9c
...
...
@@ -37,7 +37,7 @@ QGCView {
readonly
property
real
_margin
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
readonly
property
var
_activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
readonly
property
real
_rightPanelWidth
:
Math
.
min
(
parent
.
width
/
3
,
ScreenTools
.
defaultFontPixelWidth
*
30
)
readonly
property
real
_rightPanelOpacity
:
0.8
readonly
property
real
_rightPanelOpacity
:
1
readonly
property
int
_toolButtonCount
:
6
readonly
property
real
_toolButtonTopMargin
:
parent
.
height
-
ScreenTools
.
availableHeight
+
(
ScreenTools
.
defaultFontPixelHeight
/
2
)
readonly
property
var
_defaultVehicleCoordinate
:
QtPositioning
.
coordinate
(
37.803784
,
-
122.462276
)
...
...
src/MissionEditor/MissionItemEditor.qml
View file @
851d2c9c
...
...
@@ -18,8 +18,8 @@ Rectangle {
color
:
_currentItem
?
qgcPal
.
buttonHighlight
:
qgcPal
.
windowShade
radius
:
_radius
property
var
missionItem
///< MissionItem associated with this editor
property
bool
readOnly
///< true: read only view, false: full editing view
property
var
missionItem
///< MissionItem associated with this editor
property
bool
readOnly
///< true: read only view, false: full editing view
signal
clicked
signal
remove
...
...
@@ -33,6 +33,7 @@ Rectangle {
readonly
property
real
_editFieldWidth
:
Math
.
min
(
width
-
_margin
*
2
,
ScreenTools
.
defaultFontPixelWidth
*
12
)
readonly
property
real
_margin
:
ScreenTools
.
defaultFontPixelWidth
/
2
readonly
property
real
_radius
:
ScreenTools
.
defaultFontPixelWidth
/
2
readonly
property
real
_hamburgerSize
:
commandPicker
.
height
*
0.75
QGCPalette
{
id
:
qgcPal
...
...
@@ -54,16 +55,17 @@ Rectangle {
color
:
_outerTextColor
}
Image
{
QGCColored
Image
{
id
:
hamburger
anchors.rightMargin
:
ScreenTools
.
defaultFontPixelWidth
anchors.right
:
parent
.
right
anchors.verticalCenter
:
commandPicker
.
verticalCenter
width
:
commandPicker
.
height
height
:
commandPicker
.
height
sourceSize.height
:
height
width
:
_hamburgerSize
height
:
_hamburgerSize
sourceSize.height
:
_hamburgerSize
source
:
"
qrc:/qmlimages/Hamburger.svg
"
visible
:
missionItem
.
isCurrentItem
&&
missionItem
.
sequenceNumber
!=
0
color
:
qgcPal
.
windowShade
MouseArea
{
anchors.fill
:
parent
...
...
src/MissionEditor/MissionSettingsEditor.qml
View file @
851d2c9c
...
...
@@ -37,6 +37,7 @@ Rectangle {
property
bool
_showOfflineEditingCombos
:
_offlineEditing
&&
_noMissionItemsAdded
property
bool
_showCruiseSpeed
:
!
_missionVehicle
.
multiRotor
property
bool
_showHoverSpeed
:
_missionVehicle
.
multiRotor
||
missionController
.
vehicle
.
vtol
property
bool
_multipleFirmware
:
QGroundControl
.
supportedFirmwareCount
>
2
readonly
property
string
_firmwareLabel
:
qsTr
(
"
Firmware:
"
)
readonly
property
string
_vehicleLabel
:
qsTr
(
"
Vehicle:
"
)
...
...
@@ -50,7 +51,9 @@ Rectangle {
anchors.top
:
parent
.
top
spacing
:
_margin
QGCLabel
{
text
:
qsTr
(
"
Planned Home Position:
"
)
}
QGCLabel
{
text
:
qsTr
(
"
Planned Home Position
"
)
}
Rectangle
{
anchors.left
:
parent
.
left
...
...
@@ -90,27 +93,25 @@ Rectangle {
}
}
QGCButton
{
text
:
qsTr
(
"
Move Home to map center
"
)
visible
:
missionItem
.
homePosition
onClicked
:
editorRoot
.
moveHomeToMapCenter
()
anchors.horizontalCenter
:
parent
.
horizontalCenter
}
QGCLabel
{
width
:
parent
.
width
wrapMode
:
Text
.
WordWrap
font.pointSize
:
ScreenTools
.
smallFontPointSize
text
:
qsTr
(
"
Note: Planned home position for mission display only. Actual home position set by vehicle at flight time.
"
)
text
:
qsTr
(
"
Actual position set by vehicle at flight time.
"
)
horizontalAlignment
:
Text
.
AlignHCenter
}
QGCLabel
{
text
:
qsTr
(
"
Vehicle Info:
"
)
}
QGCLabel
{
text
:
qsTr
(
"
Vehicle Info:
"
)
visible
:
_multipleFirmware
}
Rectangle
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
height
:
1
color
:
qgcPal
.
text
visible
:
_multipleFirmware
}
GridLayout
{
...
...
@@ -119,6 +120,7 @@ Rectangle {
columnSpacing
:
ScreenTools
.
defaultFontPixelWidth
rowSpacing
:
columnSpacing
columns
:
2
visible
:
_multipleFirmware
QGCLabel
{
text
:
_firmwareLabel
...
...
@@ -187,8 +189,23 @@ Rectangle {
width
:
parent
.
width
wrapMode
:
Text
.
WordWrap
font.pointSize
:
ScreenTools
.
smallFontPointSize
text
:
qsTr
(
"
Note: Speeds are planned speeds only for time calculations. Actual vehicle will not be affected.
"
)
visible
:
_multipleFirmware
text
:
qsTr
(
"
Speeds are only for time calculations. Actual vehicle will not be affected.
"
)
}
Rectangle
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
height
:
1
color
:
qgcPal
.
text
}
QGCButton
{
text
:
qsTr
(
"
Set Home To Map Center
"
)
onClicked
:
editorRoot
.
moveHomeToMapCenter
()
anchors.horizontalCenter
:
parent
.
horizontalCenter
}
}
// Column
}
// Item
}
// Component
...
...
src/MissionManager/GeoFenceController.cc
View file @
851d2c9c
...
...
@@ -214,7 +214,7 @@ void GeoFenceController::loadFromFile(const QString& filename)
QFile
file
(
filename
);
if
(
!
file
.
open
(
QIODevice
::
ReadOnly
|
QIODevice
::
Text
))
{
errorString
=
file
.
errorString
();
errorString
=
file
.
errorString
()
+
QStringLiteral
(
" "
)
+
filename
;
}
else
{
QJsonDocument
jsonDoc
;
QByteArray
bytes
=
file
.
readAll
();
...
...
src/MissionManager/MissionController.cc
View file @
851d2c9c
...
...
@@ -87,7 +87,7 @@ void MissionController::_init(void)
{
// We start with an empty mission
_visualItems
=
new
QmlObjectListModel
(
this
);
_addPlannedHomePosition
(
_visualItems
,
false
/* addToCenter */
);
_addPlannedHomePosition
(
_activeVehicle
,
_visualItems
,
false
/* addToCenter */
);
_initAllVisualItems
();
}
...
...
@@ -113,11 +113,11 @@ void MissionController::_newMissionItemsAvailableFromVehicle(void)
_deinitAllVisualItems
();
_visualItems
->
deleteL
istAndContents
();
_visualItems
->
deleteL
ater
();
_visualItems
=
newControllerMissionItems
;
if
(
!
_activeVehicle
->
firmwarePlugin
()
->
sendHomePositionToVehicle
()
||
_visualItems
->
count
()
==
0
)
{
_addPlannedHomePosition
(
_visualItems
,
true
/* addToCenter */
);
_addPlannedHomePosition
(
_activeVehicle
,
_visualItems
,
true
/* addToCenter */
);
}
_missionItemsRequested
=
false
;
...
...
@@ -139,12 +139,18 @@ void MissionController::loadFromVehicle(void)
void
MissionController
::
sendToVehicle
(
void
)
{
if
(
_activeVehicle
)
{
sendItemsToVehicle
(
_activeVehicle
,
_visualItems
);
_visualItems
->
setDirty
(
false
);
}
void
MissionController
::
sendItemsToVehicle
(
Vehicle
*
vehicle
,
QmlObjectListModel
*
visualMissionItems
)
{
if
(
vehicle
)
{
// Convert to MissionItems so we can send to vehicle
QList
<
MissionItem
*>
missionItems
;
for
(
int
i
=
0
;
i
<
_
visualItems
->
count
();
i
++
)
{
VisualMissionItem
*
visualItem
=
qobject_cast
<
VisualMissionItem
*>
(
_
visualItems
->
get
(
i
));
for
(
int
i
=
0
;
i
<
visual
Mission
Items
->
count
();
i
++
)
{
VisualMissionItem
*
visualItem
=
qobject_cast
<
VisualMissionItem
*>
(
visual
Mission
Items
->
get
(
i
));
if
(
visualItem
->
isSimpleItem
())
{
missionItems
.
append
(
new
MissionItem
(
qobject_cast
<
SimpleMissionItem
*>
(
visualItem
)
->
missionItem
()));
}
else
{
...
...
@@ -153,15 +159,14 @@ void MissionController::sendToVehicle(void)
for
(
int
j
=
0
;
j
<
complexMissionItems
->
count
();
j
++
)
{
missionItems
.
append
(
new
MissionItem
(
*
qobject_cast
<
MissionItem
*>
(
complexMissionItems
->
get
(
j
))));
}
delete
complexMissionItems
;
complexMissionItems
->
deleteLater
()
;
}
}
_activeVehicle
->
missionManager
()
->
writeMissionItems
(
missionItems
);
_visualItems
->
setDirty
(
false
);
vehicle
->
missionManager
()
->
writeMissionItems
(
missionItems
);
for
(
int
i
=
0
;
i
<
missionItems
.
count
();
i
++
)
{
delete
missionItems
[
i
];
missionItems
[
i
]
->
deleteLater
()
;
}
}
}
...
...
@@ -216,7 +221,7 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
int
MissionController
::
insertComplexMissionItem
(
QGeoCoordinate
coordinate
,
int
i
)
{
int
sequenceNumber
=
_nextSequenceNumber
();
SurveyMissionItem
*
newItem
=
new
SurveyMissionItem
(
_activeVehicle
,
thi
s
);
SurveyMissionItem
*
newItem
=
new
SurveyMissionItem
(
_activeVehicle
,
_visualItem
s
);
newItem
->
setSequenceNumber
(
sequenceNumber
);
newItem
->
setCoordinate
(
coordinate
);
_initVisualItem
(
newItem
);
...
...
@@ -260,15 +265,15 @@ void MissionController::removeAll(void)
{
if
(
_visualItems
)
{
_deinitAllVisualItems
();
_visualItems
->
deleteL
istAndContents
();
_visualItems
->
deleteL
ater
();
_visualItems
=
new
QmlObjectListModel
(
this
);
_addPlannedHomePosition
(
_visualItems
,
false
/* addToCenter */
);
_addPlannedHomePosition
(
_activeVehicle
,
_visualItems
,
false
/* addToCenter */
);
_initAllVisualItems
();
_visualItems
->
setDirty
(
true
);
}
}
bool
MissionController
::
_loadJsonMissionFile
(
const
QByteArray
&
bytes
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
)
bool
MissionController
::
_loadJsonMissionFile
(
Vehicle
*
vehicle
,
const
QByteArray
&
bytes
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
)
{
QJsonParseError
jsonParseError
;
QJsonDocument
jsonDoc
(
QJsonDocument
::
fromJson
(
bytes
,
&
jsonParseError
));
...
...
@@ -295,13 +300,13 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL
}
if
(
fileVersion
==
1
)
{
return
_loadJsonMissionFileV1
(
json
,
visualItems
,
complexItems
,
errorString
);
return
_loadJsonMissionFileV1
(
vehicle
,
json
,
visualItems
,
complexItems
,
errorString
);
}
else
{
return
_loadJsonMissionFileV2
(
json
,
visualItems
,
complexItems
,
errorString
);
return
_loadJsonMissionFileV2
(
vehicle
,
json
,
visualItems
,
complexItems
,
errorString
);
}
}
bool
MissionController
::
_loadJsonMissionFileV1
(
const
QJsonObject
&
json
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
)
bool
MissionController
::
_loadJsonMissionFileV1
(
Vehicle
*
vehicle
,
const
QJsonObject
&
json
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
)
{
// Validate root object keys
QList
<
JsonHelper
::
KeyValidateInfo
>
rootKeyInfoList
=
{
...
...
@@ -325,7 +330,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
return
false
;
}
SurveyMissionItem
*
item
=
new
SurveyMissionItem
(
_activeVehicle
,
thi
s
);
SurveyMissionItem
*
item
=
new
SurveyMissionItem
(
vehicle
,
visualItem
s
);
const
QJsonObject
itemObject
=
itemValue
.
toObject
();
if
(
item
->
load
(
itemObject
,
itemObject
[
"id"
].
toInt
(),
errorString
))
{
complexItems
->
append
(
item
);
...
...
@@ -368,7 +373,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
}
const
QJsonObject
itemObject
=
itemValue
.
toObject
();
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
_activeVehicle
,
thi
s
);
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
vehicle
,
visualItem
s
);
if
(
item
->
load
(
itemObject
,
itemObject
[
"id"
].
toInt
(),
errorString
))
{
qCDebug
(
MissionControllerLog
)
<<
"Json load: adding simple item expectedSequence:actualSequence"
<<
nextSequenceNumber
<<
item
->
sequenceNumber
();
visualItems
->
append
(
item
);
...
...
@@ -381,7 +386,7 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
}
while
(
nextSimpleItemIndex
<
itemArray
.
count
()
||
nextComplexItemIndex
<
complexItems
->
count
());
if
(
json
.
contains
(
_jsonPlannedHomePositionKey
))
{
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
_activeVehicle
,
thi
s
);
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
vehicle
,
visualItem
s
);
if
(
item
->
load
(
json
[
_jsonPlannedHomePositionKey
].
toObject
(),
0
,
errorString
))
{
visualItems
->
insert
(
0
,
item
);
...
...
@@ -389,13 +394,13 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
return
false
;
}
}
else
{
_addPlannedHomePosition
(
visualItems
,
true
/* addToCenter */
);
_addPlannedHomePosition
(
vehicle
,
visualItems
,
true
/* addToCenter */
);
}
return
true
;
}
bool
MissionController
::
_loadJsonMissionFileV2
(
const
QJsonObject
&
json
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
)
bool
MissionController
::
_loadJsonMissionFileV2
(
Vehicle
*
vehicle
,
const
QJsonObject
&
json
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
)
{
// Validate root object keys
QList
<
JsonHelper
::
KeyValidateInfo
>
rootKeyInfoList
=
{
...
...
@@ -417,7 +422,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if
(
!
JsonHelper
::
loadGeoCoordinate
(
json
[
_jsonPlannedHomePositionKey
],
true
/* altitudeRequired */
,
homeCoordinate
,
errorString
))
{
return
false
;
}
if
(
json
.
contains
(
_jsonVehicleTypeKey
)
&&
_activeV
ehicle
->
isOfflineEditingVehicle
())
{
if
(
json
.
contains
(
_jsonVehicleTypeKey
)
&&
v
ehicle
->
isOfflineEditingVehicle
())
{
QGroundControlQmlGlobal
::
offlineEditingVehicleType
()
->
setRawValue
(
json
[
_jsonVehicleTypeKey
].
toDouble
());
}
if
(
json
.
contains
(
_jsonCruiseSpeedKey
))
{
...
...
@@ -427,7 +432,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
QGroundControlQmlGlobal
::
offlineEditingHoverSpeed
()
->
setRawValue
(
json
[
_jsonHoverSpeedKey
].
toDouble
());
}
SimpleMissionItem
*
homeItem
=
new
SimpleMissionItem
(
_activeVehicle
,
thi
s
);
SimpleMissionItem
*
homeItem
=
new
SimpleMissionItem
(
vehicle
,
visualItem
s
);
homeItem
->
setCoordinate
(
homeCoordinate
);
visualItems
->
insert
(
0
,
homeItem
);
qCDebug
(
MissionControllerLog
)
<<
"plannedHomePosition"
<<
homeCoordinate
;
...
...
@@ -457,7 +462,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if
(
itemType
==
VisualMissionItem
::
jsonTypeSimpleItemValue
)
{
qCDebug
(
MissionControllerLog
)
<<
"Loading MISSION_ITEM: nextSequenceNumber"
<<
nextSequenceNumber
;
SimpleMissionItem
*
simpleItem
=
new
SimpleMissionItem
(
_activeVehicle
,
thi
s
);
SimpleMissionItem
*
simpleItem
=
new
SimpleMissionItem
(
vehicle
,
visualItem
s
);
if
(
simpleItem
->
load
(
itemObject
,
nextSequenceNumber
++
,
errorString
))
{
visualItems
->
append
(
simpleItem
);
}
else
{
...
...
@@ -474,7 +479,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if
(
complexItemType
==
SurveyMissionItem
::
jsonComplexItemTypeValue
)
{
qCDebug
(
MissionControllerLog
)
<<
"Loading Survey: nextSequenceNumber"
<<
nextSequenceNumber
;
SurveyMissionItem
*
surveyItem
=
new
SurveyMissionItem
(
_activeVehicle
,
thi
s
);
SurveyMissionItem
*
surveyItem
=
new
SurveyMissionItem
(
vehicle
,
visualItem
s
);
if
(
!
surveyItem
->
load
(
itemObject
,
nextSequenceNumber
++
,
errorString
))
{
return
false
;
}
...
...
@@ -519,7 +524,7 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
return
true
;
}
bool
MissionController
::
_loadTextMissionFile
(
QTextStream
&
stream
,
QmlObjectListModel
*
visualItems
,
QString
&
errorString
)
bool
MissionController
::
_loadTextMissionFile
(
Vehicle
*
vehicle
,
QTextStream
&
stream
,
QmlObjectListModel
*
visualItems
,
QString
&
errorString
)
{
bool
addPlannedHomePosition
=
false
;
...
...
@@ -540,7 +545,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
if
(
versionOk
)
{
while
(
!
stream
.
atEnd
())
{
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
_activeVehicle
,
thi
s
);
SimpleMissionItem
*
item
=
new
SimpleMissionItem
(
vehicle
,
visualItem
s
);
if
(
item
->
load
(
stream
))
{
visualItems
->
append
(
item
);
...
...
@@ -555,7 +560,7 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
}
if
(
addPlannedHomePosition
||
visualItems
->
count
()
==
0
)
{
_addPlannedHomePosition
(
visualItems
,
true
/* addToCenter */
);
_addPlannedHomePosition
(
vehicle
,
visualItems
,
true
/* addToCenter */
);
// Update sequence numbers in DO_JUMP commands to take into account added home position in index 0
for
(
int
i
=
1
;
i
<
visualItems
->
count
();
i
++
)
{
...
...
@@ -571,19 +576,49 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
void
MissionController
::
loadFromFile
(
const
QString
&
filename
)
{
QmlObjectListModel
*
newVisualItems
=
NULL
;
QmlObjectListModel
*
newComplexItems
=
NULL
;
if
(
!
loadItemsFromFile
(
_activeVehicle
,
filename
,
&
newVisualItems
,
&
newComplexItems
))
{
return
;
}
if
(
_visualItems
)
{
_deinitAllVisualItems
();
_visualItems
->
deleteLater
();
}
if
(
_complexItems
)
{
_complexItems
->
deleteLater
();
}
_visualItems
=
newVisualItems
;
_complexItems
=
newComplexItems
;
if
(
_visualItems
->
count
()
==
0
)
{
_addPlannedHomePosition
(
_activeVehicle
,
_visualItems
,
true
/* addToCenter */
);
}
_initAllVisualItems
();
}
bool
MissionController
::
loadItemsFromFile
(
Vehicle
*
vehicle
,
const
QString
&
filename
,
QmlObjectListModel
**
visualItems
,
QmlObjectListModel
**
complexItems
)
{
*
visualItems
=
NULL
;
*
complexItems
=
NULL
;
QString
errorString
;
if
(
filename
.
isEmpty
())
{
return
;
return
false
;
}
QmlObjectListModel
*
newV
isualItems
=
new
QmlObjectListModel
(
this
);
QmlObjectListModel
*
newC
omplexItems
=
new
QmlObjectListModel
(
this
);
*
v
isualItems
=
new
QmlObjectListModel
();
*
c
omplexItems
=
new
QmlObjectListModel
();
QFile
file
(
filename
);
if
(
!
file
.
open
(
QIODevice
::
ReadOnly
|
QIODevice
::
Text
))
{
errorString
=
file
.
errorString
();
errorString
=
file
.
errorString
()
+
QStringLiteral
(
" "
)
+
filename
;
}
else
{
QByteArray
bytes
=
file
.
readAll
();
QTextStream
stream
(
&
bytes
);
...
...
@@ -591,42 +626,21 @@ void MissionController::loadFromFile(const QString& filename)
QString
firstLine
=
stream
.
readLine
();
if
(
firstLine
.
contains
(
QRegExp
(
"QGC.*WPL"
)))
{
stream
.
seek
(
0
);
_loadTextMissionFile
(
stream
,
newV
isualItems
,
errorString
);
_loadTextMissionFile
(
vehicle
,
stream
,
*
v
isualItems
,
errorString
);
}
else
{
_loadJsonMissionFile
(
bytes
,
newV
isualItems
,
newC
omplexItems
,
errorString
);
_loadJsonMissionFile
(
vehicle
,
bytes
,
*
v
isualItems
,
*
c
omplexItems
,
errorString
);
}
}
if
(
!
errorString
.
isEmpty
())
{
for
(
int
i
=
0
;
i
<
newVisualItems
->
count
();
i
++
)
{
newVisualItems
->
get
(
i
)
->
deleteLater
();
}
for
(
int
i
=
0
;
i
<
newComplexItems
->
count
();
i
++
)
{
newComplexItems
->
get
(
i
)
->
deleteLater
();
}
delete
newVisualItems
;
delete
newComplexItems
;
(
*
visualItems
)
->
deleteLater
();
(
*
complexItems
)
->
deleteLater
();
qgcApp
()
->
showMessage
(
errorString
);
return
;
}
if
(
_visualItems
)
{
_deinitAllVisualItems
();
_visualItems
->
deleteListAndContents
();
}
if
(
_complexItems
)
{
_complexItems
->
deleteLater
();
}
_visualItems
=
newVisualItems
;
_complexItems
=
newComplexItems
;
if
(
_visualItems
->
count
()
==
0
)
{
_addPlannedHomePosition
(
_visualItems
,
true
/* addToCenter */
);
return
false
;
}
_initAllVisualItems
()
;
return
true
;
}
void
MissionController
::
loadFromFilePicker
(
void
)
...
...
@@ -1394,11 +1408,11 @@ double MissionController::_normalizeLon(double lon)
}
/// Add the home position item to the front of the list
void
MissionController
::
_addPlannedHomePosition
(
QmlObjectListModel
*
visualItems
,
bool
addToCenter
)
void
MissionController
::
_addPlannedHomePosition
(
Vehicle
*
vehicle
,
QmlObjectListModel
*
visualItems
,
bool
addToCenter
)
{
bool
homePositionSet
=
false
;
SimpleMissionItem
*
homeItem
=
new
SimpleMissionItem
(
_activeVehicle
,
thi
s
);
SimpleMissionItem
*
homeItem
=
new
SimpleMissionItem
(
vehicle
,
visualItem
s
);
visualItems
->
insert
(
0
,
homeItem
);
if
(
visualItems
->
count
()
>
1
&&
addToCenter
)
{
...
...
src/MissionManager/MissionController.h
View file @
851d2c9c
...
...
@@ -59,6 +59,17 @@ public:
/// @return Sequence number for new item
Q_INVOKABLE
int
insertComplexMissionItem
(
QGeoCoordinate
coordinate
,
int
i
);
/// Loads the mission items from the specified file
/// @param[in] vehicle Vehicle we are loading items for
/// @param[in] filename File to load from
/// @param[out] visualItems Visual items loaded, returns NULL if error
/// @param[out] complexItems Complex items loaded, returns NULL if error
/// @return success/fail
static
bool
loadItemsFromFile
(
Vehicle
*
vehicle
,
const
QString
&
filename
,
QmlObjectListModel
**
visualItems
,
QmlObjectListModel
**
complexItems
);
/// Sends the mission items to the specified vehicle
static
void
sendItemsToVehicle
(
Vehicle
*
vehicle
,
QmlObjectListModel
*
visualMissionItems
);
// Overrides from PlanElementController
void
start
(
bool
editMode
)
final
;
void
startStaticActiveVehicle
(
Vehicle
*
vehicle
)
final
;
...
...
@@ -135,13 +146,13 @@ private:
static
double
_calcDistanceToHome
(
VisualMissionItem
*
currentItem
,
VisualMissionItem
*
homeItem
);
bool
_findLastAltitude
(
double
*
lastAltitude
,
MAV_FRAME
*
frame
);
bool
_findLastAcceptanceRadius
(
double
*
lastAcceptanceRadius
);
void
_addPlannedHomePosition
(
QmlObjectListModel
*
visualItems
,
bool
addToCenter
);
double
_normalizeL
at
(
double
l
at
);
double
_normalizeLon
(
double
lon
);
bool
_loadJsonMissionFile
(
const
QByteArray
&
bytes
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
);
bool
_loadJsonMissionFileV1
(
const
QJsonObject
&
json
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
);
bool
_loadJsonMissionFileV2
(
const
QJsonObject
&
json
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
);
bool
_loadTextMissionFile
(
QTextStream
&
stream
,
QmlObjectListModel
*
visualItems
,
QString
&
errorString
);
static
double
_normalizeLat
(
double
lat
);
static
double
_normalizeL
on
(
double
l
on
);
static
void
_addPlannedHomePosition
(
Vehicle
*
vehicle
,
QmlObjectListModel
*
visualItems
,
bool
addToCenter
);
static
bool
_loadJsonMissionFile
(
Vehicle
*
vehicle
,
const
QByteArray
&
bytes
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
);
static
bool
_loadJsonMissionFileV1
(
Vehicle
*
vehicle
,
const
QJsonObject
&
json
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
);
static
bool
_loadJsonMissionFileV2
(
Vehicle
*
vehicle
,
const
QJsonObject
&
json
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
);
static
bool
_loadTextMissionFile
(
Vehicle
*
vehicle
,
QTextStream
&
stream
,
QmlObjectListModel
*
visualItems
,
QString
&
errorString
);
int
_nextSequenceNumber
(
void
);
void
_setMissionDistance
(
double
missionDistance
);
void
_setMissionTime
(
double
missionTime
);
...
...
src/MissionManager/MissionLoader.h
0 → 100644
View file @
851d2c9c
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#ifndef MissionController_H
#define MissionController_H
#include
"PlanElementController.h"
#include
"QmlObjectListModel.h"
#include
"Vehicle.h"
#include
"QGCLoggingCategory.h"
#include
"MavlinkQmlSingleton.h"
#include
"VisualMissionItem.h"
#include
<QHash>
class
CoordinateVector
;
Q_DECLARE_LOGGING_CATEGORY
(
MissionControllerLog
)
typedef
QPair
<
VisualMissionItem
*
,
VisualMissionItem
*>
VisualItemPair
;
typedef
QHash
<
VisualItemPair
,
CoordinateVector
*>
CoordVectHashTable
;
class
MissionController
:
public
PlanElementController
{
Q_OBJECT
public:
MissionController
(
QObject
*
parent
=
NULL
);
~
MissionController
();
Q_PROPERTY
(
QGeoCoordinate
plannedHomePosition
READ
plannedHomePosition
NOTIFY
plannedHomePositionChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
visualItems
READ
visualItems
NOTIFY
visualItemsChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
complexVisualItems
READ
complexVisualItems
NOTIFY
complexVisualItemsChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
waypointLines
READ
waypointLines
NOTIFY
waypointLinesChanged
)
Q_PROPERTY
(
double
missionDistance
READ
missionDistance
NOTIFY
missionDistanceChanged
)
Q_PROPERTY
(
double
missionTime
READ
missionTime
NOTIFY
missionTimeChanged
)
Q_PROPERTY
(
double
missionHoverDistance
READ
missionHoverDistance
NOTIFY
missionHoverDistanceChanged
)
Q_PROPERTY
(
double
missionCruiseDistance
READ
missionCruiseDistance
NOTIFY
missionCruiseDistanceChanged
)
Q_PROPERTY
(
double
missionHoverTime
READ
missionHoverTime
NOTIFY
missionHoverTimeChanged
)
Q_PROPERTY
(
double
missionCruiseTime
READ
missionCruiseTime
NOTIFY
missionCruiseTimeChanged
)
Q_PROPERTY
(
double
missionMaxTelemetry
READ
missionMaxTelemetry
NOTIFY
missionMaxTelemetryChanged
)
Q_INVOKABLE
void
removeMissionItem
(
int
index
);
/// Add a new simple mission item to the list
/// @param i: index to insert at
/// @return Sequence number for new item
Q_INVOKABLE
int
insertSimpleMissionItem
(
QGeoCoordinate
coordinate
,
int
i
);
/// Add a new complex mission item to the list
/// @param i: index to insert at
/// @return Sequence number for new item
Q_INVOKABLE
int
insertComplexMissionItem
(
QGeoCoordinate
coordinate
,
int
i
);
// Overrides from PlanElementController
void
start
(
bool
editMode
)
final
;
void
startStaticActiveVehicle
(
Vehicle
*
vehicle
)
final
;
void
loadFromVehicle
(
void
)
final
;
void
sendToVehicle
(
void
)
final
;
void
loadFromFilePicker
(
void
)
final
;
void
loadFromFile
(
const
QString
&
filename
)
final
;
void
saveToFilePicker
(
void
)
final
;
void
saveToFile
(
const
QString
&
filename
)
final
;
void
removeAll
(
void
)
final
;
bool
syncInProgress
(
void
)
const
final
;
bool
dirty
(
void
)
const
final
;
void
setDirty
(
bool
dirty
)
final
;
QString
fileExtension
(
void
)
const
final
;
// Property accessors
QGeoCoordinate
plannedHomePosition
(
void
);
QmlObjectListModel
*
visualItems
(
void
)
{
return
_visualItems
;
}
QmlObjectListModel
*
complexVisualItems
(
void
)
{
return
_complexItems
;
}
QmlObjectListModel
*
waypointLines
(
void
)
{
return
&
_waypointLines
;
}
double
missionDistance
(
void
)
const
{
return
_missionDistance
;
}
double
missionTime
(
void
)
const
{
return
_missionTime
;
}
double
missionHoverDistance
(
void
)
const
{
return
_missionHoverDistance
;
}
double
missionHoverTime
(
void
)
const
{
return
_missionHoverTime
;
}
double
missionCruiseDistance
(
void
)
const
{
return
_missionCruiseDistance
;
}
double
missionCruiseTime
(
void
)
const
{
return
_missionCruiseTime
;
}
double
missionMaxTelemetry
(
void
)
const
{
return
_missionMaxTelemetry
;
}
double
cruiseSpeed
(
void
)
const
;
double
hoverSpeed
(
void
)
const
;
static
void
createVisualItemsFromFile
(
const
QString
&
filename
);
signals:
void
plannedHomePositionChanged
(
QGeoCoordinate
plannedHomePosition
);
void
visualItemsChanged
(
void
);
void
complexVisualItemsChanged
(
void
);
void
waypointLinesChanged
(
void
);
void
newItemsFromVehicle
(
void
);
void
missionDistanceChanged
(
double
missionDistance
);
void
missionTimeChanged
(
void
);
void
missionHoverDistanceChanged
(
double
missionHoverDistance
);
void
missionHoverTimeChanged
(
void
);
void
missionCruiseDistanceChanged
(
double
missionCruiseDistance
);
void
missionCruiseTimeChanged
(
void
);
void
missionMaxTelemetryChanged
(
double
missionMaxTelemetry
);
void
cruiseDistanceChanged
(
double
cruiseDistance
);
void
hoverDistanceChanged
(
double
hoverDistance
);
void
cruiseSpeedChanged
(
double
cruiseSpeed
);
void
hoverSpeedChanged
(
double
hoverSpeed
);
private
slots
:
void
_newMissionItemsAvailableFromVehicle
();
void
_itemCommandChanged
(
void
);
void
_activeVehicleHomePositionAvailableChanged
(
bool
homePositionAvailable
);
void
_activeVehicleHomePositionChanged
(
const
QGeoCoordinate
&
homePosition
);
void
_inProgressChanged
(
bool
inProgress
);
void
_currentMissionItemChanged
(
int
sequenceNumber
);
void
_recalcWaypointLines
(
void
);
void
_recalcAltitudeRangeBearing
(
void
);
void
_homeCoordinateChanged
(
void
);
private:
void
_init
(
void
);
void
_recalcSequence
(
void
);
void
_recalcChildItems
(
void
);
void
_recalcAll
(
void
);
void
_initAllVisualItems
(
void
);
void
_deinitAllVisualItems
(
void
);
void
_initVisualItem
(
VisualMissionItem
*
item
);
void
_deinitVisualItem
(
VisualMissionItem
*
item
);
void
_setupActiveVehicle
(
Vehicle
*
activeVehicle
,
bool
forceLoadFromVehicle
);
static
void
_calcPrevWaypointValues
(
double
homeAlt
,
VisualMissionItem
*
currentItem
,
VisualMissionItem
*
prevItem
,
double
*
azimuth
,
double
*
distance
,
double
*
altDifference
);
static
double
_calcDistanceToHome
(
VisualMissionItem
*
currentItem
,
VisualMissionItem
*
homeItem
);
bool
_findLastAltitude
(
double
*
lastAltitude
,
MAV_FRAME
*
frame
);
bool
_findLastAcceptanceRadius
(
double
*
lastAcceptanceRadius
);
void
_addPlannedHomePosition
(
QmlObjectListModel
*
visualItems
,
bool
addToCenter
);
double
_normalizeLat
(
double
lat
);
double
_normalizeLon
(
double
lon
);
bool
_loadJsonMissionFile
(
const
QByteArray
&
bytes
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
);
bool
_loadJsonMissionFileV1
(
const
QJsonObject
&
json
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
);
bool
_loadJsonMissionFileV2
(
const
QJsonObject
&
json
,
QmlObjectListModel
*
visualItems
,
QmlObjectListModel
*
complexItems
,
QString
&
errorString
);
bool
_loadTextMissionFile
(
QTextStream
&
stream
,
QmlObjectListModel
*
visualItems
,
QString
&
errorString
);
int
_nextSequenceNumber
(
void
);
void
_setMissionDistance
(
double
missionDistance
);
void
_setMissionTime
(
double
missionTime
);
void
_setMissionHoverDistance
(
double
missionHoverDistance
);
void
_setMissionHoverTime
(
double
missionHoverTime
);
void
_setMissionCruiseDistance
(
double
missionCruiseDistance
);
void
_setMissionCruiseTime
(
double
missionCruiseTime
);
void
_setMissionMaxTelemetry
(
double
missionMaxTelemetry
);
// Overrides from PlanElementController
void
_activeVehicleBeingRemoved
(
void
)
final
;
void
_activeVehicleSet
(
void
)
final
;
private:
QmlObjectListModel
*
_visualItems
;
QmlObjectListModel
*
_complexItems
;
QmlObjectListModel
_waypointLines
;
CoordVectHashTable
_linesTable
;
bool
_firstItemsFromVehicle
;
bool
_missionItemsRequested
;
bool
_queuedSend
;
double
_missionDistance
;
double
_missionTime
;
double
_missionHoverDistance
;
double
_missionHoverTime
;
double
_missionCruiseDistance
;
double
_missionCruiseTime
;
double
_missionMaxTelemetry
;
static
const
char
*
_settingsGroup
;
static
const
char
*
_jsonFileTypeValue
;
static
const
char
*
_jsonFirmwareTypeKey
;
static
const
char
*
_jsonVehicleTypeKey
;
static
const
char
*
_jsonCruiseSpeedKey
;
static
const
char
*
_jsonHoverSpeedKey
;
static
const
char
*
_jsonItemsKey
;
static
const
char
*
_jsonPlannedHomePositionKey
;
static
const
char
*
_jsonParamsKey
;
// Deprecated V1 format keys
static
const
char
*
_jsonMavAutopilotKey
;
static
const
char
*
_jsonComplexItemsKey
;
static
const
int
_missionFileVersion
;
};
#endif
src/MissionManager/RallyPointController.cc
View file @
851d2c9c
...
...
@@ -111,7 +111,7 @@ void RallyPointController::loadFromFile(const QString& filename)
QFile
file
(
filename
);
if
(
!
file
.
open
(
QIODevice
::
ReadOnly
|
QIODevice
::
Text
))
{
errorString
=
file
.
errorString
();
errorString
=
file
.
errorString
()
+
QStringLiteral
(
" "
)
+
filename
;
}
else
{
QJsonDocument
jsonDoc
;
QByteArray
bytes
=
file
.
readAll
();
...
...
src/QGCApplication.cc
View file @
851d2c9c
...
...
@@ -429,6 +429,9 @@ bool QGCApplication::_initForNormalAppBoot(void)
// Load known link configurations
toolbox
()
->
linkManager
()
->
loadLinkConfigurationList
();
// Probe for joysticks - TODO: manage on a timer or use events to deal with hotplug
toolbox
()
->
joystickManager
()
->
discoverJoysticks
();
if
(
_settingsUpgraded
)
{
settings
.
clear
();
settings
.
setValue
(
_settingsVersionKey
,
QGC_SETTINGS_VERSION
);
...
...
src/QGCPalette.cc
View file @
851d2c9c
...
...
@@ -42,7 +42,7 @@ QColor QGCPalette::_text[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = {
QColor
QGCPalette
::
_warningText
[
QGCPalette
::
_cThemes
][
QGCPalette
::
_cColorGroups
]
=
{
{
QColor
(
"#cc0808"
),
QColor
(
"#cc0808"
)
},
{
QColor
(
"
#e4e428"
),
QColor
(
"#e4e428
"
)
}
{
QColor
(
"
0xed, 0xd4, 0x69"
),
QColor
(
"0xed, 0xd4, 0x69
"
)
}
};
QColor
QGCPalette
::
_button
[
QGCPalette
::
_cThemes
][
QGCPalette
::
_cColorGroups
]
=
{
...
...
@@ -57,7 +57,7 @@ QColor QGCPalette::_buttonText[QGCPalette::_cThemes][QGCPalette::_cColorGroups]
QColor
QGCPalette
::
_buttonHighlight
[
QGCPalette
::
_cThemes
][
QGCPalette
::
_cColorGroups
]
=
{
{
QColor
(
"#e4e4e4"
),
QColor
(
"#33b5e5"
)
},
{
QColor
(
0x58
,
0x58
,
0x58
),
QColor
(
237
,
235
,
51
)
},
{
QColor
(
0x58
,
0x58
,
0x58
),
QColor
(
0xed
,
0xd4
,
0x69
)
},
};
QColor
QGCPalette
::
_buttonHighlightText
[
QGCPalette
::
_cThemes
][
QGCPalette
::
_cColorGroups
]
=
{
...
...
src/QmlControls/FlightModeMenu.qml
0 → 100644
View file @
851d2c9c
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import
QtQuick
2.5
import
QtQuick
.
Controls
1.2
import
QGroundControl
1.0
import
QGroundControl
.
Controls
1.0
import
QGroundControl
.
ScreenTools
1.0
// Label control whichs pop up a flight mode change menu when clicked
QGCLabel
{
id
:
flightModeMenuLabel
text
:
activeVehicle
?
activeVehicle
.
flightMode
:
qsTr
(
"
N/A
"
,
"
No data to display
"
)
property
var
activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
Menu
{
id
:
flightModesMenu
}
Component
{
id
:
flightModeMenuItemComponent
MenuItem
{
onTriggered
:
activeVehicle
.
flightMode
=
text
}
}
property
var
flightModesMenuItems
:
[]
function
updateFlightModesMenu
()
{
if
(
activeVehicle
&&
activeVehicle
.
flightModeSetAvailable
)
{
// Remove old menu items
for
(
var
i
=
0
;
i
<
flightModesMenuItems
.
length
;
i
++
)
{
flightModesMenu
.
removeItem
(
flightModesMenuItems
[
i
])
}
flightModesMenuItems
.
length
=
0
// Add new items
for
(
var
i
=
0
;
i
<
activeVehicle
.
flightModes
.
length
;
i
++
)
{
var
menuItem
=
flightModeMenuItemComponent
.
createObject
(
null
,
{
"
text
"
:
activeVehicle
.
flightModes
[
i
]
})
flightModesMenuItems
.
push
(
menuItem
)
flightModesMenu
.
insertItem
(
i
,
menuItem
)
}
}
}
Component.onCompleted
:
flightModeMenuLabel
.
updateFlightModesMenu
()
Connections
{
target
:
QGroundControl
.
multiVehicleManager
onActiveVehicleChanged
:
flightModeMenuLabel
.
updateFlightModesMenu
()
}
MouseArea
{
visible
:
activeVehicle
&&
activeVehicle
.
flightModeSetAvailable
anchors.fill
:
parent
onClicked
:
flightModesMenu
.
popup
()
}
}
Prev
1
2
3
Next
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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