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
96995949
Commit
96995949
authored
Feb 08, 2016
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Support command editor overrides
- override by vehicle type - override by firmware type
parent
8a049a99
Changes
28
Hide whitespace changes
Inline
Side-by-side
Showing
28 changed files
with
806 additions
and
417 deletions
+806
-417
qgroundcontrol.pro
qgroundcontrol.pro
+2
-0
qgroundcontrol.qrc
qgroundcontrol.qrc
+7
-1
APMFirmwarePlugin.cc
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+7
-0
APMFirmwarePlugin.h
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
+1
-0
MavCmdInfoCommon.json
src/FirmwarePlugin/APM/MavCmdInfoCommon.json
+6
-0
MavCmdInfoFixedWing.json
src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json
+21
-0
MavCmdInfoMultiRotor.json
src/FirmwarePlugin/APM/MavCmdInfoMultiRotor.json
+59
-0
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+6
-0
GenericFirmwarePlugin.cc
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc
+8
-0
GenericFirmwarePlugin.h
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h
+13
-13
MavCmdInfoCommon.json
src/FirmwarePlugin/PX4/MavCmdInfoCommon.json
+6
-0
MavCmdInfoFixedWing.json
src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json
+6
-0
MavCmdInfoMultiRotor.json
src/FirmwarePlugin/PX4/MavCmdInfoMultiRotor.json
+44
-0
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+8
-0
PX4FirmwarePlugin.h
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
+13
-12
MavCmdInfoCommon.json
src/MissionManager/MavCmdInfoCommon.json
+0
-0
MissionCommandList.cc
src/MissionManager/MissionCommandList.cc
+274
-0
MissionCommandList.h
src/MissionManager/MissionCommandList.h
+174
-0
MissionCommands.cc
src/MissionManager/MissionCommands.cc
+78
-231
MissionCommands.h
src/MissionManager/MissionCommands.h
+25
-128
MissionController.cc
src/MissionManager/MissionController.cc
+3
-3
MissionItem.cc
src/MissionManager/MissionItem.cc
+29
-20
MissionItem.h
src/MissionManager/MissionItem.h
+5
-3
MissionItemTest.cc
src/MissionManager/MissionItemTest.cc
+4
-3
MissionManager.cc
src/MissionManager/MissionManager.cc
+2
-1
MissionManagerTest.cc
src/MissionManager/MissionManagerTest.cc
+2
-2
QGCLoggingCategory.cc
src/QGCLoggingCategory.cc
+2
-0
QGCLoggingCategory.h
src/QGCLoggingCategory.h
+1
-0
No files found.
qgroundcontrol.pro
View file @
96995949
...
@@ -251,6 +251,7 @@ HEADERS += \
...
@@ -251,6 +251,7 @@ HEADERS += \
src
/
Joystick
/
JoystickManager
.
h
\
src
/
Joystick
/
JoystickManager
.
h
\
src
/
LogCompressor
.
h
\
src
/
LogCompressor
.
h
\
src
/
MG
.
h
\
src
/
MG
.
h
\
src
/
MissionManager
/
MissionCommandList
.
h
\
src
/
MissionManager
/
MissionCommands
.
h
\
src
/
MissionManager
/
MissionCommands
.
h
\
src
/
MissionManager
/
MissionController
.
h
\
src
/
MissionManager
/
MissionController
.
h
\
src
/
MissionManager
/
MissionItem
.
h
\
src
/
MissionManager
/
MissionItem
.
h
\
...
@@ -374,6 +375,7 @@ SOURCES += \
...
@@ -374,6 +375,7 @@ SOURCES += \
src
/
Joystick
/
JoystickManager
.
cc
\
src
/
Joystick
/
JoystickManager
.
cc
\
src
/
LogCompressor
.
cc
\
src
/
LogCompressor
.
cc
\
src
/
main
.
cc
\
src
/
main
.
cc
\
src
/
MissionManager
/
MissionCommandList
.
cc
\
src
/
MissionManager
/
MissionCommands
.
cc
\
src
/
MissionManager
/
MissionCommands
.
cc
\
src
/
MissionManager
/
MissionController
.
cc
\
src
/
MissionManager
/
MissionController
.
cc
\
src
/
MissionManager
/
MissionItem
.
cc
\
src
/
MissionManager
/
MissionItem
.
cc
\
...
...
qgroundcontrol.qrc
View file @
96995949
...
@@ -141,6 +141,12 @@
...
@@ -141,6 +141,12 @@
<file alias="VehicleSummary.qml">src/VehicleSetup/VehicleSummary.qml</file>
<file alias="VehicleSummary.qml">src/VehicleSetup/VehicleSummary.qml</file>
</qresource>
</qresource>
<qresource prefix="/json">
<qresource prefix="/json">
<file alias="MavCmdInfo.json">src/MissionManager/MavCmdInfo.json</file>
<file alias="MavCmdInfoCommon.json">src/MissionManager/MavCmdInfoCommon.json</file>
<file alias="APM/MavCmdInfoCommon.json">src/FirmwarePlugin/APM/MavCmdInfoCommon.json</file>
<file alias="APM/MavCmdInfoFixedWing.json">src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json</file>
<file alias="APM/MavCmdInfoMultiRotor.json">src/FirmwarePlugin/APM/MavCmdInfoMultiRotor.json</file>
<file alias="PX4/MavCmdInfoCommon.json">src/FirmwarePlugin/PX4/MavCmdInfoCommon.json</file>
<file alias="PX4/MavCmdInfoFixedWing.json">src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json</file>
<file alias="PX4/MavCmdInfoMultiRotor.json">src/FirmwarePlugin/PX4/MavCmdInfoMultiRotor.json</file>
</qresource>
</qresource>
</RCC>
</RCC>
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
View file @
96995949
...
@@ -495,3 +495,10 @@ QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
...
@@ -495,3 +495,10 @@ QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
<<
MAV_CMD_CONDITION_DELAY
<<
MAV_CMD_CONDITION_CHANGE_ALT
<<
MAV_CMD_CONDITION_DISTANCE
<<
MAV_CMD_CONDITION_YAW
;
<<
MAV_CMD_CONDITION_DELAY
<<
MAV_CMD_CONDITION_CHANGE_ALT
<<
MAV_CMD_CONDITION_DISTANCE
<<
MAV_CMD_CONDITION_YAW
;
return
list
;
return
list
;
}
}
void
APMFirmwarePlugin
::
missionCommandOverrides
(
QString
&
commonJsonFilename
,
QString
&
fixedWingJsonFilename
,
QString
&
multiRotorJsonFilename
)
const
{
commonJsonFilename
=
QStringLiteral
(
":/json/APM/MavCmdInfoCommon.json"
);
fixedWingJsonFilename
=
QStringLiteral
(
":/json/APM/MavCmdInfoFixedWing.json"
);
multiRotorJsonFilename
=
QStringLiteral
(
":/json/APM/MavCmdInfoMultiRotor.json"
);
}
src/FirmwarePlugin/APM/APMFirmwarePlugin.h
View file @
96995949
...
@@ -92,6 +92,7 @@ public:
...
@@ -92,6 +92,7 @@ public:
virtual
void
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
);
virtual
void
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
);
virtual
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
(
"SYSID_SW_TYPE"
);
}
virtual
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
(
"SYSID_SW_TYPE"
);
}
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
void
missionCommandOverrides
(
QString
&
commonJsonFilename
,
QString
&
fixedWingJsonFilename
,
QString
&
multiRotorJsonFilename
)
const
final
;
protected:
protected:
/// All access to singleton is through stack specific implementation
/// All access to singleton is through stack specific implementation
...
...
src/FirmwarePlugin/APM/MavCmdInfoCommon.json
0 → 100644
View file @
96995949
{
"version"
:
1
,
"mavCmdInfo"
:
[
]
}
src/FirmwarePlugin/APM/MavCmdInfoFixedWing.json
0 → 100644
View file @
96995949
{
"version"
:
1
,
"mavCmdInfo"
:
[
{
"id"
:
22
,
"rawName"
:
"MAV_CMD_NAV_TAKEOFF"
,
"friendlyName"
:
"Takeoff"
,
"description"
:
"Take off from the ground."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Pitch:"
,
"units"
:
"radians"
,
"default"
:
0.26179939
,
"decimalPlaces"
:
2
}
}
]
}
src/FirmwarePlugin/APM/MavCmdInfoMultiRotor.json
0 → 100644
View file @
96995949
{
"version"
:
1
,
"mavCmdInfo"
:
[
{
"id"
:
22
,
"rawName"
:
"MAV_CMD_NAV_TAKEOFF"
,
"friendlyName"
:
"Takeoff"
,
"description"
:
"Take off from the ground."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
},
{
"id"
:
17
,
"rawName"
:
"MAV_CMD_NAV_LOITER_UNLIM"
,
"friendlyName"
:
"Loiter"
,
"description"
:
"Travel to a position and Loiter indefinitely."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
},
{
"id"
:
18
,
"rawName"
:
"MAV_CMD_NAV_LOITER_TURNS"
,
"friendlyName"
:
"Loiter (turns)"
,
"description"
:
"Travel to a position and Circle with the specified radius for a number of turns."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Turns:"
,
"default"
:
1
,
"decimalPlaces"
:
0
},
"param3"
:
{
"label"
:
"Radius:"
,
"units"
:
"meters"
,
"default"
:
10.0
,
"decimalPlaces"
:
2
}
},
{
"id"
:
19
,
"rawName"
:
"MAV_CMD_NAV_LOITER_TIME"
,
"friendlyName"
:
"Loiter (time)"
,
"description"
:
"Travel to a position and Loiter for an amount of time."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Hold:"
,
"units"
:
"seconds"
,
"default"
:
30
,
"decimalPlaces"
:
0
}
}
]
}
src/FirmwarePlugin/FirmwarePlugin.h
View file @
96995949
...
@@ -113,6 +113,12 @@ public:
...
@@ -113,6 +113,12 @@ public:
/// List of supported mission commands. Empty list for all commands supported.
/// List of supported mission commands. Empty list for all commands supported.
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
)
=
0
;
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
)
=
0
;
/// Returns the names for the mission command json override files. Empty string to specify no overrides.
/// @param[out] commonJsonFilename Filename for common overrides
/// @param[out] fixedWingJsonFilename Filename for fixed wing overrides
/// @param[out] multiRotorJsonFilename Filename for multi rotor overrides
virtual
void
missionCommandOverrides
(
QString
&
commonJsonFilename
,
QString
&
fixedWingJsonFilename
,
QString
&
multiRotorJsonFilename
)
const
=
0
;
};
};
#endif
#endif
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc
View file @
96995949
...
@@ -127,3 +127,11 @@ QList<MAV_CMD> GenericFirmwarePlugin::supportedMissionCommands(void)
...
@@ -127,3 +127,11 @@ QList<MAV_CMD> GenericFirmwarePlugin::supportedMissionCommands(void)
// Generic supports all commands
// Generic supports all commands
return
QList
<
MAV_CMD
>
();
return
QList
<
MAV_CMD
>
();
}
}
void
GenericFirmwarePlugin
::
missionCommandOverrides
(
QString
&
commonJsonFilename
,
QString
&
fixedWingJsonFilename
,
QString
&
multiRotorJsonFilename
)
const
{
// No overrides
commonJsonFilename
.
clear
();
fixedWingJsonFilename
.
clear
();
multiRotorJsonFilename
.
clear
();
}
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h
View file @
96995949
...
@@ -35,19 +35,19 @@ class GenericFirmwarePlugin : public FirmwarePlugin
...
@@ -35,19 +35,19 @@ class GenericFirmwarePlugin : public FirmwarePlugin
public:
public:
// Overrides from FirmwarePlugin
// Overrides from FirmwarePlugin
bool
isCapable
(
FirmwareCapabilities
capabilities
)
final
{
Q_UNUSED
(
capabilities
);
return
false
;
}
virtual
bool
isCapable
(
FirmwareCapabilities
capabilities
)
{
Q_UNUSED
(
capabilities
);
return
false
;
}
QList
<
VehicleComponent
*>
componentsForVehicle
(
AutoPilotPlugin
*
vehicle
)
final
;
virtual
QList
<
VehicleComponent
*>
componentsForVehicle
(
AutoPilotPlugin
*
vehicle
);
QStringList
flightModes
(
void
)
final
{
return
QStringList
();
}
virtual
QStringList
flightModes
(
void
)
{
return
QStringList
();
}
QString
flightMode
(
uint8_t
base_mode
,
uint32_t
custom_mode
)
final
;
virtual
QString
flightMode
(
uint8_t
base_mode
,
uint32_t
custom_mode
)
;
bool
setFlightMode
(
const
QString
&
flightMode
,
uint8_t
*
base_mode
,
uint32_t
*
custom_mode
)
final
;
virtual
bool
setFlightMode
(
const
QString
&
flightMode
,
uint8_t
*
base_mode
,
uint32_t
*
custom_mode
)
;
int
manualControlReservedButtonCount
(
void
)
final
;
v
irtual
int
manualControlReservedButtonCount
(
void
)
;
v
oid
adjustMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
final
;
v
irtual
void
adjustMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
;
v
oid
initializeVehicle
(
Vehicle
*
vehicle
)
final
;
virtual
void
initializeVehicle
(
Vehicle
*
vehicle
)
;
bool
sendHomePositionToVehicle
(
void
)
final
;
v
irtual
bool
sendHomePositionToVehicle
(
void
)
;
v
oid
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
)
final
;
virtual
void
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
);
QString
getDefaultComponentIdParam
(
void
)
const
final
{
return
QString
();
}
virtual
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
();
}
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
)
final
;
v
irtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
)
;
v
oid
missionCommandOverrides
(
QString
&
commonJsonFilename
,
QString
&
fixedWingJsonFilename
,
QString
&
multiRotorJsonFilename
)
const
final
;
};
};
#endif
#endif
src/FirmwarePlugin/PX4/MavCmdInfoCommon.json
0 → 100644
View file @
96995949
{
"version"
:
1
,
"mavCmdInfo"
:
[
]
}
src/FirmwarePlugin/PX4/MavCmdInfoFixedWing.json
0 → 100644
View file @
96995949
{
"version"
:
1
,
"mavCmdInfo"
:
[
]
}
src/FirmwarePlugin/PX4/MavCmdInfoMultiRotor.json
0 → 100644
View file @
96995949
{
"version"
:
1
,
"mavCmdInfo"
:
[
{
"id"
:
17
,
"rawName"
:
"MAV_CMD_NAV_LOITER_UNLIM"
,
"friendlyName"
:
"Loiter"
,
"description"
:
"Travel to a position and Loiter indefinitely."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
},
{
"id"
:
18
,
"rawName"
:
"MAV_CMD_NAV_LOITER_TURNS"
,
"friendlyName"
:
"Loiter (turns)"
,
"description"
:
"Travel to a position and Loiter for a number of turns."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Turns:"
,
"default"
:
1
,
"decimalPlaces"
:
0
}
},
{
"id"
:
19
,
"rawName"
:
"MAV_CMD_NAV_LOITER_TIME"
,
"friendlyName"
:
"Loiter (time)"
,
"description"
:
"Travel to a position and Loiter for an amount of time."
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"param1"
:
{
"label"
:
"Hold:"
,
"units"
:
"seconds"
,
"default"
:
30
,
"decimalPlaces"
:
0
}
}
]
}
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
96995949
...
@@ -225,3 +225,11 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
...
@@ -225,3 +225,11 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
<<
MAV_CMD_DO_CHANGE_SPEED
;
<<
MAV_CMD_DO_CHANGE_SPEED
;
return
list
;
return
list
;
}
}
void
PX4FirmwarePlugin
::
missionCommandOverrides
(
QString
&
commonJsonFilename
,
QString
&
fixedWingJsonFilename
,
QString
&
multiRotorJsonFilename
)
const
{
// No overrides
commonJsonFilename
=
QStringLiteral
(
":/json/PX4/MavCmdInfoCommon.json"
);
fixedWingJsonFilename
=
QStringLiteral
(
":/json/PX4/MavCmdInfoFixedWing.json"
);
multiRotorJsonFilename
=
QStringLiteral
(
":/json/PX4/MavCmdInfoMultiRotor.json"
);
}
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
View file @
96995949
...
@@ -36,18 +36,19 @@ class PX4FirmwarePlugin : public FirmwarePlugin
...
@@ -36,18 +36,19 @@ class PX4FirmwarePlugin : public FirmwarePlugin
public:
public:
// Overrides from FirmwarePlugin
// Overrides from FirmwarePlugin
virtual
bool
isCapable
(
FirmwareCapabilities
capabilities
);
bool
isCapable
(
FirmwareCapabilities
capabilities
)
final
;
virtual
QList
<
VehicleComponent
*>
componentsForVehicle
(
AutoPilotPlugin
*
vehicle
);
QList
<
VehicleComponent
*>
componentsForVehicle
(
AutoPilotPlugin
*
vehicle
)
final
;
virtual
QStringList
flightModes
(
void
);
QStringList
flightModes
(
void
)
final
;
virtual
QString
flightMode
(
uint8_t
base_mode
,
uint32_t
custom_mode
);
QString
flightMode
(
uint8_t
base_mode
,
uint32_t
custom_mode
)
final
;
virtual
bool
setFlightMode
(
const
QString
&
flightMode
,
uint8_t
*
base_mode
,
uint32_t
*
custom_mode
);
bool
setFlightMode
(
const
QString
&
flightMode
,
uint8_t
*
base_mode
,
uint32_t
*
custom_mode
)
final
;
virtual
int
manualControlReservedButtonCount
(
void
);
int
manualControlReservedButtonCount
(
void
)
final
;
virtual
void
adjustMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
);
void
adjustMavlinkMessage
(
Vehicle
*
vehicle
,
mavlink_message_t
*
message
)
final
;
virtual
void
initializeVehicle
(
Vehicle
*
vehicle
);
void
initializeVehicle
(
Vehicle
*
vehicle
)
final
;
virtual
bool
sendHomePositionToVehicle
(
void
);
bool
sendHomePositionToVehicle
(
void
)
final
;
virtual
void
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
);
void
addMetaDataToFact
(
Fact
*
fact
,
MAV_TYPE
vehicleType
)
final
;
virtual
QString
getDefaultComponentIdParam
(
void
)
const
{
return
QString
(
"SYS_AUTOSTART"
);
}
QString
getDefaultComponentIdParam
(
void
)
const
final
{
return
QString
(
"SYS_AUTOSTART"
);
}
virtual
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
);
QList
<
MAV_CMD
>
supportedMissionCommands
(
void
)
final
;
void
missionCommandOverrides
(
QString
&
commonJsonFilename
,
QString
&
fixedWingJsonFilename
,
QString
&
multiRotorJsonFilename
)
const
final
;
private:
private:
PX4ParameterMetaData
_parameterMetaData
;
PX4ParameterMetaData
_parameterMetaData
;
...
...
src/MissionManager/MavCmdInfo.json
→
src/MissionManager/MavCmdInfo
Common
.json
View file @
96995949
File moved
src/MissionManager/MissionCommandList.cc
0 → 100644
View file @
96995949
/*===================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#include "MissionCommandList.h"
#include "FactMetaData.h"
#include "Vehicle.h"
#include "FirmwarePluginManager.h"
#include "QGCApplication.h"
#include "QGroundControlQmlGlobal.h"
#include <QStringList>
#include <QJsonDocument>
#include <QJsonParseError>
#include <QJsonArray>
#include <QDebug>
#include <QFile>
const
QString
MissionCommandList
::
_categoryJsonKey
(
QStringLiteral
(
"category"
));
const
QString
MissionCommandList
::
_decimalPlacesJsonKey
(
QStringLiteral
(
"decimalPlaces"
));
const
QString
MissionCommandList
::
_defaultJsonKey
(
QStringLiteral
(
"default"
));
const
QString
MissionCommandList
::
_descriptionJsonKey
(
QStringLiteral
(
"description"
));
const
QString
MissionCommandList
::
_enumStringsJsonKey
(
QStringLiteral
(
"enumStrings"
));
const
QString
MissionCommandList
::
_enumValuesJsonKey
(
QStringLiteral
(
"enumValues"
));
const
QString
MissionCommandList
::
_friendlyEditJsonKey
(
QStringLiteral
(
"friendlyEdit"
));
const
QString
MissionCommandList
::
_friendlyNameJsonKey
(
QStringLiteral
(
"friendlyName"
));
const
QString
MissionCommandList
::
_idJsonKey
(
QStringLiteral
(
"id"
));
const
QString
MissionCommandList
::
_labelJsonKey
(
QStringLiteral
(
"label"
));
const
QString
MissionCommandList
::
_mavCmdInfoJsonKey
(
QStringLiteral
(
"mavCmdInfo"
));
const
QString
MissionCommandList
::
_param1JsonKey
(
QStringLiteral
(
"param1"
));
const
QString
MissionCommandList
::
_param2JsonKey
(
QStringLiteral
(
"param2"
));
const
QString
MissionCommandList
::
_param3JsonKey
(
QStringLiteral
(
"param3"
));
const
QString
MissionCommandList
::
_param4JsonKey
(
QStringLiteral
(
"param4"
));
const
QString
MissionCommandList
::
_paramJsonKeyFormat
(
QStringLiteral
(
"param%1"
));
const
QString
MissionCommandList
::
_rawNameJsonKey
(
QStringLiteral
(
"rawName"
));
const
QString
MissionCommandList
::
_standaloneCoordinateJsonKey
(
QStringLiteral
(
"standaloneCoordinate"
));
const
QString
MissionCommandList
::
_specifiesCoordinateJsonKey
(
QStringLiteral
(
"specifiesCoordinate"
));
const
QString
MissionCommandList
::
_unitsJsonKey
(
QStringLiteral
(
"units"
));
const
QString
MissionCommandList
::
_versionJsonKey
(
QStringLiteral
(
"version"
));
MissionCommandList
::
MissionCommandList
(
const
QString
&
jsonFilename
,
QObject
*
parent
)
:
QObject
(
parent
)
{
_loadMavCmdInfoJson
(
jsonFilename
);
}
bool
MissionCommandList
::
_validateKeyTypes
(
QJsonObject
&
jsonObject
,
const
QStringList
&
keys
,
const
QList
<
QJsonValue
::
Type
>&
types
)
{
for
(
int
i
=
0
;
i
<
keys
.
count
();
i
++
)
{
if
(
jsonObject
.
contains
(
keys
[
i
]))
{
if
(
jsonObject
.
value
(
keys
[
i
]).
type
()
!=
types
[
i
])
{
qWarning
()
<<
"Incorrect type key:type:expected"
<<
keys
[
i
]
<<
jsonObject
.
value
(
keys
[
i
]).
type
()
<<
types
[
i
];
return
false
;
}
}
}
return
true
;
}
void
MissionCommandList
::
_loadMavCmdInfoJson
(
const
QString
&
jsonFilename
)
{
if
(
jsonFilename
.
isEmpty
())
{
return
;
}
qCDebug
(
MissionCommandsLog
)
<<
"Loading"
<<
jsonFilename
;
QFile
jsonFile
(
jsonFilename
);
if
(
!
jsonFile
.
open
(
QIODevice
::
ReadOnly
|
QIODevice
::
Text
))
{
qWarning
()
<<
"Unable to open file"
<<
jsonFilename
<<
jsonFile
.
errorString
();
return
;
}
QByteArray
bytes
=
jsonFile
.
readAll
();
jsonFile
.
close
();
QJsonParseError
jsonParseError
;
QJsonDocument
doc
=
QJsonDocument
::
fromJson
(
bytes
,
&
jsonParseError
);
if
(
jsonParseError
.
error
!=
QJsonParseError
::
NoError
)
{
qWarning
()
<<
"Unable to open json document"
<<
jsonParseError
.
errorString
();
return
;
}
QJsonObject
json
=
doc
.
object
();
int
version
=
json
.
value
(
_versionJsonKey
).
toInt
();
if
(
version
!=
1
)
{
qWarning
()
<<
"Invalid version"
<<
version
;
return
;
}
QJsonValue
jsonValue
=
json
.
value
(
_mavCmdInfoJsonKey
);
if
(
!
jsonValue
.
isArray
())
{
qWarning
()
<<
"mavCmdInfo not array"
;
return
;
}
QJsonArray
jsonArray
=
jsonValue
.
toArray
();
foreach
(
QJsonValue
info
,
jsonArray
)
{
if
(
!
info
.
isObject
())
{
qWarning
()
<<
"mavCmdArray should contain objects"
;
return
;
}
QJsonObject
jsonObject
=
info
.
toObject
();
// Make sure we have the required keys
QStringList
requiredKeys
;
requiredKeys
<<
_idJsonKey
<<
_rawNameJsonKey
;
foreach
(
const
QString
&
key
,
requiredKeys
)
{
if
(
!
jsonObject
.
contains
(
key
))
{
qWarning
()
<<
"Mission required key"
<<
key
;
return
;
}
}
// Validate key types
QStringList
keys
;
QList
<
QJsonValue
::
Type
>
types
;
keys
<<
_idJsonKey
<<
_rawNameJsonKey
<<
_friendlyNameJsonKey
<<
_descriptionJsonKey
<<
_standaloneCoordinateJsonKey
<<
_specifiesCoordinateJsonKey
<<
_friendlyEditJsonKey
<<
_param1JsonKey
<<
_param2JsonKey
<<
_param3JsonKey
<<
_param4JsonKey
<<
_categoryJsonKey
;
types
<<
QJsonValue
::
Double
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
String
;
if
(
!
_validateKeyTypes
(
jsonObject
,
keys
,
types
))
{
return
;
}
MavCmdInfo
*
mavCmdInfo
=
new
MavCmdInfo
(
this
);
mavCmdInfo
->
_command
=
(
MAV_CMD
)
jsonObject
.
value
(
_idJsonKey
).
toInt
();
mavCmdInfo
->
_category
=
jsonObject
.
value
(
_categoryJsonKey
).
toString
(
"Advanced"
);
mavCmdInfo
->
_rawName
=
jsonObject
.
value
(
_rawNameJsonKey
).
toString
();
mavCmdInfo
->
_friendlyName
=
jsonObject
.
value
(
_friendlyNameJsonKey
).
toString
(
QString
());
mavCmdInfo
->
_description
=
jsonObject
.
value
(
_descriptionJsonKey
).
toString
(
QString
());
mavCmdInfo
->
_standaloneCoordinate
=
jsonObject
.
value
(
_standaloneCoordinateJsonKey
).
toBool
(
false
);
mavCmdInfo
->
_specifiesCoordinate
=
jsonObject
.
value
(
_specifiesCoordinateJsonKey
).
toBool
(
false
);
mavCmdInfo
->
_friendlyEdit
=
jsonObject
.
value
(
_friendlyEditJsonKey
).
toBool
(
false
);
qCDebug
(
MissionCommandsLog
)
<<
"Command"
<<
mavCmdInfo
->
_command
<<
mavCmdInfo
->
_category
<<
mavCmdInfo
->
_rawName
<<
mavCmdInfo
->
_friendlyName
<<
mavCmdInfo
->
_description
<<
mavCmdInfo
->
_standaloneCoordinate
<<
mavCmdInfo
->
_specifiesCoordinate
<<
mavCmdInfo
->
_friendlyEdit
;
if
(
_mavCmdInfoMap
.
contains
((
MAV_CMD
)
mavCmdInfo
->
command
()))
{
qWarning
()
<<
"Duplicate command"
<<
mavCmdInfo
->
command
();
return
;
}
_mavCmdInfoMap
[
mavCmdInfo
->
_command
]
=
mavCmdInfo
;
// Read params
for
(
int
i
=
1
;
i
<=
7
;
i
++
)
{
QString
paramKey
=
QString
(
_paramJsonKeyFormat
).
arg
(
i
);
if
(
jsonObject
.
contains
(
paramKey
))
{
QJsonObject
paramObject
=
jsonObject
.
value
(
paramKey
).
toObject
();
// Validate key types
QStringList
keys
;
QList
<
QJsonValue
::
Type
>
types
;
keys
<<
_defaultJsonKey
<<
_decimalPlacesJsonKey
<<
_enumStringsJsonKey
<<
_enumValuesJsonKey
<<
_labelJsonKey
<<
_unitsJsonKey
;
types
<<
QJsonValue
::
Double
<<
QJsonValue
::
Double
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
String
;
if
(
!
_validateKeyTypes
(
paramObject
,
keys
,
types
))
{
return
;
}
mavCmdInfo
->
_friendlyEdit
=
true
;
// Assume friendly edit if we have params
if
(
!
paramObject
.
contains
(
_labelJsonKey
))
{
qWarning
()
<<
"param object missing label key"
<<
mavCmdInfo
->
rawName
()
<<
paramKey
;
return
;
}
MavCmdParamInfo
*
paramInfo
=
new
MavCmdParamInfo
(
this
);
paramInfo
->
_label
=
paramObject
.
value
(
_labelJsonKey
).
toString
();
paramInfo
->
_defaultValue
=
paramObject
.
value
(
_defaultJsonKey
).
toDouble
(
0.0
);
paramInfo
->
_decimalPlaces
=
paramObject
.
value
(
_decimalPlacesJsonKey
).
toInt
(
FactMetaData
::
defaultDecimalPlaces
);
paramInfo
->
_enumStrings
=
paramObject
.
value
(
_enumStringsJsonKey
).
toString
().
split
(
","
,
QString
::
SkipEmptyParts
);
paramInfo
->
_param
=
i
;
paramInfo
->
_units
=
paramObject
.
value
(
_unitsJsonKey
).
toString
();
QStringList
enumValues
=
paramObject
.
value
(
_enumValuesJsonKey
).
toString
().
split
(
","
,
QString
::
SkipEmptyParts
);
foreach
(
const
QString
&
enumValue
,
enumValues
)
{
bool
convertOk
;
double
value
=
enumValue
.
toDouble
(
&
convertOk
);
if
(
!
convertOk
)
{
qWarning
()
<<
"Bad enumValue"
<<
enumValue
;
return
;
}
paramInfo
->
_enumValues
<<
QVariant
(
value
);
}
if
(
paramInfo
->
_enumValues
.
count
()
!=
paramInfo
->
_enumStrings
.
count
())
{
qWarning
()
<<
"enum strings/values count mismatch"
<<
paramInfo
->
_enumStrings
.
count
()
<<
paramInfo
->
_enumValues
.
count
();
return
;
}
qCDebug
(
MissionCommandsLog
)
<<
"Param"
<<
paramInfo
->
_label
<<
paramInfo
->
_defaultValue
<<
paramInfo
->
_decimalPlaces
<<
paramInfo
->
_param
<<
paramInfo
->
_units
<<
paramInfo
->
_enumStrings
<<
paramInfo
->
_enumValues
;
mavCmdInfo
->
_paramInfoMap
[
i
]
=
paramInfo
;
}
}
if
(
mavCmdInfo
->
friendlyEdit
())
{
if
(
mavCmdInfo
->
description
().
isEmpty
())
{
qWarning
()
<<
"Missing description"
<<
mavCmdInfo
->
rawName
();
return
;
}
if
(
mavCmdInfo
->
rawName
()
==
mavCmdInfo
->
friendlyName
())
{
qWarning
()
<<
"Missing friendly name"
<<
mavCmdInfo
->
rawName
()
<<
mavCmdInfo
->
friendlyName
();
return
;
}
}
}
}
bool
MissionCommandList
::
contains
(
MAV_CMD
command
)
const
{
return
_mavCmdInfoMap
.
contains
(
command
);
}
MavCmdInfo
*
MissionCommandList
::
getMavCmdInfo
(
MAV_CMD
command
)
const
{
if
(
!
contains
(
command
))
{
qWarning
()
<<
"Unknown command"
<<
command
;
return
NULL
;
}
return
_mavCmdInfoMap
[
command
];
}
QList
<
MAV_CMD
>
MissionCommandList
::
commandsIds
(
void
)
const
{
QList
<
MAV_CMD
>
list
;
foreach
(
const
MavCmdInfo
*
mavCmdInfo
,
_mavCmdInfoMap
)
{
list
<<
(
MAV_CMD
)
mavCmdInfo
->
command
();
}
return
list
;
}
src/MissionManager/MissionCommandList.h
0 → 100644
View file @
96995949
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef MissionCommandList_H
#define MissionCommandList_H
#include "QGCToolbox.h"
#include "QGCMAVLink.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
#include "MavlinkQmlSingleton.h"
#include <QObject>
#include <QString>
#include <QJsonObject>
#include <QJsonValue>
class
MissionCommandList
;
class
Vehicle
;
/// The information associated with a mission command parameter.
class
MavCmdParamInfo
:
public
QObject
{
Q_OBJECT
public:
MavCmdParamInfo
(
QObject
*
parent
=
NULL
)
:
QObject
(
parent
)
{
}
Q_PROPERTY
(
int
decimalPlaces
READ
decimalPlaces
CONSTANT
)
Q_PROPERTY
(
double
defaultValue
READ
defaultValue
CONSTANT
)
Q_PROPERTY
(
QStringList
enumStrings
READ
enumStrings
CONSTANT
)
Q_PROPERTY
(
QVariantList
enumValues
READ
enumValues
CONSTANT
)
Q_PROPERTY
(
QString
label
READ
label
CONSTANT
)
Q_PROPERTY
(
int
param
READ
param
CONSTANT
)
Q_PROPERTY
(
QString
units
READ
units
CONSTANT
)
int
decimalPlaces
(
void
)
const
{
return
_decimalPlaces
;
}
double
defaultValue
(
void
)
const
{
return
_defaultValue
;
}
QStringList
enumStrings
(
void
)
const
{
return
_enumStrings
;
}
QVariantList
enumValues
(
void
)
const
{
return
_enumValues
;
}
QString
label
(
void
)
const
{
return
_label
;
}
int
param
(
void
)
const
{
return
_param
;
}
QString
units
(
void
)
const
{
return
_units
;
}
private:
int
_decimalPlaces
;
double
_defaultValue
;
QStringList
_enumStrings
;
QVariantList
_enumValues
;
QString
_label
;
int
_param
;
QString
_units
;
friend
class
MissionCommandList
;
};
// The information associated with a mission command.
class
MavCmdInfo
:
public
QObject
{
Q_OBJECT
public:
MavCmdInfo
(
QObject
*
parent
=
NULL
)
:
QObject
(
parent
)
{
}
Q_PROPERTY
(
QString
category
READ
category
CONSTANT
)
Q_PROPERTY
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
READ
qmlCommand
CONSTANT
)
Q_PROPERTY
(
QString
description
READ
description
CONSTANT
)
Q_PROPERTY
(
bool
friendlyEdit
READ
friendlyEdit
CONSTANT
)
Q_PROPERTY
(
QString
friendlyName
READ
friendlyName
CONSTANT
)
Q_PROPERTY
(
QString
rawName
READ
rawName
CONSTANT
)
Q_PROPERTY
(
bool
standaloneCoordinate
READ
standaloneCoordinate
CONSTANT
)
Q_PROPERTY
(
bool
specifiesCoordinate
READ
specifiesCoordinate
CONSTANT
)
MavlinkQmlSingleton
::
Qml_MAV_CMD
qmlCommand
(
void
)
const
{
return
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
)
_command
;
}
MAV_CMD
command
(
void
)
const
{
return
_command
;
}
QString
category
(
void
)
const
{
return
_category
;
}
QString
description
(
void
)
const
{
return
_description
;
}
bool
friendlyEdit
(
void
)
const
{
return
_friendlyEdit
;
}
QString
friendlyName
(
void
)
const
{
return
_friendlyName
;
}
QString
rawName
(
void
)
const
{
return
_rawName
;
}
bool
standaloneCoordinate
(
void
)
const
{
return
_standaloneCoordinate
;
}
bool
specifiesCoordinate
(
void
)
const
{
return
_specifiesCoordinate
;
}
const
QMap
<
int
,
MavCmdParamInfo
*>&
paramInfoMap
(
void
)
const
{
return
_paramInfoMap
;
}
private:
QString
_category
;
MAV_CMD
_command
;
QString
_description
;
bool
_friendlyEdit
;
QString
_friendlyName
;
QMap
<
int
,
MavCmdParamInfo
*>
_paramInfoMap
;
QString
_rawName
;
bool
_standaloneCoordinate
;
bool
_specifiesCoordinate
;
friend
class
MissionCommandList
;
};
// A list of mission command info loaded from a json file.
class
MissionCommandList
:
public
QObject
{
Q_OBJECT
public:
MissionCommandList
(
const
QString
&
jsonFilename
,
QObject
*
parent
=
NULL
);
Q_INVOKABLE
bool
contains
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
)
const
{
return
contains
((
MAV_CMD
)
command
);
}
bool
contains
(
MAV_CMD
command
)
const
;
Q_INVOKABLE
QVariant
getMavCmdInfo
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
)
const
{
return
QVariant
::
fromValue
(
getMavCmdInfo
((
MAV_CMD
)
command
));
}
MavCmdInfo
*
getMavCmdInfo
(
MAV_CMD
command
)
const
;
QList
<
MAV_CMD
>
commandsIds
(
void
)
const
;
private:
void
_loadMavCmdInfoJson
(
const
QString
&
jsonFilename
);
bool
_validateKeyTypes
(
QJsonObject
&
jsonObject
,
const
QStringList
&
keys
,
const
QList
<
QJsonValue
::
Type
>&
types
);
private:
QMap
<
MAV_CMD
,
MavCmdInfo
*>
_mavCmdInfoMap
;
static
const
QString
_categoryJsonKey
;
static
const
QString
_decimalPlacesJsonKey
;
static
const
QString
_defaultJsonKey
;
static
const
QString
_descriptionJsonKey
;
static
const
QString
_enumStringsJsonKey
;
static
const
QString
_enumValuesJsonKey
;
static
const
QString
_friendlyNameJsonKey
;
static
const
QString
_friendlyEditJsonKey
;
static
const
QString
_idJsonKey
;
static
const
QString
_labelJsonKey
;
static
const
QString
_mavCmdInfoJsonKey
;
static
const
QString
_param1JsonKey
;
static
const
QString
_param2JsonKey
;
static
const
QString
_param3JsonKey
;
static
const
QString
_param4JsonKey
;
static
const
QString
_paramJsonKeyFormat
;
static
const
QString
_rawNameJsonKey
;
static
const
QString
_standaloneCoordinateJsonKey
;
static
const
QString
_specifiesCoordinateJsonKey
;
static
const
QString
_unitsJsonKey
;
static
const
QString
_versionJsonKey
;
};
#endif
src/MissionManager/MissionCommands.cc
View file @
96995949
...
@@ -27,241 +27,64 @@ This file is part of the QGROUNDCONTROL project
...
@@ -27,241 +27,64 @@ This file is part of the QGROUNDCONTROL project
#include "QGCApplication.h"
#include "QGCApplication.h"
#include "QGroundControlQmlGlobal.h"
#include "QGroundControlQmlGlobal.h"
#include <QStringList>
#include <QJsonDocument>
#include <QJsonParseError>
#include <QJsonArray>
#include <QDebug>
#include <QFile>
QGC_LOGGING_CATEGORY
(
MissionCommandsLog
,
"MissionCommandsLog"
)
const
QString
MissionCommands
::
_categoryJsonKey
(
QStringLiteral
(
"category"
));
const
QString
MissionCommands
::
_decimalPlacesJsonKey
(
QStringLiteral
(
"decimalPlaces"
));
const
QString
MissionCommands
::
_defaultJsonKey
(
QStringLiteral
(
"default"
));
const
QString
MissionCommands
::
_descriptionJsonKey
(
QStringLiteral
(
"description"
));
const
QString
MissionCommands
::
_enumStringsJsonKey
(
QStringLiteral
(
"enumStrings"
));
const
QString
MissionCommands
::
_enumValuesJsonKey
(
QStringLiteral
(
"enumValues"
));
const
QString
MissionCommands
::
_friendlyEditJsonKey
(
QStringLiteral
(
"friendlyEdit"
));
const
QString
MissionCommands
::
_friendlyNameJsonKey
(
QStringLiteral
(
"friendlyName"
));
const
QString
MissionCommands
::
_idJsonKey
(
QStringLiteral
(
"id"
));
const
QString
MissionCommands
::
_labelJsonKey
(
QStringLiteral
(
"label"
));
const
QString
MissionCommands
::
_mavCmdInfoJsonKey
(
QStringLiteral
(
"mavCmdInfo"
));
const
QString
MissionCommands
::
_param1JsonKey
(
QStringLiteral
(
"param1"
));
const
QString
MissionCommands
::
_param2JsonKey
(
QStringLiteral
(
"param2"
));
const
QString
MissionCommands
::
_param3JsonKey
(
QStringLiteral
(
"param3"
));
const
QString
MissionCommands
::
_param4JsonKey
(
QStringLiteral
(
"param4"
));
const
QString
MissionCommands
::
_paramJsonKeyFormat
(
QStringLiteral
(
"param%1"
));
const
QString
MissionCommands
::
_rawNameJsonKey
(
QStringLiteral
(
"rawName"
));
const
QString
MissionCommands
::
_standaloneCoordinateJsonKey
(
QStringLiteral
(
"standaloneCoordinate"
));
const
QString
MissionCommands
::
_specifiesCoordinateJsonKey
(
QStringLiteral
(
"specifiesCoordinate"
));
const
QString
MissionCommands
::
_unitsJsonKey
(
QStringLiteral
(
"units"
));
const
QString
MissionCommands
::
_versionJsonKey
(
QStringLiteral
(
"version"
));
MissionCommands
::
MissionCommands
(
QGCApplication
*
app
)
MissionCommands
::
MissionCommands
(
QGCApplication
*
app
)
:
QGCTool
(
app
)
:
QGCTool
(
app
)
,
_commonMissionCommands
(
QStringLiteral
(
":/json/MavCmdInfoCommon.json"
))
{
{
}
}
void
MissionCommands
::
setToolbox
(
QGCToolbox
*
toolbox
)
void
MissionCommands
::
setToolbox
(
QGCToolbox
*
toolbox
)
{
{
QGCTool
::
setToolbox
(
toolbox
);
QGCTool
::
setToolbox
(
toolbox
);
_loadMavCmdInfoJson
();
_createFirmwareSpecificLists
();
}
bool
MissionCommands
::
_validateKeyTypes
(
QJsonObject
&
jsonObject
,
const
QStringList
&
keys
,
const
QList
<
QJsonValue
::
Type
>&
types
)
// Setup overrides
{
QString
overrideCommonJsonFilename
;
for
(
int
i
=
0
;
i
<
keys
.
count
();
i
++
)
{
QString
overrideFixedWingJsonFilename
;
if
(
jsonObject
.
contains
(
keys
[
i
]))
{
QString
overrideMultiRotorJsonFilename
;
if
(
jsonObject
.
value
(
keys
[
i
]).
type
()
!=
types
[
i
])
{
qWarning
()
<<
"Incorrect type key:type:expected"
<<
keys
[
i
]
<<
jsonObject
.
value
(
keys
[
i
]).
type
()
<<
types
[
i
];
return
false
;
}
}
}
return
true
;
QList
<
MAV_AUTOPILOT
>
firmwareList
;
}
firmwareList
<<
MAV_AUTOPILOT_GENERIC
<<
MAV_AUTOPILOT_PX4
<<
MAV_AUTOPILOT_ARDUPILOTMEGA
;
void
MissionCommands
::
_loadMavCmdInfoJson
(
void
)
foreach
(
MAV_AUTOPILOT
firmwareType
,
firmwareList
)
{
{
FirmwarePlugin
*
plugin
=
_toolbox
->
firmwarePluginManager
()
->
firmwarePluginForAutopilot
(
firmwareType
,
MAV_TYPE_QUADROTOR
);
QFile
jsonFile
(
":/json/MavCmdInfo.json"
);
if
(
!
jsonFile
.
open
(
QIODevice
::
ReadOnly
|
QIODevice
::
Text
))
{
qWarning
()
<<
"Unable to open MavCmdInfo.json"
<<
jsonFile
.
errorString
();
return
;
}
QByteArray
bytes
=
jsonFile
.
readAll
();
jsonFile
.
close
();
QJsonParseError
jsonParseError
;
QJsonDocument
doc
=
QJsonDocument
::
fromJson
(
bytes
,
&
jsonParseError
);
if
(
jsonParseError
.
error
!=
QJsonParseError
::
NoError
)
{
qWarning
()
<<
"Unable to open json document"
<<
jsonParseError
.
errorString
();
return
;
}
QJsonObject
json
=
doc
.
object
();
int
version
=
json
.
value
(
_versionJsonKey
).
toInt
();
if
(
version
!=
1
)
{
qWarning
()
<<
"Invalid version"
<<
version
;
return
;
}
QJsonValue
jsonValue
=
json
.
value
(
_mavCmdInfoJsonKey
);
plugin
->
missionCommandOverrides
(
overrideCommonJsonFilename
,
overrideFixedWingJsonFilename
,
overrideMultiRotorJsonFilename
);
if
(
!
jsonValue
.
isArray
())
{
_autopilotToCommonMissionCommands
[
firmwareType
]
=
new
MissionCommandList
(
overrideCommonJsonFilename
);
qWarning
()
<<
"mavCmdInfo not array"
;
_autopilotToFixedWingMissionCommands
[
firmwareType
]
=
new
MissionCommandList
(
overrideFixedWingJsonFilename
)
;
return
;
_autopilotToMultiRotorMissionCommands
[
firmwareType
]
=
new
MissionCommandList
(
overrideMultiRotorJsonFilename
)
;
}
}
QJsonArray
jsonArray
=
jsonValue
.
toArray
();
_createCategories
();
foreach
(
QJsonValue
info
,
jsonArray
)
{
}
if
(
!
info
.
isObject
())
{
qWarning
()
<<
"mavCmdArray should contain objects"
;
return
;
}
QJsonObject
jsonObject
=
info
.
toObject
();
// Make sure we have the required keys
QStringList
requiredKeys
;
requiredKeys
<<
_idJsonKey
<<
_rawNameJsonKey
;
foreach
(
const
QString
&
key
,
requiredKeys
)
{
if
(
!
jsonObject
.
contains
(
key
))
{
qWarning
()
<<
"Mission required key"
<<
key
;
return
;
}
}
// Validate key types
QStringList
keys
;
/// Create category hierarchy for support commands
QList
<
QJsonValue
::
Type
>
types
;
void
MissionCommands
::
_createCategories
(
void
)
keys
<<
_idJsonKey
<<
_rawNameJsonKey
<<
_friendlyNameJsonKey
<<
_descriptionJsonKey
<<
_standaloneCoordinateJsonKey
<<
_specifiesCoordinateJsonKey
<<
_friendlyEditJsonKey
{
<<
_param1JsonKey
<<
_param2JsonKey
<<
_param3JsonKey
<<
_param4JsonKey
<<
_categoryJsonKey
;
// FIXME: This isn't quite right since it's hardcoding the firmware providers. But ok for now.
types
<<
QJsonValue
::
Double
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Bool
QList
<
MAV_AUTOPILOT
>
firmwareList
;
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
String
;
firmwareList
<<
MAV_AUTOPILOT_GENERIC
<<
MAV_AUTOPILOT_PX4
<<
MAV_AUTOPILOT_ARDUPILOTMEGA
;
if
(
!
_validateKeyTypes
(
jsonObject
,
keys
,
types
))
{
return
;
}
MavCmdInfo
*
mavCmdInfo
=
new
MavCmdInfo
(
this
);
foreach
(
MAV_AUTOPILOT
firmwareType
,
firmwareList
)
{
FirmwarePlugin
*
plugin
=
_toolbox
->
firmwarePluginManager
()
->
firmwarePluginForAutopilot
(
firmwareType
,
MAV_TYPE_QUADROTOR
);
mavCmdInfo
->
_command
=
(
MAV_CMD
)
jsonObject
.
value
(
_idJsonKey
).
toInt
();
mavCmdInfo
->
_category
=
jsonObject
.
value
(
_categoryJsonKey
).
toString
(
"Advanced"
);
mavCmdInfo
->
_rawName
=
jsonObject
.
value
(
_rawNameJsonKey
).
toString
();
mavCmdInfo
->
_friendlyName
=
jsonObject
.
value
(
_friendlyNameJsonKey
).
toString
(
QString
());
mavCmdInfo
->
_description
=
jsonObject
.
value
(
_descriptionJsonKey
).
toString
(
QString
());
mavCmdInfo
->
_standaloneCoordinate
=
jsonObject
.
value
(
_standaloneCoordinateJsonKey
).
toBool
(
false
);
mavCmdInfo
->
_specifiesCoordinate
=
jsonObject
.
value
(
_specifiesCoordinateJsonKey
).
toBool
(
false
);
mavCmdInfo
->
_friendlyEdit
=
jsonObject
.
value
(
_friendlyEditJsonKey
).
toBool
(
false
);
qCDebug
(
MissionCommandsLog
)
<<
"Command"
<<
mavCmdInfo
->
_command
<<
mavCmdInfo
->
_category
<<
mavCmdInfo
->
_rawName
<<
mavCmdInfo
->
_friendlyName
<<
mavCmdInfo
->
_description
<<
mavCmdInfo
->
_standaloneCoordinate
<<
mavCmdInfo
->
_specifiesCoordinate
<<
mavCmdInfo
->
_friendlyEdit
;
if
(
_mavCmdInfoMap
.
contains
((
MAV_CMD
)
mavCmdInfo
->
command
()))
{
qWarning
()
<<
"Duplicate command"
<<
mavCmdInfo
->
command
();
return
;
}
_mavCmdInfoMap
[
mavCmdInfo
->
_command
]
=
mavCmdInfo
;
bool
allCommandsSupported
=
false
;
QList
<
MAV_CMD
>
cmdList
=
plugin
->
supportedMissionCommands
();
// Read params
if
(
cmdList
.
isEmpty
())
{
allCommandsSupported
=
true
;
for
(
int
i
=
1
;
i
<=
7
;
i
++
)
{
cmdList
=
_commonMissionCommands
.
commandsIds
();
QString
paramKey
=
QString
(
_paramJsonKeyFormat
).
arg
(
i
);
if
(
jsonObject
.
contains
(
paramKey
))
{
QJsonObject
paramObject
=
jsonObject
.
value
(
paramKey
).
toObject
();
// Validate key types
QStringList
keys
;
QList
<
QJsonValue
::
Type
>
types
;
keys
<<
_defaultJsonKey
<<
_decimalPlacesJsonKey
<<
_enumStringsJsonKey
<<
_enumValuesJsonKey
<<
_labelJsonKey
<<
_unitsJsonKey
;
types
<<
QJsonValue
::
Double
<<
QJsonValue
::
Double
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
String
;
if
(
!
_validateKeyTypes
(
paramObject
,
keys
,
types
))
{
return
;
}
mavCmdInfo
->
_friendlyEdit
=
true
;
// Assume friendly edit if we have params
if
(
!
paramObject
.
contains
(
_labelJsonKey
))
{
qWarning
()
<<
"param object missing label key"
<<
mavCmdInfo
->
rawName
()
<<
paramKey
;
return
;
}
MavCmdParamInfo
*
paramInfo
=
new
MavCmdParamInfo
(
this
);
paramInfo
->
_label
=
paramObject
.
value
(
_labelJsonKey
).
toString
();
paramInfo
->
_defaultValue
=
paramObject
.
value
(
_defaultJsonKey
).
toDouble
(
0.0
);
paramInfo
->
_decimalPlaces
=
paramObject
.
value
(
_decimalPlacesJsonKey
).
toInt
(
FactMetaData
::
defaultDecimalPlaces
);
paramInfo
->
_enumStrings
=
paramObject
.
value
(
_enumStringsJsonKey
).
toString
().
split
(
","
,
QString
::
SkipEmptyParts
);
paramInfo
->
_param
=
i
;
paramInfo
->
_units
=
paramObject
.
value
(
_unitsJsonKey
).
toString
();
QStringList
enumValues
=
paramObject
.
value
(
_enumValuesJsonKey
).
toString
().
split
(
","
,
QString
::
SkipEmptyParts
);
foreach
(
const
QString
&
enumValue
,
enumValues
)
{
bool
convertOk
;
double
value
=
enumValue
.
toDouble
(
&
convertOk
);
if
(
!
convertOk
)
{
qWarning
()
<<
"Bad enumValue"
<<
enumValue
;
return
;
}
paramInfo
->
_enumValues
<<
QVariant
(
value
);
}
if
(
paramInfo
->
_enumValues
.
count
()
!=
paramInfo
->
_enumStrings
.
count
())
{
qWarning
()
<<
"enum strings/values count mismatch"
<<
paramInfo
->
_enumStrings
.
count
()
<<
paramInfo
->
_enumValues
.
count
();
return
;
}
qCDebug
(
MissionCommandsLog
)
<<
"Param"
<<
paramInfo
->
_label
<<
paramInfo
->
_defaultValue
<<
paramInfo
->
_decimalPlaces
<<
paramInfo
->
_param
<<
paramInfo
->
_units
<<
paramInfo
->
_enumStrings
<<
paramInfo
->
_enumValues
;
mavCmdInfo
->
_paramInfoMap
[
i
]
=
paramInfo
;
}
}
}
// We don't add categories till down here, since friendly edit isn't valid till here
foreach
(
MAV_CMD
command
,
cmdList
)
{
if
(
mavCmdInfo
->
_command
!=
MAV_CMD_NAV_LAST
)
{
MavCmdInfo
*
mavCmdInfo
=
_commonMissionCommands
.
getMavCmdInfo
(
command
);
// Don't add fake home position command to categories
if
(
mavCmdInfo
->
friendlyEdit
())
{
if
(
mavCmdInfo
->
friendlyEdit
())
{
// Only friendly edit commands go in category list. We use MAV_AUTOPILOT_GENERIC key to store full list.
_categoryToMavCmdListMap
[
firmwareType
][
mavCmdInfo
->
category
()].
append
(
command
);
if
(
!
_categoryToMavCmdInfoListMap
.
contains
(
MAV_AUTOPILOT_GENERIC
)
||
!
_categoryToMavCmdInfoListMap
[
MAV_AUTOPILOT_GENERIC
].
contains
(
mavCmdInfo
->
category
()))
{
}
else
if
(
!
allCommandsSupported
)
{
qCDebug
(
MissionCommandsLog
)
<<
"Adding new category"
;
qWarning
()
<<
"Attempt to add non friendly edit supported command"
;
_categoryToMavCmdInfoListMap
[
MAV_AUTOPILOT_GENERIC
][
mavCmdInfo
->
category
()]
=
new
QmlObjectListModel
(
this
);
}
_categoryToMavCmdInfoListMap
[
MAV_AUTOPILOT_GENERIC
][
mavCmdInfo
->
category
()]
->
append
(
mavCmdInfo
);
}
}
if
(
mavCmdInfo
->
friendlyEdit
())
{
if
(
mavCmdInfo
->
description
().
isEmpty
())
{
qWarning
()
<<
"Missing description"
<<
mavCmdInfo
->
rawName
();
return
;
}
if
(
mavCmdInfo
->
rawName
()
==
mavCmdInfo
->
friendlyName
())
{
qWarning
()
<<
"Missing friendly name"
<<
mavCmdInfo
->
rawName
()
<<
mavCmdInfo
->
friendlyName
();
return
;
}
}
}
}
}
}
}
}
MAV_AUTOPILOT
MissionCommands
::
_firmwareTypeFromVehicle
(
Vehicle
*
vehicle
)
const
MAV_AUTOPILOT
MissionCommands
::
_firmwareTypeFromVehicle
(
Vehicle
*
vehicle
)
const
...
@@ -280,47 +103,71 @@ MAV_AUTOPILOT MissionCommands::_firmwareTypeFromVehicle(Vehicle* vehicle) const
...
@@ -280,47 +103,71 @@ MAV_AUTOPILOT MissionCommands::_firmwareTypeFromVehicle(Vehicle* vehicle) const
QString
MissionCommands
::
categoryFromCommand
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
)
const
QString
MissionCommands
::
categoryFromCommand
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
)
const
{
{
return
_
mavCmdInfoMap
[(
MAV_CMD
)
command
]
->
category
();
return
_
commonMissionCommands
.
getMavCmdInfo
((
MAV_CMD
)
command
)
->
category
();
}
}
QVariant
MissionCommands
::
getCommandsForCategory
(
Vehicle
*
vehicle
,
const
QString
&
category
)
const
QVariant
MissionCommands
::
getCommandsForCategory
(
Vehicle
*
vehicle
,
const
QString
&
category
)
const
{
{
return
QVariant
::
fromValue
(
_categoryToMavCmdInfoListMap
[
_firmwareTypeFromVehicle
(
vehicle
)][
category
]);
QmlObjectListModel
*
list
=
new
QmlObjectListModel
();
QQmlEngine
::
setObjectOwnership
(
list
,
QQmlEngine
::
JavaScriptOwnership
);
foreach
(
MAV_CMD
command
,
_categoryToMavCmdListMap
[
_firmwareTypeFromVehicle
(
vehicle
)][
category
])
{
list
->
append
(
getMavCmdInfo
(
command
,
vehicle
));
}
return
QVariant
::
fromValue
(
list
);
}
}
const
QStringList
MissionCommands
::
categories
(
Vehicle
*
vehicle
)
const
const
QStringList
MissionCommands
::
categories
(
Vehicle
*
vehicle
)
const
{
{
QStringList
list
;
QStringList
list
;
foreach
(
const
QString
&
category
,
_categoryToMavCmd
Info
ListMap
[
_firmwareTypeFromVehicle
(
vehicle
)].
keys
())
{
foreach
(
const
QString
&
category
,
_categoryToMavCmdListMap
[
_firmwareTypeFromVehicle
(
vehicle
)].
keys
())
{
list
<<
category
;
list
<<
category
;
}
}
return
list
;
return
list
;
}
}
void
MissionCommands
::
_createFirmwareSpecificLists
(
void
)
bool
MissionCommands
::
contains
(
MAV_CMD
command
)
const
{
{
QList
<
MAV_AUTOPILOT
>
firmwareList
;
return
_commonMissionCommands
.
contains
(
command
);
}
firmwareList
<<
MAV_AUTOPILOT_PX4
<<
MAV_AUTOPILOT_ARDUPILOTMEGA
;
foreach
(
MAV_AUTOPILOT
firmwareType
,
firmwareList
)
{
MavCmdInfo
*
MissionCommands
::
getMavCmdInfo
(
MAV_CMD
command
,
Vehicle
*
vehicle
)
const
FirmwarePlugin
*
plugin
=
_toolbox
->
firmwarePluginManager
()
->
firmwarePluginForAutopilot
(
firmwareType
,
MAV_TYPE_QUADROTOR
);
{
if
(
!
contains
(
command
))
{
qWarning
()
<<
"Unknown command"
<<
command
;
return
NULL
;
}
QList
<
MAV_CMD
>
cmdList
=
plugin
->
supportedMissionCommands
();
MavCmdInfo
*
mavCmdInfo
=
NULL
;
foreach
(
MAV_CMD
command
,
cmdList
)
{
MAV_AUTOPILOT
firmwareType
=
_firmwareTypeFromVehicle
(
vehicle
);
MavCmdInfo
*
mavCmdInfo
=
_mavCmdInfoMap
[
command
];
if
(
mavCmdInfo
->
friendlyEdit
())
{
if
(
vehicle
)
{
if
(
!
_categoryToMavCmdInfoListMap
.
contains
(
firmwareType
)
||
!
_categoryToMavCmdInfoListMap
[
firmwareType
].
contains
(
mavCmdInfo
->
category
()))
{
if
(
vehicle
->
fixedWing
())
{
qCDebug
(
MissionCommandsLog
)
<<
"Adding new category"
<<
firmwareType
;
if
(
_autopilotToFixedWingMissionCommands
[
firmwareType
]
->
contains
(
command
))
{
_categoryToMavCmdInfoListMap
[
firmwareType
][
mavCmdInfo
->
category
()]
=
new
QmlObjectListModel
(
this
);
mavCmdInfo
=
_autopilotToFixedWingMissionCommands
[
firmwareType
]
->
getMavCmdInfo
(
command
);
}
}
_categoryToMavCmdInfoListMap
[
firmwareType
][
mavCmdInfo
->
category
()]
->
append
(
mavCmdInfo
);
}
else
if
(
vehicle
->
multiRotor
())
{
}
else
{
if
(
_autopilotToMultiRotorMissionCommands
[
firmwareType
]
->
contains
(
command
))
{
qWarning
()
<<
"Attempt to add non friendly edit supported command"
;
mavCmdInfo
=
_autopilotToMultiRotorMissionCommands
[
firmwareType
]
->
getMavCmdInfo
(
command
);
}
}
else
{
if
(
_autopilotToCommonMissionCommands
[
firmwareType
]
->
contains
(
command
))
{
mavCmdInfo
=
_autopilotToCommonMissionCommands
[
firmwareType
]
->
getMavCmdInfo
(
command
);
}
}
}
}
}
}
if
(
!
mavCmdInfo
)
{
mavCmdInfo
=
_commonMissionCommands
.
getMavCmdInfo
(
command
);
}
return
mavCmdInfo
;
}
QList
<
MAV_CMD
>
MissionCommands
::
commandsIds
(
void
)
const
{
return
_commonMissionCommands
.
commandsIds
();
}
}
src/MissionManager/MissionCommands.h
View file @
96995949
...
@@ -25,104 +25,17 @@
...
@@ -25,104 +25,17 @@
#define MissionCommands_H
#define MissionCommands_H
#include "QGCToolbox.h"
#include "QGCToolbox.h"
#include "QGCMAVLink.h"
#include "MissionCommandList.h"
#include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
/// Provides access to mission command information used for creating mission command ui editors. There is a base common set
#include "MavlinkQmlSingleton.h"
/// of definitions. Individual commands can then be overriden depending on Vehicle information:
/// Common command definitions
#include <QObject>
/// MAV_AUTOPILOT common overrides
#include <QString>
/// Fixed Wing
#include <QJsonObject>
/// MAV_AUTOPILOT specific Fixed Wing overrides
#include <QJsonValue>
/// Multi-Rotor
/// MAV_AUTOPILOT specific Multi Rotor overrides
Q_DECLARE_LOGGING_CATEGORY
(
MissionCommandsLog
)
/// The leaf nodes of the hierarchy take precedence over higher level branches
class
MissionCommands
;
class
Vehicle
;
class
MavCmdParamInfo
:
public
QObject
{
Q_OBJECT
public:
MavCmdParamInfo
(
QObject
*
parent
=
NULL
)
:
QObject
(
parent
)
{
}
Q_PROPERTY
(
int
decimalPlaces
READ
decimalPlaces
CONSTANT
)
Q_PROPERTY
(
double
defaultValue
READ
defaultValue
CONSTANT
)
Q_PROPERTY
(
QStringList
enumStrings
READ
enumStrings
CONSTANT
)
Q_PROPERTY
(
QVariantList
enumValues
READ
enumValues
CONSTANT
)
Q_PROPERTY
(
QString
label
READ
label
CONSTANT
)
Q_PROPERTY
(
int
param
READ
param
CONSTANT
)
Q_PROPERTY
(
QString
units
READ
units
CONSTANT
)
int
decimalPlaces
(
void
)
const
{
return
_decimalPlaces
;
}
double
defaultValue
(
void
)
const
{
return
_defaultValue
;
}
QStringList
enumStrings
(
void
)
const
{
return
_enumStrings
;
}
QVariantList
enumValues
(
void
)
const
{
return
_enumValues
;
}
QString
label
(
void
)
const
{
return
_label
;
}
int
param
(
void
)
const
{
return
_param
;
}
QString
units
(
void
)
const
{
return
_units
;
}
private:
int
_decimalPlaces
;
double
_defaultValue
;
QStringList
_enumStrings
;
QVariantList
_enumValues
;
QString
_label
;
int
_param
;
QString
_units
;
friend
class
MissionCommands
;
};
class
MavCmdInfo
:
public
QObject
{
Q_OBJECT
public:
MavCmdInfo
(
QObject
*
parent
=
NULL
)
:
QObject
(
parent
)
{
}
Q_PROPERTY
(
QString
category
READ
category
CONSTANT
)
Q_PROPERTY
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
READ
command
CONSTANT
)
Q_PROPERTY
(
QString
description
READ
description
CONSTANT
)
Q_PROPERTY
(
bool
friendlyEdit
READ
friendlyEdit
CONSTANT
)
Q_PROPERTY
(
QString
friendlyName
READ
friendlyName
CONSTANT
)
Q_PROPERTY
(
QString
rawName
READ
rawName
CONSTANT
)
Q_PROPERTY
(
bool
standaloneCoordinate
READ
standaloneCoordinate
CONSTANT
)
Q_PROPERTY
(
bool
specifiesCoordinate
READ
specifiesCoordinate
CONSTANT
)
QString
category
(
void
)
const
{
return
_category
;
}
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
(
void
)
const
{
return
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
)
_command
;
}
QString
description
(
void
)
const
{
return
_description
;
}
bool
friendlyEdit
(
void
)
const
{
return
_friendlyEdit
;
}
QString
friendlyName
(
void
)
const
{
return
_friendlyName
;
}
QString
rawName
(
void
)
const
{
return
_rawName
;
}
bool
standaloneCoordinate
(
void
)
const
{
return
_standaloneCoordinate
;
}
bool
specifiesCoordinate
(
void
)
const
{
return
_specifiesCoordinate
;
}
const
QMap
<
int
,
MavCmdParamInfo
*>&
paramInfoMap
(
void
)
const
{
return
_paramInfoMap
;
}
private:
QString
_category
;
MAV_CMD
_command
;
QString
_description
;
bool
_friendlyEdit
;
QString
_friendlyName
;
QMap
<
int
,
MavCmdParamInfo
*>
_paramInfoMap
;
QString
_rawName
;
bool
_standaloneCoordinate
;
bool
_specifiesCoordinate
;
friend
class
MissionCommands
;
};
class
MissionCommands
:
public
QGCTool
class
MissionCommands
:
public
QGCTool
{
{
Q_OBJECT
Q_OBJECT
...
@@ -134,45 +47,29 @@ public:
...
@@ -134,45 +47,29 @@ public:
Q_INVOKABLE
QString
categoryFromCommand
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
)
const
;
Q_INVOKABLE
QString
categoryFromCommand
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
)
const
;
Q_INVOKABLE
QVariant
getCommandsForCategory
(
Vehicle
*
vehicle
,
const
QString
&
category
)
const
;
Q_INVOKABLE
QVariant
getCommandsForCategory
(
Vehicle
*
vehicle
,
const
QString
&
category
)
const
;
const
QMap
<
MAV_CMD
,
MavCmdInfo
*>&
commandInfoMap
(
void
)
const
{
return
_mavCmdInfoMap
;
};
Q_INVOKABLE
bool
contains
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
)
const
{
return
contains
((
MAV_CMD
)
command
);
}
bool
contains
(
MAV_CMD
command
)
const
;
Q_INVOKABLE
QVariant
getMavCmdInfo
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
,
Vehicle
*
vehicle
)
const
{
return
QVariant
::
fromValue
(
getMavCmdInfo
((
MAV_CMD
)
command
,
vehicle
));
}
MavCmdInfo
*
getMavCmdInfo
(
MAV_CMD
command
,
Vehicle
*
vehicle
)
const
;
QList
<
MAV_CMD
>
commandsIds
(
void
)
const
;
// Overrides from QGCTool
// Overrides from QGCTool
virtual
void
setToolbox
(
QGCToolbox
*
toolbox
);
virtual
void
setToolbox
(
QGCToolbox
*
toolbox
);
signals:
private:
private:
void
_loadMavCmdInfoJson
(
void
);
void
_createCategories
(
void
);
void
_createFirmwareSpecificLists
(
void
);
void
_setupMetaData
(
void
);
bool
_validateKeyTypes
(
QJsonObject
&
jsonObject
,
const
QStringList
&
keys
,
const
QList
<
QJsonValue
::
Type
>&
types
);
MAV_AUTOPILOT
_firmwareTypeFromVehicle
(
Vehicle
*
vehicle
)
const
;
MAV_AUTOPILOT
_firmwareTypeFromVehicle
(
Vehicle
*
vehicle
)
const
;
private:
private:
QMap
<
MAV_AUTOPILOT
,
QMap
<
QString
,
QmlObjectListModel
*>
>
_categoryToMavCmdInfoListMap
;
QMap
<
MAV_AUTOPILOT
,
QMap
<
QString
,
QList
<
MAV_CMD
>
>
>
_categoryToMavCmdListMap
;
QMap
<
MAV_CMD
,
MavCmdInfo
*>
_mavCmdInfoMap
;
MissionCommandList
_commonMissionCommands
;
///< Mission command definitions for common generic mavlink use case
static
const
QString
_categoryJsonKey
;
QMap
<
MAV_AUTOPILOT
,
MissionCommandList
*>
_autopilotToCommonMissionCommands
;
///< MAV_AUTOPILOT specific common overrides
static
const
QString
_decimalPlacesJsonKey
;
QMap
<
MAV_AUTOPILOT
,
MissionCommandList
*>
_autopilotToFixedWingMissionCommands
;
///< MAV_AUTOPILOT specific fixed wing overrides
static
const
QString
_defaultJsonKey
;
QMap
<
MAV_AUTOPILOT
,
MissionCommandList
*>
_autopilotToMultiRotorMissionCommands
;
///< MAV_AUTOPILOT specific multi rotor overrides
static
const
QString
_descriptionJsonKey
;
static
const
QString
_enumStringsJsonKey
;
static
const
QString
_enumValuesJsonKey
;
static
const
QString
_friendlyNameJsonKey
;
static
const
QString
_friendlyEditJsonKey
;
static
const
QString
_idJsonKey
;
static
const
QString
_labelJsonKey
;
static
const
QString
_mavCmdInfoJsonKey
;
static
const
QString
_param1JsonKey
;
static
const
QString
_param2JsonKey
;
static
const
QString
_param3JsonKey
;
static
const
QString
_param4JsonKey
;
static
const
QString
_paramJsonKeyFormat
;
static
const
QString
_rawNameJsonKey
;
static
const
QString
_standaloneCoordinateJsonKey
;
static
const
QString
_specifiesCoordinateJsonKey
;
static
const
QString
_unitsJsonKey
;
static
const
QString
_versionJsonKey
;
};
};
#endif
#endif
src/MissionManager/MissionController.cc
View file @
96995949
...
@@ -161,7 +161,7 @@ void MissionController::sendMissionItems(void)
...
@@ -161,7 +161,7 @@ void MissionController::sendMissionItems(void)
int
MissionController
::
insertMissionItem
(
QGeoCoordinate
coordinate
,
int
i
)
int
MissionController
::
insertMissionItem
(
QGeoCoordinate
coordinate
,
int
i
)
{
{
MissionItem
*
newItem
=
new
MissionItem
(
this
);
MissionItem
*
newItem
=
new
MissionItem
(
_activeVehicle
,
this
);
newItem
->
setSequenceNumber
(
_missionItems
->
count
());
newItem
->
setSequenceNumber
(
_missionItems
->
count
());
newItem
->
setCoordinate
(
coordinate
);
newItem
->
setCoordinate
(
coordinate
);
newItem
->
setCommand
(
MAV_CMD_NAV_WAYPOINT
);
newItem
->
setCommand
(
MAV_CMD_NAV_WAYPOINT
);
...
@@ -258,7 +258,7 @@ void MissionController::loadMissionFromFile(void)
...
@@ -258,7 +258,7 @@ void MissionController::loadMissionFromFile(void)
if
(
versionOk
)
{
if
(
versionOk
)
{
while
(
!
in
.
atEnd
())
{
while
(
!
in
.
atEnd
())
{
MissionItem
*
item
=
new
MissionItem
();
MissionItem
*
item
=
new
MissionItem
(
_activeVehicle
,
this
);
if
(
item
->
load
(
in
))
{
if
(
item
->
load
(
in
))
{
_missionItems
->
append
(
item
);
_missionItems
->
append
(
item
);
...
@@ -494,7 +494,7 @@ void MissionController::_initAllMissionItems(void)
...
@@ -494,7 +494,7 @@ void MissionController::_initAllMissionItems(void)
homeItem
=
qobject_cast
<
MissionItem
*>
(
_missionItems
->
get
(
0
));
homeItem
=
qobject_cast
<
MissionItem
*>
(
_missionItems
->
get
(
0
));
}
else
{
}
else
{
// Add the home position item to the front
// Add the home position item to the front
homeItem
=
new
MissionItem
(
this
);
homeItem
=
new
MissionItem
(
_activeVehicle
,
this
);
homeItem
->
setSequenceNumber
(
0
);
homeItem
->
setSequenceNumber
(
0
);
_missionItems
->
insert
(
0
,
homeItem
);
_missionItems
->
insert
(
0
,
homeItem
);
}
}
...
...
src/MissionManager/MissionItem.cc
View file @
96995949
...
@@ -74,8 +74,9 @@ QDebug operator<<(QDebug dbg, const MissionItem* missionItem)
...
@@ -74,8 +74,9 @@ QDebug operator<<(QDebug dbg, const MissionItem* missionItem)
return
dbg
;
return
dbg
;
}
}
MissionItem
::
MissionItem
(
QObject
*
parent
)
MissionItem
::
MissionItem
(
Vehicle
*
vehicle
,
QObject
*
parent
)
:
QObject
(
parent
)
:
QObject
(
parent
)
,
_vehicle
(
vehicle
)
,
_rawEdit
(
false
)
,
_rawEdit
(
false
)
,
_dirty
(
false
)
,
_dirty
(
false
)
,
_sequenceNumber
(
0
)
,
_sequenceNumber
(
0
)
...
@@ -107,7 +108,7 @@ MissionItem::MissionItem(QObject* parent)
...
@@ -107,7 +108,7 @@ MissionItem::MissionItem(QObject* parent)
,
_param7MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_param7MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_syncingAltitudeRelativeToHomeAndFrame
(
false
)
,
_syncingAltitudeRelativeToHomeAndFrame
(
false
)
,
_syncingHeadingDegreesAndParam4
(
false
)
,
_syncingHeadingDegreesAndParam4
(
false
)
,
_m
avCmdInfoMap
(
qgcApp
()
->
toolbox
()
->
missionCommands
()
->
commandInfoMap
())
,
_m
issionCommands
(
qgcApp
()
->
toolbox
()
->
missionCommands
())
{
{
// Need a good command and frame before we start passing signals around
// Need a good command and frame before we start passing signals around
_commandFact
.
setRawValue
(
MAV_CMD_NAV_WAYPOINT
);
_commandFact
.
setRawValue
(
MAV_CMD_NAV_WAYPOINT
);
...
@@ -121,7 +122,8 @@ MissionItem::MissionItem(QObject* parent)
...
@@ -121,7 +122,8 @@ MissionItem::MissionItem(QObject* parent)
setDefaultsForCommand
();
setDefaultsForCommand
();
}
}
MissionItem
::
MissionItem
(
int
sequenceNumber
,
MissionItem
::
MissionItem
(
Vehicle
*
vehicle
,
int
sequenceNumber
,
MAV_CMD
command
,
MAV_CMD
command
,
MAV_FRAME
frame
,
MAV_FRAME
frame
,
double
param1
,
double
param1
,
...
@@ -135,6 +137,7 @@ MissionItem::MissionItem(int sequenceNumber,
...
@@ -135,6 +137,7 @@ MissionItem::MissionItem(int sequenceNumber,
bool
isCurrentItem
,
bool
isCurrentItem
,
QObject
*
parent
)
QObject
*
parent
)
:
QObject
(
parent
)
:
QObject
(
parent
)
,
_vehicle
(
vehicle
)
,
_rawEdit
(
false
)
,
_rawEdit
(
false
)
,
_dirty
(
false
)
,
_dirty
(
false
)
,
_sequenceNumber
(
sequenceNumber
)
,
_sequenceNumber
(
sequenceNumber
)
...
@@ -165,7 +168,7 @@ MissionItem::MissionItem(int sequenceNumber,
...
@@ -165,7 +168,7 @@ MissionItem::MissionItem(int sequenceNumber,
,
_param7MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_param7MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_syncingAltitudeRelativeToHomeAndFrame
(
false
)
,
_syncingAltitudeRelativeToHomeAndFrame
(
false
)
,
_syncingHeadingDegreesAndParam4
(
false
)
,
_syncingHeadingDegreesAndParam4
(
false
)
,
_m
avCmdInfoMap
(
qgcApp
()
->
toolbox
()
->
missionCommands
()
->
commandInfoMap
())
,
_m
issionCommands
(
qgcApp
()
->
toolbox
()
->
missionCommands
())
{
{
// Need a good command and frame before we start passing signals around
// Need a good command and frame before we start passing signals around
_commandFact
.
setRawValue
(
MAV_CMD_NAV_WAYPOINT
);
_commandFact
.
setRawValue
(
MAV_CMD_NAV_WAYPOINT
);
...
@@ -192,6 +195,7 @@ MissionItem::MissionItem(int sequenceNumber,
...
@@ -192,6 +195,7 @@ MissionItem::MissionItem(int sequenceNumber,
MissionItem
::
MissionItem
(
const
MissionItem
&
other
,
QObject
*
parent
)
MissionItem
::
MissionItem
(
const
MissionItem
&
other
,
QObject
*
parent
)
:
QObject
(
parent
)
:
QObject
(
parent
)
,
_vehicle
(
NULL
)
,
_rawEdit
(
false
)
,
_rawEdit
(
false
)
,
_dirty
(
false
)
,
_dirty
(
false
)
,
_sequenceNumber
(
0
)
,
_sequenceNumber
(
0
)
...
@@ -219,7 +223,7 @@ MissionItem::MissionItem(const MissionItem& other, QObject* parent)
...
@@ -219,7 +223,7 @@ MissionItem::MissionItem(const MissionItem& other, QObject* parent)
,
_param4MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_param4MetaData
(
FactMetaData
::
valueTypeDouble
)
,
_syncingAltitudeRelativeToHomeAndFrame
(
false
)
,
_syncingAltitudeRelativeToHomeAndFrame
(
false
)
,
_syncingHeadingDegreesAndParam4
(
false
)
,
_syncingHeadingDegreesAndParam4
(
false
)
,
_m
avCmdInfoMap
(
qgcApp
()
->
toolbox
()
->
missionCommands
()
->
commandInfoMap
())
,
_m
issionCommands
(
qgcApp
()
->
toolbox
()
->
missionCommands
())
{
{
// Need a good command and frame before we start passing signals around
// Need a good command and frame before we start passing signals around
_commandFact
.
setRawValue
(
MAV_CMD_NAV_WAYPOINT
);
_commandFact
.
setRawValue
(
MAV_CMD_NAV_WAYPOINT
);
...
@@ -234,6 +238,8 @@ MissionItem::MissionItem(const MissionItem& other, QObject* parent)
...
@@ -234,6 +238,8 @@ MissionItem::MissionItem(const MissionItem& other, QObject* parent)
const
MissionItem
&
MissionItem
::
operator
=
(
const
MissionItem
&
other
)
const
MissionItem
&
MissionItem
::
operator
=
(
const
MissionItem
&
other
)
{
{
_vehicle
=
other
.
_vehicle
;
setCommand
(
other
.
command
());
setCommand
(
other
.
command
());
setFrame
(
other
.
frame
());
setFrame
(
other
.
frame
());
setRawEdit
(
other
.
_rawEdit
);
setRawEdit
(
other
.
_rawEdit
);
...
@@ -314,7 +320,8 @@ void MissionItem::_setupMetaData(void)
...
@@ -314,7 +320,8 @@ void MissionItem::_setupMetaData(void)
enumStrings
.
clear
();
enumStrings
.
clear
();
enumValues
.
clear
();
enumValues
.
clear
();
foreach
(
const
MavCmdInfo
*
mavCmdInfo
,
_mavCmdInfoMap
)
{
foreach
(
const
MAV_CMD
command
,
_missionCommands
->
commandsIds
())
{
const
MavCmdInfo
*
mavCmdInfo
=
_missionCommands
->
getMavCmdInfo
(
command
,
_vehicle
);
enumStrings
.
append
(
mavCmdInfo
->
rawName
());
enumStrings
.
append
(
mavCmdInfo
->
rawName
());
enumValues
.
append
(
QVariant
(
mavCmdInfo
->
command
()));
enumValues
.
append
(
QVariant
(
mavCmdInfo
->
command
()));
}
}
...
@@ -488,8 +495,8 @@ void MissionItem::setParam7(double param)
...
@@ -488,8 +495,8 @@ void MissionItem::setParam7(double param)
bool
MissionItem
::
standaloneCoordinate
(
void
)
const
bool
MissionItem
::
standaloneCoordinate
(
void
)
const
{
{
if
(
_m
avCmdInfoMap
.
contains
((
MAV_CMD
)
command
()))
{
if
(
_m
issionCommands
->
contains
((
MAV_CMD
)
command
()))
{
return
_m
avCmdInfoMap
[(
MAV_CMD
)
command
()]
->
standaloneCoordinate
();
return
_m
issionCommands
->
getMavCmdInfo
((
MAV_CMD
)
command
(),
_vehicle
)
->
standaloneCoordinate
();
}
else
{
}
else
{
return
false
;
return
false
;
}
}
...
@@ -497,8 +504,8 @@ bool MissionItem::standaloneCoordinate(void) const
...
@@ -497,8 +504,8 @@ bool MissionItem::standaloneCoordinate(void) const
bool
MissionItem
::
specifiesCoordinate
(
void
)
const
bool
MissionItem
::
specifiesCoordinate
(
void
)
const
{
{
if
(
_m
avCmdInfoMap
.
contains
((
MAV_CMD
)
command
()))
{
if
(
_m
issionCommands
->
contains
((
MAV_CMD
)
command
()))
{
return
_m
avCmdInfoMap
[(
MAV_CMD
)
command
()]
->
specifiesCoordinate
();
return
_m
issionCommands
->
getMavCmdInfo
((
MAV_CMD
)
command
(),
_vehicle
)
->
specifiesCoordinate
();
}
else
{
}
else
{
return
false
;
return
false
;
}
}
...
@@ -506,8 +513,8 @@ bool MissionItem::specifiesCoordinate(void) const
...
@@ -506,8 +513,8 @@ bool MissionItem::specifiesCoordinate(void) const
QString
MissionItem
::
commandDescription
(
void
)
const
QString
MissionItem
::
commandDescription
(
void
)
const
{
{
if
(
_m
avCmdInfoMap
.
contains
((
MAV_CMD
)
command
()))
{
if
(
_m
issionCommands
->
contains
((
MAV_CMD
)
command
()))
{
return
_m
avCmdInfoMap
[(
MAV_CMD
)
command
()]
->
description
();
return
_m
issionCommands
->
getMavCmdInfo
((
MAV_CMD
)
command
(),
_vehicle
)
->
description
();
}
else
{
}
else
{
qWarning
()
<<
"Should not ask for command description on unknown command"
;
qWarning
()
<<
"Should not ask for command description on unknown command"
;
return
QString
();
return
QString
();
...
@@ -561,7 +568,7 @@ QmlObjectListModel* MissionItem::textFieldFacts(void)
...
@@ -561,7 +568,7 @@ QmlObjectListModel* MissionItem::textFieldFacts(void)
FactMetaData
*
rgParamMetaData
[
7
]
=
{
&
_param1MetaData
,
&
_param2MetaData
,
&
_param3MetaData
,
&
_param4MetaData
,
&
_param5MetaData
,
&
_param6MetaData
,
&
_param7MetaData
};
FactMetaData
*
rgParamMetaData
[
7
]
=
{
&
_param1MetaData
,
&
_param2MetaData
,
&
_param3MetaData
,
&
_param4MetaData
,
&
_param5MetaData
,
&
_param6MetaData
,
&
_param7MetaData
};
for
(
int
i
=
1
;
i
<=
7
;
i
++
)
{
for
(
int
i
=
1
;
i
<=
7
;
i
++
)
{
const
QMap
<
int
,
MavCmdParamInfo
*>&
paramInfoMap
=
_m
avCmdInfoMap
[
command
]
->
paramInfoMap
();
const
QMap
<
int
,
MavCmdParamInfo
*>&
paramInfoMap
=
_m
issionCommands
->
getMavCmdInfo
(
command
,
_vehicle
)
->
paramInfoMap
();
if
(
paramInfoMap
.
contains
(
i
)
&&
paramInfoMap
[
i
]
->
enumStrings
().
count
()
==
0
)
{
if
(
paramInfoMap
.
contains
(
i
)
&&
paramInfoMap
[
i
]
->
enumStrings
().
count
()
==
0
)
{
Fact
*
paramFact
=
rgParamFacts
[
i
-
1
];
Fact
*
paramFact
=
rgParamFacts
[
i
-
1
];
...
@@ -615,7 +622,7 @@ QmlObjectListModel* MissionItem::comboboxFacts(void)
...
@@ -615,7 +622,7 @@ QmlObjectListModel* MissionItem::comboboxFacts(void)
MAV_CMD
command
=
(
MAV_CMD
)
this
->
command
();
MAV_CMD
command
=
(
MAV_CMD
)
this
->
command
();
for
(
int
i
=
1
;
i
<=
7
;
i
++
)
{
for
(
int
i
=
1
;
i
<=
7
;
i
++
)
{
const
QMap
<
int
,
MavCmdParamInfo
*>&
paramInfoMap
=
_m
avCmdInfoMap
[
command
]
->
paramInfoMap
();
const
QMap
<
int
,
MavCmdParamInfo
*>&
paramInfoMap
=
_m
issionCommands
->
getMavCmdInfo
(
command
,
_vehicle
)
->
paramInfoMap
();
if
(
paramInfoMap
.
contains
(
i
)
&&
paramInfoMap
[
i
]
->
enumStrings
().
count
()
!=
0
)
{
if
(
paramInfoMap
.
contains
(
i
)
&&
paramInfoMap
[
i
]
->
enumStrings
().
count
()
!=
0
)
{
Fact
*
paramFact
=
rgParamFacts
[
i
-
1
];
Fact
*
paramFact
=
rgParamFacts
[
i
-
1
];
...
@@ -649,7 +656,7 @@ void MissionItem::setCoordinate(const QGeoCoordinate& coordinate)
...
@@ -649,7 +656,7 @@ void MissionItem::setCoordinate(const QGeoCoordinate& coordinate)
bool
MissionItem
::
friendlyEditAllowed
(
void
)
const
bool
MissionItem
::
friendlyEditAllowed
(
void
)
const
{
{
if
(
_m
avCmdInfoMap
.
contains
((
MAV_CMD
)
command
())
&&
_mavCmdInfoMap
[(
MAV_CMD
)
command
()]
->
friendlyEdit
())
{
if
(
_m
issionCommands
->
contains
((
MAV_CMD
)
command
())
&&
_missionCommands
->
getMavCmdInfo
((
MAV_CMD
)
command
(),
_vehicle
)
->
friendlyEdit
())
{
if
(
!
autoContinue
())
{
if
(
!
autoContinue
())
{
return
false
;
return
false
;
}
}
...
@@ -752,8 +759,9 @@ void MissionItem::setDefaultsForCommand(void)
...
@@ -752,8 +759,9 @@ void MissionItem::setDefaultsForCommand(void)
// We set these global defaults first, then if there are param defaults they will get reset
// We set these global defaults first, then if there are param defaults they will get reset
setParam7
(
defaultAltitude
);
setParam7
(
defaultAltitude
);
if
(
_mavCmdInfoMap
.
contains
((
MAV_CMD
)
command
()))
{
MAV_CMD
command
=
(
MAV_CMD
)
this
->
command
();
foreach
(
const
MavCmdParamInfo
*
paramInfo
,
_mavCmdInfoMap
[(
MAV_CMD
)
command
()]
->
paramInfoMap
())
{
if
(
_missionCommands
->
contains
(
command
))
{
foreach
(
const
MavCmdParamInfo
*
paramInfo
,
_missionCommands
->
getMavCmdInfo
(
command
,
_vehicle
)
->
paramInfoMap
())
{
Fact
*
rgParamFacts
[
7
]
=
{
&
_param1Fact
,
&
_param2Fact
,
&
_param3Fact
,
&
_param4Fact
,
&
_param5Fact
,
&
_param6Fact
,
&
_param7Fact
};
Fact
*
rgParamFacts
[
7
]
=
{
&
_param1Fact
,
&
_param2Fact
,
&
_param3Fact
,
&
_param4Fact
,
&
_param5Fact
,
&
_param6Fact
,
&
_param7Fact
};
rgParamFacts
[
paramInfo
->
param
()
-
1
]
->
setRawValue
(
paramInfo
->
defaultValue
());
rgParamFacts
[
paramInfo
->
param
()
-
1
]
->
setRawValue
(
paramInfo
->
defaultValue
());
...
@@ -782,11 +790,12 @@ void MissionItem::_sendCommandChanged(void)
...
@@ -782,11 +790,12 @@ void MissionItem::_sendCommandChanged(void)
QString
MissionItem
::
commandName
(
void
)
const
QString
MissionItem
::
commandName
(
void
)
const
{
{
if
(
_mavCmdInfoMap
.
contains
((
MAV_CMD
)
command
()))
{
MAV_CMD
command
=
(
MAV_CMD
)
this
->
command
();
const
MavCmdInfo
*
mavCmdInfo
=
_mavCmdInfoMap
[(
MAV_CMD
)
command
()];
if
(
_missionCommands
->
contains
(
command
))
{
const
MavCmdInfo
*
mavCmdInfo
=
_missionCommands
->
getMavCmdInfo
(
command
,
_vehicle
);
return
mavCmdInfo
->
friendlyName
().
isEmpty
()
?
mavCmdInfo
->
rawName
()
:
mavCmdInfo
->
friendlyName
();
return
mavCmdInfo
->
friendlyName
().
isEmpty
()
?
mavCmdInfo
->
rawName
()
:
mavCmdInfo
->
friendlyName
();
}
else
{
}
else
{
return
QString
(
"Unknown: %1"
).
arg
(
command
()
);
return
QString
(
"Unknown: %1"
).
arg
(
command
);
}
}
}
}
...
...
src/MissionManager/MissionItem.h
View file @
96995949
...
@@ -46,9 +46,10 @@ class MissionItem : public QObject
...
@@ -46,9 +46,10 @@ class MissionItem : public QObject
Q_OBJECT
Q_OBJECT
public:
public:
MissionItem
(
QObject
*
parent
=
NULL
);
MissionItem
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
MissionItem
(
int
sequenceNumber
,
MissionItem
(
Vehicle
*
vehicle
,
int
sequenceNumber
,
MAV_CMD
command
,
MAV_CMD
command
,
MAV_FRAME
frame
,
MAV_FRAME
frame
,
double
param1
,
double
param1
,
...
@@ -212,6 +213,7 @@ private:
...
@@ -212,6 +213,7 @@ private:
void
_setupMetaData
(
void
);
void
_setupMetaData
(
void
);
private:
private:
Vehicle
*
_vehicle
;
///< Vehicle associated with this item, NULL for offline mode
bool
_rawEdit
;
bool
_rawEdit
;
bool
_dirty
;
bool
_dirty
;
int
_sequenceNumber
;
int
_sequenceNumber
;
...
@@ -257,7 +259,7 @@ private:
...
@@ -257,7 +259,7 @@ private:
bool
_syncingAltitudeRelativeToHomeAndFrame
;
///< true: already in a sync signal, prevents signal loop
bool
_syncingAltitudeRelativeToHomeAndFrame
;
///< true: already in a sync signal, prevents signal loop
bool
_syncingHeadingDegreesAndParam4
;
///< true: already in a sync signal, prevents signal loop
bool
_syncingHeadingDegreesAndParam4
;
///< true: already in a sync signal, prevents signal loop
const
QMap
<
MAV_CMD
,
MavCmdInfo
*>&
_mavCmdInfoMap
;
const
MissionCommands
*
_missionCommands
;
};
};
QDebug
operator
<<
(
QDebug
dbg
,
const
MissionItem
&
missionItem
);
QDebug
operator
<<
(
QDebug
dbg
,
const
MissionItem
&
missionItem
);
...
...
src/MissionManager/MissionItemTest.cc
View file @
96995949
...
@@ -103,7 +103,8 @@ void MissionItemTest::_test(void)
...
@@ -103,7 +103,8 @@ void MissionItemTest::_test(void)
qDebug
()
<<
"Command:"
<<
info
->
command
;
qDebug
()
<<
"Command:"
<<
info
->
command
;
MissionItem
*
item
=
new
MissionItem
(
1
,
MissionItem
*
item
=
new
MissionItem
(
NULL
,
// Vehicle
1
,
info
->
command
,
info
->
command
,
info
->
frame
,
info
->
frame
,
10.1234567
,
10.1234567
,
...
@@ -158,7 +159,7 @@ void MissionItemTest::_test(void)
...
@@ -158,7 +159,7 @@ void MissionItemTest::_test(void)
QCOMPARE
(
factCount
,
expected
->
cFactValues
);
QCOMPARE
(
factCount
,
expected
->
cFactValues
);
// Validate that loading is working correctly
// Validate that loading is working correctly
MissionItem
*
loadedItem
=
new
MissionItem
();
MissionItem
*
loadedItem
=
new
MissionItem
(
NULL
/* Vehicle */
);
QTextStream
loadStream
(
&
savedItemString
,
QIODevice
::
ReadOnly
);
QTextStream
loadStream
(
&
savedItemString
,
QIODevice
::
ReadOnly
);
QVERIFY
(
loadedItem
->
load
(
loadStream
));
QVERIFY
(
loadedItem
->
load
(
loadStream
));
QCOMPARE
(
loadedItem
->
coordinate
().
latitude
(),
item
->
coordinate
().
latitude
());
QCOMPARE
(
loadedItem
->
coordinate
().
latitude
(),
item
->
coordinate
().
latitude
());
...
@@ -180,7 +181,7 @@ void MissionItemTest::_test(void)
...
@@ -180,7 +181,7 @@ void MissionItemTest::_test(void)
void
MissionItemTest
::
_testDefaultValues
(
void
)
void
MissionItemTest
::
_testDefaultValues
(
void
)
{
{
MissionItem
item
;
MissionItem
item
(
NULL
/* Vehicle */
)
;
item
.
setCommand
(
MAV_CMD_NAV_WAYPOINT
);
item
.
setCommand
(
MAV_CMD_NAV_WAYPOINT
);
item
.
setFrame
(
MAV_FRAME_GLOBAL_RELATIVE_ALT
);
item
.
setFrame
(
MAV_FRAME_GLOBAL_RELATIVE_ALT
);
...
...
src/MissionManager/MissionManager.cc
View file @
96995949
...
@@ -251,7 +251,8 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message)
...
@@ -251,7 +251,8 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message)
_requestItemRetryCount
=
0
;
_requestItemRetryCount
=
0
;
_itemIndicesToRead
.
removeOne
(
missionItem
.
seq
);
_itemIndicesToRead
.
removeOne
(
missionItem
.
seq
);
MissionItem
*
item
=
new
MissionItem
(
missionItem
.
seq
,
MissionItem
*
item
=
new
MissionItem
(
_vehicle
,
missionItem
.
seq
,
(
MAV_CMD
)
missionItem
.
command
,
(
MAV_CMD
)
missionItem
.
command
,
(
MAV_FRAME
)
missionItem
.
frame
,
(
MAV_FRAME
)
missionItem
.
frame
,
missionItem
.
param1
,
missionItem
.
param1
,
...
...
src/MissionManager/MissionManagerTest.cc
View file @
96995949
...
@@ -50,7 +50,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
...
@@ -50,7 +50,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
QmlObjectListModel
*
list
=
new
QmlObjectListModel
();
QmlObjectListModel
*
list
=
new
QmlObjectListModel
();
// Editor has a home position item on the front, so we do the same
// Editor has a home position item on the front, so we do the same
MissionItem
*
homeItem
=
new
MissionItem
(
this
);
MissionItem
*
homeItem
=
new
MissionItem
(
NULL
/* Vehicle */
,
this
);
homeItem
->
setHomePositionSpecialCase
(
true
);
homeItem
->
setHomePositionSpecialCase
(
true
);
homeItem
->
setHomePositionValid
(
false
);
homeItem
->
setHomePositionValid
(
false
);
homeItem
->
setCommand
(
MavlinkQmlSingleton
::
MAV_CMD_NAV_WAYPOINT
);
homeItem
->
setCommand
(
MavlinkQmlSingleton
::
MAV_CMD_NAV_WAYPOINT
);
...
@@ -61,7 +61,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
...
@@ -61,7 +61,7 @@ void MissionManagerTest::_writeItems(MockLinkMissionItemHandler::FailureMode_t f
for
(
size_t
i
=
0
;
i
<
_cTestCases
;
i
++
)
{
for
(
size_t
i
=
0
;
i
<
_cTestCases
;
i
++
)
{
const
TestCase_t
*
testCase
=
&
_rgTestCases
[
i
];
const
TestCase_t
*
testCase
=
&
_rgTestCases
[
i
];
MissionItem
*
item
=
new
MissionItem
(
list
);
MissionItem
*
item
=
new
MissionItem
(
NULL
/* Vehicle */
,
list
);
QTextStream
loadStream
(
testCase
->
itemStream
,
QIODevice
::
ReadOnly
);
QTextStream
loadStream
(
testCase
->
itemStream
,
QIODevice
::
ReadOnly
);
QVERIFY
(
item
->
load
(
loadStream
));
QVERIFY
(
item
->
load
(
loadStream
));
...
...
src/QGCLoggingCategory.cc
View file @
96995949
...
@@ -29,6 +29,8 @@
...
@@ -29,6 +29,8 @@
// Add Global logging categories (not class specific) here using QGC_LOGGING_CATEGORY
// Add Global logging categories (not class specific) here using QGC_LOGGING_CATEGORY
QGC_LOGGING_CATEGORY
(
FirmwareUpgradeLog
,
"FirmwareUpgradeLog"
)
QGC_LOGGING_CATEGORY
(
FirmwareUpgradeLog
,
"FirmwareUpgradeLog"
)
QGC_LOGGING_CATEGORY
(
FirmwareUpgradeVerboseLog
,
"FirmwareUpgradeVerboseLog"
)
QGC_LOGGING_CATEGORY
(
FirmwareUpgradeVerboseLog
,
"FirmwareUpgradeVerboseLog"
)
QGC_LOGGING_CATEGORY
(
MissionCommandsLog
,
"MissionCommandsLog"
)
QGCLoggingCategoryRegister
*
_instance
=
NULL
;
QGCLoggingCategoryRegister
*
_instance
=
NULL
;
...
...
src/QGCLoggingCategory.h
View file @
96995949
...
@@ -33,6 +33,7 @@
...
@@ -33,6 +33,7 @@
// Add Global logging categories (not class specific) here using Q_DECLARE_LOGGING_CATEGORY
// Add Global logging categories (not class specific) here using Q_DECLARE_LOGGING_CATEGORY
Q_DECLARE_LOGGING_CATEGORY
(
FirmwareUpgradeLog
)
Q_DECLARE_LOGGING_CATEGORY
(
FirmwareUpgradeLog
)
Q_DECLARE_LOGGING_CATEGORY
(
FirmwareUpgradeVerboseLog
)
Q_DECLARE_LOGGING_CATEGORY
(
FirmwareUpgradeVerboseLog
)
Q_DECLARE_LOGGING_CATEGORY
(
MissionCommandsLog
)
/// @def QGC_LOGGING_CATEGORY
/// @def QGC_LOGGING_CATEGORY
/// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a
/// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a
...
...
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