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
6cbba176
Commit
6cbba176
authored
Apr 09, 2017
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Support for flight speed change in Waypoint item
parent
a4248679
Changes
26
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
26 changed files
with
487 additions
and
221 deletions
+487
-221
qgroundcontrol.pro
qgroundcontrol.pro
+3
-0
qgroundcontrol.qrc
qgroundcontrol.qrc
+1
-0
ArduCopterFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+14
-0
ArduCopterFirmwarePlugin.h
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
+1
-0
FirmwarePlugin.cc
src/FirmwarePlugin/FirmwarePlugin.cc
+12
-0
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+5
-0
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+19
-1
PX4FirmwarePlugin.h
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
+1
-0
CameraSection.cc
src/MissionManager/CameraSection.cc
+20
-10
CameraSection.h
src/MissionManager/CameraSection.h
+16
-36
MavCmdInfoCommon.json
src/MissionManager/MavCmdInfoCommon.json
+0
-1
MissionCommandUIInfo.cc
src/MissionManager/MissionCommandUIInfo.cc
+2
-15
MissionCommandUIInfo.h
src/MissionManager/MissionCommandUIInfo.h
+0
-4
MissionController.cc
src/MissionManager/MissionController.cc
+6
-4
MissionSettings.FactMetaData.json
src/MissionManager/MissionSettings.FactMetaData.json
+0
-8
MissionSettingsItem.cc
src/MissionManager/MissionSettingsItem.cc
+25
-100
MissionSettingsItem.h
src/MissionManager/MissionSettingsItem.h
+7
-11
Section.h
src/MissionManager/Section.h
+66
-0
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+39
-19
SimpleMissionItem.h
src/MissionManager/SimpleMissionItem.h
+11
-6
SpeedSection.FactMetaData.json
src/MissionManager/SpeedSection.FactMetaData.json
+11
-0
SpeedSection.cc
src/MissionManager/SpeedSection.cc
+145
-0
SpeedSection.h
src/MissionManager/SpeedSection.h
+56
-0
MissionSettingsEditor.qml
src/PlanView/MissionSettingsEditor.qml
+6
-5
SimpleItemEditor.qml
src/PlanView/SimpleItemEditor.qml
+20
-0
MissionItemIndexLabel.qml
src/QmlControls/MissionItemIndexLabel.qml
+1
-1
No files found.
qgroundcontrol.pro
View file @
6cbba176
...
...
@@ -469,6 +469,8 @@ HEADERS += \
src/MissionManager/RallyPointController.h \
src/MissionManager/RallyPointManager.h \
src/MissionManager/SimpleMissionItem.h \
src/MissionManager/Section.h \
src/MissionManager/SpeedSection.h \
src/MissionManager/SurveyMissionItem.h \
src/MissionManager/VisualMissionItem.h \
src/PositionManager/PositionManager.h \
...
...
@@ -648,6 +650,7 @@ SOURCES += \
src/MissionManager/RallyPointController.cc \
src/MissionManager/RallyPointManager.cc \
src/MissionManager/SimpleMissionItem.cc \
src/MissionManager/SpeedSection.cc \
src/MissionManager/SurveyMissionItem.cc \
src/MissionManager/VisualMissionItem.cc \
src/PositionManager/PositionManager.cpp \
...
...
qgroundcontrol.qrc
View file @
6cbba176
...
...
@@ -197,6 +197,7 @@
<file alias="FWLandingPattern.FactMetaData.json">src/MissionManager/FWLandingPattern.FactMetaData.json</file>
<file alias="USBBoardInfo.json">src/comm/USBBoardInfo.json</file>
<file alias="CameraSection.FactMetaData.json">src/MissionManager/CameraSection.FactMetaData.json</file>
<file alias="SpeedSection.FactMetaData.json">src/MissionManager/SpeedSection.FactMetaData.json</file>
<file alias="MissionSettings.FactMetaData.json">src/MissionManager/MissionSettings.FactMetaData.json</file>
<file alias="Vehicle/VehicleFact.json">src/Vehicle/VehicleFact.json</file>
<file alias="Vehicle/BatteryFact.json">src/Vehicle/BatteryFact.json</file>
...
...
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
6cbba176
...
...
@@ -241,3 +241,17 @@ bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle*
}
return
false
;
}
void
ArduCopterFirmwarePlugin
::
missionFlightSpeedInfo
(
Vehicle
*
vehicle
,
double
&
hoverSpeed
,
double
&
cruiseSpeed
)
{
QString
hoverSpeedParam
(
"WPNAV_SPEED"
);
// First pull settings defaults
FirmwarePlugin
::
missionFlightSpeedInfo
(
vehicle
,
hoverSpeed
,
cruiseSpeed
);
cruiseSpeed
=
0
;
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
hoverSpeedParam
))
{
Fact
*
speed
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
hoverSpeedParam
);
hoverSpeed
=
speed
->
rawValue
().
toDouble
();
}
}
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h
View file @
6cbba176
...
...
@@ -76,6 +76,7 @@ public:
QString
takeControlFlightMode
(
void
)
const
override
{
return
QString
(
"Stablize"
);
}
bool
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
final
;
QString
autoDisarmParameter
(
Vehicle
*
vehicle
)
final
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"DISARM_DELAY"
);
}
void
missionFlightSpeedInfo
(
Vehicle
*
vehicle
,
double
&
hoverSpeed
,
double
&
cruiseSpeed
)
override
;
private:
static
bool
_remapParamNameIntialized
;
...
...
src/FirmwarePlugin/FirmwarePlugin.cc
View file @
6cbba176
...
...
@@ -11,6 +11,8 @@
#include "QGCApplication.h"
#include "Generic/GenericAutoPilotPlugin.h"
#include "CameraMetaData.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include <QDebug>
...
...
@@ -452,3 +454,13 @@ QString FirmwarePlugin::autoDisarmParameter(Vehicle* vehicle)
Q_UNUSED
(
vehicle
);
return
QString
();
}
void
FirmwarePlugin
::
missionFlightSpeedInfo
(
Vehicle
*
vehicle
,
double
&
hoverSpeed
,
double
&
cruiseSpeed
)
{
Q_UNUSED
(
vehicle
);
// Best we can do is use settings
AppSettings
*
appSettings
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
();
hoverSpeed
=
appSettings
->
offlineEditingHoverSpeed
()
->
rawValue
().
toDouble
();
cruiseSpeed
=
appSettings
->
offlineEditingCruiseSpeed
()
->
rawValue
().
toDouble
();
}
src/FirmwarePlugin/FirmwarePlugin.h
View file @
6cbba176
...
...
@@ -282,6 +282,11 @@ public:
/// @param[out] cruiseAmps Current draw in amps during cruise
virtual
void
batteryConsumptionData
(
Vehicle
*
vehicle
,
int
&
mAhBattery
,
double
&
hoverAmps
,
double
&
cruiseAmps
)
const
;
/// Returns the default mission flight speeds.
/// @param[out] hoverSpeed Flight speed for vehicle flying in multi-rotor mode. 0 for none, or not available.
/// @param[out] cruiseSpeed Flight speed for vehicle flying in fixed wing forward flight mode. 0 for none, or not available.
virtual
void
missionFlightSpeedInfo
(
Vehicle
*
vehicle
,
double
&
hoverSpeed
,
double
&
cruiseSpeed
);
// Returns the parameter which control auto-dismar. Assume == 0 means no auto disarm
virtual
QString
autoDisarmParameter
(
Vehicle
*
vehicle
);
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
6cbba176
...
...
@@ -518,9 +518,27 @@ void PX4FirmwarePlugin::_handleAutopilotVersion(Vehicle* vehicle, mavlink_messag
bool
PX4FirmwarePlugin
::
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
{
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"MIS_YAWMODE"
)))
{
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"MIS_YAWMODE"
)))
{
Fact
*
yawMode
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"MIS_YAWMODE"
));
return
yawMode
&&
yawMode
->
rawValue
().
toInt
()
==
1
;
}
return
false
;
}
void
PX4FirmwarePlugin
::
missionFlightSpeedInfo
(
Vehicle
*
vehicle
,
double
&
hoverSpeed
,
double
&
cruiseSpeed
)
{
QString
hoverSpeedParam
(
"MPC_XY_CRUISE"
);
QString
cruiseSpeedParam
(
"FW_AIRSPD_TRIM"
);
// First pull settings defaults
FirmwarePlugin
::
missionFlightSpeedInfo
(
vehicle
,
hoverSpeed
,
cruiseSpeed
);
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
hoverSpeedParam
))
{
Fact
*
speed
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
hoverSpeedParam
);
hoverSpeed
=
speed
->
rawValue
().
toDouble
();
}
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
cruiseSpeedParam
))
{
Fact
*
speed
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
cruiseSpeedParam
);
cruiseSpeed
=
speed
->
rawValue
().
toDouble
();
}
}
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
View file @
6cbba176
...
...
@@ -68,6 +68,7 @@ public:
QString
brandImageOutdoor
(
const
Vehicle
*
vehicle
)
const
override
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"/qmlimages/PX4/BrandImage"
);
}
bool
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
override
;
QString
autoDisarmParameter
(
Vehicle
*
vehicle
)
override
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"COM_DISARM_LAND"
);
}
void
missionFlightSpeedInfo
(
Vehicle
*
vehicle
,
double
&
hoverSpeed
,
double
&
cruiseSpeed
)
override
;
protected:
typedef
struct
{
...
...
src/MissionManager/CameraSection.cc
View file @
6cbba176
...
...
@@ -20,8 +20,8 @@ const char* CameraSection::_cameraPhotoIntervalTimeName = "CameraPhotoInter
QMap
<
QString
,
FactMetaData
*>
CameraSection
::
_metaDataMap
;
CameraSection
::
CameraSection
(
QObject
*
parent
)
:
QObject
(
parent
)
CameraSection
::
CameraSection
(
Vehicle
*
vehicle
,
QObject
*
parent
)
:
Section
(
vehicle
,
parent
)
,
_available
(
false
)
,
_settingsSpecified
(
false
)
,
_specifyGimbal
(
false
)
...
...
@@ -48,8 +48,8 @@ CameraSection::CameraSection(QObject* parent)
_cameraPhotoIntervalDistanceFact
.
setRawValue
(
_cameraPhotoIntervalDistanceFact
.
rawDefaultValue
());
_cameraPhotoIntervalTimeFact
.
setRawValue
(
_cameraPhotoIntervalTimeFact
.
rawDefaultValue
());
connect
(
this
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
CameraSection
::
_setDirtyAndUpdate
Mission
ItemCount
);
connect
(
&
_cameraActionFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirtyAndUpdate
Mission
ItemCount
);
connect
(
this
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
CameraSection
::
_setDirtyAndUpdateItemCount
);
connect
(
&
_cameraActionFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirtyAndUpdateItemCount
);
connect
(
&
_gimbalPitchFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirty
);
connect
(
&
_gimbalYawFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirty
);
...
...
@@ -67,7 +67,7 @@ void CameraSection::setSpecifyGimbal(bool specifyGimbal)
}
}
int
CameraSection
::
missionI
temCount
(
void
)
const
int
CameraSection
::
i
temCount
(
void
)
const
{
int
itemCount
=
0
;
...
...
@@ -89,9 +89,9 @@ void CameraSection::setDirty(bool dirty)
}
}
void
CameraSection
::
append
MissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
,
int
nextSequenceNumber
)
void
CameraSection
::
append
SectionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
,
int
&
nextSequenceNumber
)
{
// IMPORTANT NOTE: If anything changes here you must also change CameraSection::scanFor
MissionSettings
// IMPORTANT NOTE: If anything changes here you must also change CameraSection::scanFor
Section
if
(
_specifyGimbal
)
{
MissionItem
*
item
=
new
MissionItem
(
nextSequenceNumber
++
,
...
...
@@ -188,7 +188,7 @@ void CameraSection::appendMissionItems(QList<MissionItem*>& items, QObject* miss
}
}
bool
CameraSection
::
scanFor
CameraSection
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
)
bool
CameraSection
::
scanFor
Section
(
QmlObjectListModel
*
visualItems
,
int
&
scanIndex
)
{
bool
foundGimbal
=
false
;
bool
foundCameraAction
=
false
;
...
...
@@ -196,6 +196,10 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
qCDebug
(
CameraSectionLog
)
<<
"CameraSection::scanForCameraSection"
<<
visualItems
->
count
()
<<
scanIndex
;
if
(
!
_available
||
scanIndex
>=
visualItems
->
count
())
{
return
false
;
}
// Scan through the initial mission items for possible mission settings
while
(
!
stopLooking
&&
visualItems
->
count
()
>
scanIndex
)
{
...
...
@@ -214,6 +218,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
case
MAV_CMD_DO_MOUNT_CONTROL
:
if
(
!
foundGimbal
&&
missionItem
.
param2
()
==
0
&&
missionItem
.
param4
()
==
0
&&
missionItem
.
param5
()
==
0
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
MAV_MOUNT_MODE_MAVLINK_TARGETING
)
{
foundGimbal
=
true
;
scanIndex
++
;
setSpecifyGimbal
(
true
);
gimbalPitch
()
->
setRawValue
(
missionItem
.
param1
());
gimbalYaw
()
->
setRawValue
(
missionItem
.
param3
());
...
...
@@ -226,6 +231,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
case
MAV_CMD_IMAGE_START_CAPTURE
:
if
(
!
foundCameraAction
&&
missionItem
.
param1
()
!=
0
&&
missionItem
.
param2
()
==
0
&&
missionItem
.
param3
()
==
-
1
&&
missionItem
.
param4
()
==
0
&&
missionItem
.
param5
()
==
0
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
0
)
{
foundCameraAction
=
true
;
scanIndex
++
;
cameraAction
()
->
setRawValue
(
TakePhotosIntervalTime
);
cameraPhotoIntervalTime
()
->
setRawValue
(
missionItem
.
param1
());
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
...
...
@@ -245,6 +251,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
if
(
nextMissionItem
.
command
()
==
MAV_CMD_IMAGE_STOP_CAPTURE
&&
nextMissionItem
.
param1
()
==
0
&&
nextMissionItem
.
param2
()
==
0
&&
nextMissionItem
.
param3
()
==
0
&&
nextMissionItem
.
param4
()
==
0
&&
nextMissionItem
.
param5
()
==
0
&&
nextMissionItem
.
param6
()
==
0
&&
nextMissionItem
.
param7
()
==
0
)
{
// We found a stop taking photos pair
foundCameraAction
=
true
;
scanIndex
+=
2
;
cameraAction
()
->
setRawValue
(
StopTakingPhotos
);
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
...
...
@@ -257,6 +264,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
// We didn't find a stop taking photos pair, check for trigger distance
if
(
missionItem
.
param1
()
>
0
)
{
foundCameraAction
=
true
;
scanIndex
++
;
cameraAction
()
->
setRawValue
(
TakePhotoIntervalDistance
);
cameraPhotoIntervalDistance
()
->
setRawValue
(
missionItem
.
param1
());
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
...
...
@@ -270,6 +278,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
case
MAV_CMD_VIDEO_START_CAPTURE
:
if
(
!
foundCameraAction
&&
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
==
-
1
&&
missionItem
.
param3
()
==
-
1
&&
missionItem
.
param4
()
==
0
&&
missionItem
.
param5
()
==
0
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
0
)
{
foundCameraAction
=
true
;
scanIndex
++
;
cameraAction
()
->
setRawValue
(
TakeVideo
);
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
}
...
...
@@ -279,6 +288,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
case
MAV_CMD_VIDEO_STOP_CAPTURE
:
if
(
!
foundCameraAction
&&
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
==
0
&&
missionItem
.
param3
()
==
0
&&
missionItem
.
param4
()
==
0
&&
missionItem
.
param5
()
==
0
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
0
)
{
foundCameraAction
=
true
;
scanIndex
++
;
cameraAction
()
->
setRawValue
(
StopTakingVideo
);
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
}
...
...
@@ -304,9 +314,9 @@ void CameraSection::_setDirty(void)
setDirty
(
true
);
}
void
CameraSection
::
_setDirtyAndUpdate
Mission
ItemCount
(
void
)
void
CameraSection
::
_setDirtyAndUpdateItemCount
(
void
)
{
emit
missionItemCountChanged
(
missionI
temCount
());
emit
itemCountChanged
(
i
temCount
());
setDirty
(
true
);
}
...
...
src/MissionManager/CameraSection.h
View file @
6cbba176
...
...
@@ -7,21 +7,19 @@
*
****************************************************************************/
#ifndef CameraSection_H
#define CameraSection_H
#pragma once
#include "Section.h"
#include "ComplexMissionItem.h"
#include "MissionItem.h"
#include "Fact.h"
Q_DECLARE_LOGGING_CATEGORY
(
CameraSectionLog
)
class
CameraSection
:
public
QObject
class
CameraSection
:
public
Section
{
Q_OBJECT
public:
CameraSection
(
QObject
*
parent
=
NULL
);
CameraSection
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
// These nume values must match the json meta data
enum
CameraAction
{
...
...
@@ -34,8 +32,6 @@ public:
};
Q_ENUMS
(
CameraAction
)
Q_PROPERTY
(
bool
available
READ
available
WRITE
setAvailable
NOTIFY
availableChanged
)
Q_PROPERTY
(
bool
settingsSpecified
MEMBER
_settingsSpecified
NOTIFY
settingsSpecifiedChanged
)
Q_PROPERTY
(
bool
specifyGimbal
READ
specifyGimbal
WRITE
setSpecifyGimbal
NOTIFY
specifyGimbalChanged
)
Q_PROPERTY
(
Fact
*
gimbalPitch
READ
gimbalPitch
CONSTANT
)
Q_PROPERTY
(
Fact
*
gimbalYaw
READ
gimbalYaw
CONSTANT
)
...
...
@@ -43,8 +39,6 @@ public:
Q_PROPERTY
(
Fact
*
cameraPhotoIntervalTime
READ
cameraPhotoIntervalTime
CONSTANT
)
Q_PROPERTY
(
Fact
*
cameraPhotoIntervalDistance
READ
cameraPhotoIntervalDistance
CONSTANT
)
bool
available
(
void
)
const
{
return
_available
;
}
void
setAvailable
(
bool
available
);
bool
specifyGimbal
(
void
)
const
{
return
_specifyGimbal
;
}
Fact
*
gimbalYaw
(
void
)
{
return
&
_gimbalYawFact
;
}
Fact
*
gimbalPitch
(
void
)
{
return
&
_gimbalPitchFact
;
}
...
...
@@ -52,40 +46,28 @@ public:
Fact
*
cameraPhotoIntervalTime
(
void
)
{
return
&
_cameraPhotoIntervalTimeFact
;
}
Fact
*
cameraPhotoIntervalDistance
(
void
)
{
return
&
_cameraPhotoIntervalDistanceFact
;
}
void
setSpecifyGimbal
(
bool
specifyGimbal
);
///< @return The gimbal yaw specified by this item, NaN if not specified
double
specifiedGimbalYaw
(
void
)
const
;
/// Scans the loaded items for the section items
/// @param visualItems Item list
/// @param scanIndex Index to start scanning from
/// @return true: camera section found
bool
scanForCameraSection
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
/// Appends the mission items associated with this section
/// @param items List to append to
/// @param missionItemParent QObject parent for created MissionItems
/// @param nextSequenceNumber Sequence number for first item
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
,
int
nextSequenceNumber
);
void
setSpecifyGimbal
(
bool
specifyGimbal
);
bool
dirty
(
void
)
const
{
return
_dirty
;
}
void
setDirty
(
bool
dirty
);
/// Returns the number of mission items represented by this section.
/// Signals: missionItemCountChanged on change
int
missionItemCount
(
void
)
const
;
// Overrides from Section
bool
available
(
void
)
const
override
{
return
_available
;
}
bool
dirty
(
void
)
const
override
{
return
_dirty
;
}
void
setAvailable
(
bool
available
)
override
;
void
setDirty
(
bool
dirty
)
override
;
bool
scanForSection
(
QmlObjectListModel
*
visualItems
,
int
&
scanIndex
)
override
;
void
appendSectionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
,
int
&
seqNum
)
override
;
int
itemCount
(
void
)
const
override
;
bool
settingsSpecified
(
void
)
const
override
{
return
_settingsSpecified
;
}
signals:
void
availableChanged
(
bool
available
);
void
settingsSpecifiedChanged
(
bool
settingsSpecified
);
void
dirtyChanged
(
bool
dirty
);
bool
specifyGimbalChanged
(
bool
specifyGimbal
);
void
missionItemCountChanged
(
int
missionItemCount
);
void
specifiedGimbalYawChanged
(
double
gimbalYaw
);
private
slots
:
void
_setDirty
(
void
);
void
_setDirtyAndUpdate
Mission
ItemCount
(
void
);
void
_setDirtyAndUpdateItemCount
(
void
);
void
_updateSpecifiedGimbalYaw
(
void
);
private:
...
...
@@ -107,5 +89,3 @@ private:
static
const
char
*
_cameraPhotoIntervalDistanceName
;
static
const
char
*
_cameraPhotoIntervalTimeName
;
};
#endif
src/MissionManager/MavCmdInfoCommon.json
View file @
6cbba176
...
...
@@ -32,7 +32,6 @@
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"cameraSection"
:
true
,
"param1"
:
{
"label"
:
"Hold"
,
"units"
:
"secs"
,
...
...
src/MissionManager/MissionCommandUIInfo.cc
View file @
6cbba176
...
...
@@ -39,7 +39,6 @@ const char* MissionCommandUIInfo::_specifiesCoordinateJsonKey = "specifiesCoor
const
char
*
MissionCommandUIInfo
::
_specifiesAltitudeOnlyJsonKey
=
"specifiesAltitudeOnly"
;
const
char
*
MissionCommandUIInfo
::
_unitsJsonKey
=
"units"
;
const
char
*
MissionCommandUIInfo
::
_commentJsonKey
=
"comment"
;
const
char
*
MissionCommandUIInfo
::
_cameraSectionJsonKey
=
"cameraSection"
;
const
char
*
MissionCommandUIInfo
::
_advancedCategory
=
"Advanced"
;
MissionCmdParamInfo
::
MissionCmdParamInfo
(
QObject
*
parent
)
...
...
@@ -165,15 +164,6 @@ bool MissionCommandUIInfo::specifiesAltitudeOnly(void) const
}
}
bool
MissionCommandUIInfo
::
cameraSection
(
void
)
const
{
if
(
_infoMap
.
contains
(
_cameraSectionJsonKey
))
{
return
_infoMap
[
_cameraSectionJsonKey
].
toBool
();
}
else
{
return
false
;
}
}
void
MissionCommandUIInfo
::
_overrideInfo
(
MissionCommandUIInfo
*
uiInfo
)
{
// Override info values
...
...
@@ -209,7 +199,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
QStringList
allKeys
;
allKeys
<<
_idJsonKey
<<
_rawNameJsonKey
<<
_friendlyNameJsonKey
<<
_descriptionJsonKey
<<
_standaloneCoordinateJsonKey
<<
_specifiesCoordinateJsonKey
<<
_friendlyEditJsonKey
<<
_param1JsonKey
<<
_param2JsonKey
<<
_param3JsonKey
<<
_param4JsonKey
<<
_param5JsonKey
<<
_param6JsonKey
<<
_param7JsonKey
<<
_paramRemoveJsonKey
<<
_categoryJsonKey
<<
_
cameraSectionJsonKey
<<
_
specifiesAltitudeOnlyJsonKey
;
<<
_paramRemoveJsonKey
<<
_categoryJsonKey
<<
_specifiesAltitudeOnlyJsonKey
;
// Look for unknown keys in top level object
foreach
(
const
QString
&
key
,
jsonObject
.
keys
())
{
...
...
@@ -241,7 +231,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
QList
<
QJsonValue
::
Type
>
types
;
types
<<
QJsonValue
::
Double
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
Object
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Bool
;
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
Bool
;
if
(
!
JsonHelper
::
validateKeyTypes
(
jsonObject
,
allKeys
,
types
,
internalError
))
{
errorString
=
_loadErrorString
(
internalError
);
return
false
;
...
...
@@ -275,9 +265,6 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
if
(
jsonObject
.
contains
(
_friendlyEditJsonKey
))
{
_infoMap
[
_friendlyEditJsonKey
]
=
jsonObject
.
value
(
_friendlyEditJsonKey
).
toVariant
();
}
if
(
jsonObject
.
contains
(
_cameraSectionJsonKey
))
{
_infoMap
[
_cameraSectionJsonKey
]
=
jsonObject
.
value
(
_cameraSectionJsonKey
).
toVariant
();
}
if
(
jsonObject
.
contains
(
_paramRemoveJsonKey
))
{
QStringList
indexList
=
jsonObject
.
value
(
_paramRemoveJsonKey
).
toString
().
split
(
QStringLiteral
(
","
));
foreach
(
const
QString
&
indexString
,
indexList
)
{
...
...
src/MissionManager/MissionCommandUIInfo.h
View file @
6cbba176
...
...
@@ -97,7 +97,6 @@ private:
/// specifiesAltitudeOnly bool false true: Command specifies an altitude only (no coordinate)
/// standaloneCoordinate bool false true: Vehicle does not fly through coordinate associated with command (exampl: ROI)
/// friendlyEdit bool false true: Command supports friendly editing dialog, false: Command supports 'Show all values" style editing only
/// cameraSection bool false true: Camera section of additional settings is added to editor
/// category string Advanced Category which this command belongs to
/// paramRemove string Used by an override to remove params, example: "1,3" will remove params 1 and 3 on the override
/// param[1-7] object MissionCommandParamInfo object
...
...
@@ -120,7 +119,6 @@ public:
Q_PROPERTY
(
bool
specifiesCoordinate
READ
specifiesCoordinate
CONSTANT
)
Q_PROPERTY
(
bool
specifiesAltitudeOnly
READ
specifiesAltitudeOnly
CONSTANT
)
Q_PROPERTY
(
int
command
READ
intCommand
CONSTANT
)
Q_PROPERTY
(
bool
cameraSection
READ
cameraSection
CONSTANT
)
MAV_CMD
command
(
void
)
const
{
return
_command
;
}
int
intCommand
(
void
)
const
{
return
(
int
)
_command
;
}
...
...
@@ -133,7 +131,6 @@ public:
bool
isStandaloneCoordinate
(
void
)
const
;
bool
specifiesCoordinate
(
void
)
const
;
bool
specifiesAltitudeOnly
(
void
)
const
;
bool
cameraSection
(
void
)
const
;
/// Load the data in the object from the specified json
/// @param jsonObject Json object to load from
...
...
@@ -192,7 +189,6 @@ private:
static
const
char
*
_specifiesAltitudeOnlyJsonKey
;
static
const
char
*
_unitsJsonKey
;
static
const
char
*
_commentJsonKey
;
static
const
char
*
_cameraSectionJsonKey
;
static
const
char
*
_advancedCategory
;
friend
class
MissionCommandTree
;
...
...
src/MissionManager/MissionController.cc
View file @
6cbba176
...
...
@@ -1526,16 +1526,18 @@ void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualIte
qCDebug
(
MissionControllerLog
)
<<
"MissionController::_scanForAdditionalSettings count:scanIndex"
<<
visualItems
->
count
()
<<
scanIndex
;
MissionSettingsItem
*
settingsItem
=
qobject_cast
<
MissionSettingsItem
*>
(
visualItem
);
if
(
settingsItem
&&
settingsItem
->
scanForMissionSettings
(
visualItems
,
scanIndex
,
vehicle
))
{
if
(
settingsItem
&&
settingsItem
->
scanForMissionSettings
(
visualItems
,
scanIndex
))
{
continue
;
}
SimpleMissionItem
*
simpleItem
=
qobject_cast
<
SimpleMissionItem
*>
(
visualItem
);
if
(
simpleItem
)
{
simpleItem
->
scanForSections
(
visualItems
,
scanIndex
+
1
,
vehicle
);
scanIndex
++
;
simpleItem
->
scanForSections
(
visualItems
,
scanIndex
,
vehicle
);
}
else
{
// Complex item, can't have sections
scanIndex
++
;
}
scanIndex
++
;
}
}
...
...
src/MissionManager/MissionSettings.FactMetaData.json
View file @
6cbba176
...
...
@@ -7,14 +7,6 @@
"decimalPlaces"
:
1
,
"defaultValue"
:
0
},
{
"name"
:
"FlightSpeed"
,
"shortDescription"
:
"Flight speed for mission."
,
"type"
:
"double"
,
"units"
:
"m/s"
,
"min"
:
0
,
"decimalPlaces"
:
1
},
{
"name"
:
"MissionEndAction"
,
"shortDescription"
:
"The action to take when the mission completed."
,
...
...
src/MissionManager/MissionSettingsItem.cc
View file @
6cbba176
This diff is collapsed.
Click to expand it.
src/MissionManager/MissionSettingsItem.h
View file @
6cbba176
...
...
@@ -15,6 +15,7 @@
#include "Fact.h"
#include "QGCLoggingCategory.h"
#include "CameraSection.h"
#include "SpeedSection.h"
Q_DECLARE_LOGGING_CATEGORY
(
MissionSettingsComplexItemLog
)
...
...
@@ -32,22 +33,19 @@ public:
};
Q_ENUMS
(
MissionEndAction
)
Q_PROPERTY
(
bool
specifyMissionFlightSpeed
READ
specifyMissionFlightSpeed
WRITE
setSpecifyMissionFlightSpeed
NOTIFY
specifyMissionFlightSpeedChanged
)
Q_PROPERTY
(
Fact
*
missionFlightSpeed
READ
missionFlightSpeed
CONSTANT
)
Q_PROPERTY
(
Fact
*
missionEndAction
READ
missionEndAction
CONSTANT
)
Q_PROPERTY
(
Fact
*
plannedHomePositionAltitude
READ
plannedHomePositionAltitude
CONSTANT
)
Q_PROPERTY
(
QObject
*
cameraSection
READ
cameraSection
CONSTANT
)
Q_PROPERTY
(
QObject
*
speedSection
READ
speedSection
CONSTANT
)
Fact
*
plannedHomePositionAltitude
(
void
)
{
return
&
_plannedHomePositionAltitudeFact
;
}
Fact
*
missionFlightSpeed
(
void
)
{
return
&
_missionFlightSpeedFact
;
}
Fact
*
missionEndAction
(
void
)
{
return
&
_missionEndActionFact
;
}
bool
specifyMissionFlightSpeed
(
void
)
const
{
return
_specifyMissionFlightSpeed
;
}
void
setSpecifyMissionFlightSpeed
(
bool
specifyMissionFlightSpeed
);
QObject
*
cameraSection
(
void
)
{
return
&
_cameraSection
;
}
QObject
*
speedSection
(
void
)
{
return
&
_speedSection
;
}
/// Scans the loaded items for settings items
static
bool
scanForMissionSettings
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
,
Vehicle
*
vehicle
);
static
bool
scanForMissionSettings
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
/// Adds the optional mission end action to the list
/// @param items Mission items list to append to
...
...
@@ -77,10 +75,10 @@ public:
QGeoCoordinate
coordinate
(
void
)
const
final
{
return
_plannedHomePositionCoordinate
;
}
QGeoCoordinate
exitCoordinate
(
void
)
const
final
{
return
_plannedHomePositionCoordinate
;
}
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
double
specifiedFlightSpeed
(
void
)
final
;
double
specifiedGimbalYaw
(
void
)
final
;
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
{
Q_UNUSED
(
newAltitude
);
/* no action */
}
double
specifiedFlightSpeed
(
void
)
final
;
bool
coordinateHasRelativeAltitude
(
void
)
const
final
{
return
true
;
}
bool
exitCoordinateHasRelativeAltitude
(
void
)
const
final
{
return
true
;
}
...
...
@@ -99,16 +97,15 @@ signals:
private
slots
:
void
_setDirtyAndUpdateLastSequenceNumber
(
void
);
void
_setDirty
(
void
);
void
_
cameraSectionDirtyChanged
(
bool
dirty
);
void
_
sectionDirtyChanged
(
bool
dirty
);
void
_updateAltitudeInCoordinate
(
QVariant
value
);
private:
bool
_specifyMissionFlightSpeed
;
QGeoCoordinate
_plannedHomePositionCoordinate
;
// Does not include altitde
Fact
_plannedHomePositionAltitudeFact
;
Fact
_missionFlightSpeedFact
;
Fact
_missionEndActionFact
;
CameraSection
_cameraSection
;
SpeedSection
_speedSection
;
int
_sequenceNumber
;
bool
_dirty
;
...
...
@@ -116,7 +113,6 @@ private:
static
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
static
const
char
*
_plannedHomePositionAltitudeName
;
static
const
char
*
_missionFlightSpeedName
;
static
const
char
*
_missionEndActionName
;
};
...
...
src/MissionManager/Section.h
0 → 100644
View file @
6cbba176
/****************************************************************************
*
* (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.
*
****************************************************************************/
#pragma once
#include "MissionItem.h"
#include "Vehicle.h"
#include "QmlObjectListModel.h"
Q_DECLARE_LOGGING_CATEGORY
(
SectionLog
)
// A Section encapsulates a set of mission commands which can be associated with another simple mission item.
class
Section
:
public
QObject
{
Q_OBJECT
public:
Section
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
)
:
QObject
(
parent
)
,
_vehicle
(
vehicle
)
{
}
Q_PROPERTY
(
bool
available
READ
available
WRITE
setAvailable
NOTIFY
availableChanged
)
Q_PROPERTY
(
bool
settingsSpecified
READ
settingsSpecified
NOTIFY
settingsSpecifiedChanged
)
Q_PROPERTY
(
bool
dirty
READ
dirty
WRITE
setDirty
NOTIFY
availableChanged
)
virtual
bool
available
(
void
)
const
=
0
;
virtual
bool
settingsSpecified
(
void
)
const
=
0
;
virtual
bool
dirty
(
void
)
const
=
0
;
virtual
void
setAvailable
(
bool
available
)
=
0
;
virtual
void
setDirty
(
bool
dirty
)
=
0
;
/// Scans the loaded items for the section items
/// @param visualItems Item list
/// @param scanIndex[in,out] Index to start scanning from
/// @return true: section found, items added, scanIndex updated
virtual
bool
scanForSection
(
QmlObjectListModel
*
visualItems
,
int
&
scanIndex
)
=
0
;
/// Appends the mission items associated with this section
/// @param items List to append to
/// @param missionItemParent QObject parent for created MissionItems
/// @param nextSequenceNumber[in,out] Sequence number for first item, updated as items are added
virtual
void
appendSectionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
,
int
&
nextSequenceNumber
)
=
0
;
/// Returns the number of mission items represented by this section.
/// Signals: itemCountChanged
virtual
int
itemCount
(
void
)
const
=
0
;
signals:
void
availableChanged
(
bool
available
);
void
settingsSpecifiedChanged
(
bool
settingsSpecified
);
void
dirtyChanged
(
bool
dirty
);
void
itemCountChanged
(
int
itemCount
);
protected:
Vehicle
*
_vehicle
;
};
src/MissionManager/SimpleMissionItem.cc
View file @
6cbba176
...
...
@@ -52,6 +52,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
,
_rawEdit
(
false
)
,
_dirty
(
false
)
,
_ignoreDirtyChangeSignals
(
false
)
,
_speedSection
(
NULL
)
,
_cameraSection
(
NULL
)
,
_commandTree
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
())
,
_altitudeRelativeToHomeFact
(
0
,
"Altitude is relative to home"
,
FactMetaData
::
valueTypeUint32
)
...
...
@@ -72,7 +73,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
_setupMetaData
();
_connectSignals
();
_update
CameraSection
();
_update
OptionalSections
();
setDefaultsForCommand
();
_rebuildFacts
();
...
...
@@ -90,6 +91,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
,
_rawEdit
(
false
)
,
_dirty
(
false
)
,
_ignoreDirtyChangeSignals
(
false
)
,
_speedSection
(
NULL
)
,
_cameraSection
(
NULL
)
,
_commandTree
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
())
,
_altitudeRelativeToHomeFact
(
0
,
"Altitude is relative to home"
,
FactMetaData
::
valueTypeUint32
)
...
...
@@ -110,7 +112,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
_setupMetaData
();
_connectSignals
();
_update
CameraSection
();
_update
OptionalSections
();
_syncFrameToAltitudeRelativeToHome
();
_rebuildFacts
();
}
...
...
@@ -121,6 +123,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa
,
_rawEdit
(
false
)
,
_dirty
(
false
)
,
_ignoreDirtyChangeSignals
(
false
)
,
_speedSection
(
NULL
)
,
_cameraSection
(
NULL
)
,
_commandTree
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
())
,
_altitudeRelativeToHomeFact
(
0
,
"Altitude is relative to home"
,
FactMetaData
::
valueTypeUint32
)
...
...
@@ -136,7 +139,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa
_setupMetaData
();
_connectSignals
();
_update
CameraSection
();
_update
OptionalSections
();
*
this
=
other
;
...
...
@@ -651,7 +654,7 @@ void SimpleMissionItem::setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command)
{
if
((
MAV_CMD
)
command
!=
_missionItem
.
command
())
{
_missionItem
.
setCommand
((
MAV_CMD
)
command
);
_update
CameraSection
();
_update
OptionalSections
();
}
}
...
...
@@ -674,7 +677,11 @@ void SimpleMissionItem::setSequenceNumber(int sequenceNumber)
double
SimpleMissionItem
::
specifiedFlightSpeed
(
void
)
{
return
missionItem
().
specifiedFlightSpeed
();
if
(
_speedSection
->
specifyFlightSpeed
())
{
return
_speedSection
->
flightSpeed
()
->
rawValue
().
toDouble
();
}
else
{
return
missionItem
().
specifiedFlightSpeed
();
}
}
double
SimpleMissionItem
::
specifiedGimbalYaw
(
void
)
...
...
@@ -682,47 +689,59 @@ double SimpleMissionItem::specifiedGimbalYaw(void)
return
_cameraSection
->
available
()
?
_cameraSection
->
specifiedGimbalYaw
()
:
missionItem
().
specifiedGimbalYaw
();
}
bool
SimpleMissionItem
::
scanForSections
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
,
Vehicle
*
vehicle
)
bool
SimpleMissionItem
::
scanForSections
(
QmlObjectListModel
*
visualItems
,
int
&
scanIndex
,
Vehicle
*
vehicle
)
{
bool
sectionFound
=
false
;
Q_UNUSED
(
vehicle
);
if
(
_cameraSection
->
available
())
{
sectionFound
=
_cameraSection
->
scanForCameraSection
(
visualItems
,
scanIndex
);
sectionFound
|=
_cameraSection
->
scanForSection
(
visualItems
,
scanIndex
);
}
if
(
_speedSection
->
available
())
{