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
8f9befd8
Commit
8f9befd8
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
b8c17cdb
Changes
26
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
26 changed files
with
488 additions
and
221 deletions
+488
-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
+2
-1
No files found.
qgroundcontrol.pro
View file @
8f9befd8
...
@@ -469,6 +469,8 @@ HEADERS += \
...
@@ -469,6 +469,8 @@ HEADERS += \
src/MissionManager/RallyPointController.h \
src/MissionManager/RallyPointController.h \
src/MissionManager/RallyPointManager.h \
src/MissionManager/RallyPointManager.h \
src/MissionManager/SimpleMissionItem.h \
src/MissionManager/SimpleMissionItem.h \
src/MissionManager/Section.h \
src/MissionManager/SpeedSection.h \
src/MissionManager/SurveyMissionItem.h \
src/MissionManager/SurveyMissionItem.h \
src/MissionManager/VisualMissionItem.h \
src/MissionManager/VisualMissionItem.h \
src/PositionManager/PositionManager.h \
src/PositionManager/PositionManager.h \
...
@@ -648,6 +650,7 @@ SOURCES += \
...
@@ -648,6 +650,7 @@ SOURCES += \
src/MissionManager/RallyPointController.cc \
src/MissionManager/RallyPointController.cc \
src/MissionManager/RallyPointManager.cc \
src/MissionManager/RallyPointManager.cc \
src/MissionManager/SimpleMissionItem.cc \
src/MissionManager/SimpleMissionItem.cc \
src/MissionManager/SpeedSection.cc \
src/MissionManager/SurveyMissionItem.cc \
src/MissionManager/SurveyMissionItem.cc \
src/MissionManager/VisualMissionItem.cc \
src/MissionManager/VisualMissionItem.cc \
src/PositionManager/PositionManager.cpp \
src/PositionManager/PositionManager.cpp \
...
...
qgroundcontrol.qrc
View file @
8f9befd8
...
@@ -197,6 +197,7 @@
...
@@ -197,6 +197,7 @@
<file alias="FWLandingPattern.FactMetaData.json">src/MissionManager/FWLandingPattern.FactMetaData.json</file>
<file alias="FWLandingPattern.FactMetaData.json">src/MissionManager/FWLandingPattern.FactMetaData.json</file>
<file alias="USBBoardInfo.json">src/comm/USBBoardInfo.json</file>
<file alias="USBBoardInfo.json">src/comm/USBBoardInfo.json</file>
<file alias="CameraSection.FactMetaData.json">src/MissionManager/CameraSection.FactMetaData.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="MissionSettings.FactMetaData.json">src/MissionManager/MissionSettings.FactMetaData.json</file>
<file alias="Vehicle/VehicleFact.json">src/Vehicle/VehicleFact.json</file>
<file alias="Vehicle/VehicleFact.json">src/Vehicle/VehicleFact.json</file>
<file alias="Vehicle/BatteryFact.json">src/Vehicle/BatteryFact.json</file>
<file alias="Vehicle/BatteryFact.json">src/Vehicle/BatteryFact.json</file>
...
...
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
8f9befd8
...
@@ -241,3 +241,17 @@ bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle*
...
@@ -241,3 +241,17 @@ bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle*
}
}
return
false
;
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 @
8f9befd8
...
@@ -76,6 +76,7 @@ public:
...
@@ -76,6 +76,7 @@ public:
QString
takeControlFlightMode
(
void
)
const
override
{
return
QString
(
"Stablize"
);
}
QString
takeControlFlightMode
(
void
)
const
override
{
return
QString
(
"Stablize"
);
}
bool
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
final
;
bool
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
final
;
QString
autoDisarmParameter
(
Vehicle
*
vehicle
)
final
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"DISARM_DELAY"
);
}
QString
autoDisarmParameter
(
Vehicle
*
vehicle
)
final
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"DISARM_DELAY"
);
}
void
missionFlightSpeedInfo
(
Vehicle
*
vehicle
,
double
&
hoverSpeed
,
double
&
cruiseSpeed
)
override
;
private:
private:
static
bool
_remapParamNameIntialized
;
static
bool
_remapParamNameIntialized
;
...
...
src/FirmwarePlugin/FirmwarePlugin.cc
View file @
8f9befd8
...
@@ -11,6 +11,8 @@
...
@@ -11,6 +11,8 @@
#include "QGCApplication.h"
#include "QGCApplication.h"
#include "Generic/GenericAutoPilotPlugin.h"
#include "Generic/GenericAutoPilotPlugin.h"
#include "CameraMetaData.h"
#include "CameraMetaData.h"
#include "SettingsManager.h"
#include "AppSettings.h"
#include <QDebug>
#include <QDebug>
...
@@ -452,3 +454,13 @@ QString FirmwarePlugin::autoDisarmParameter(Vehicle* vehicle)
...
@@ -452,3 +454,13 @@ QString FirmwarePlugin::autoDisarmParameter(Vehicle* vehicle)
Q_UNUSED
(
vehicle
);
Q_UNUSED
(
vehicle
);
return
QString
();
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 @
8f9befd8
...
@@ -282,6 +282,11 @@ public:
...
@@ -282,6 +282,11 @@ public:
/// @param[out] cruiseAmps Current draw in amps during cruise
/// @param[out] cruiseAmps Current draw in amps during cruise
virtual
void
batteryConsumptionData
(
Vehicle
*
vehicle
,
int
&
mAhBattery
,
double
&
hoverAmps
,
double
&
cruiseAmps
)
const
;
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
// Returns the parameter which control auto-dismar. Assume == 0 means no auto disarm
virtual
QString
autoDisarmParameter
(
Vehicle
*
vehicle
);
virtual
QString
autoDisarmParameter
(
Vehicle
*
vehicle
);
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
8f9befd8
...
@@ -518,9 +518,27 @@ void PX4FirmwarePlugin::_handleAutopilotVersion(Vehicle* vehicle, mavlink_messag
...
@@ -518,9 +518,27 @@ void PX4FirmwarePlugin::_handleAutopilotVersion(Vehicle* vehicle, mavlink_messag
bool
PX4FirmwarePlugin
::
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
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"
));
Fact
*
yawMode
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"MIS_YAWMODE"
));
return
yawMode
&&
yawMode
->
rawValue
().
toInt
()
==
1
;
return
yawMode
&&
yawMode
->
rawValue
().
toInt
()
==
1
;
}
}
return
false
;
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 @
8f9befd8
...
@@ -68,6 +68,7 @@ public:
...
@@ -68,6 +68,7 @@ public:
QString
brandImageOutdoor
(
const
Vehicle
*
vehicle
)
const
override
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"/qmlimages/PX4/BrandImage"
);
}
QString
brandImageOutdoor
(
const
Vehicle
*
vehicle
)
const
override
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"/qmlimages/PX4/BrandImage"
);
}
bool
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
override
;
bool
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
override
;
QString
autoDisarmParameter
(
Vehicle
*
vehicle
)
override
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"COM_DISARM_LAND"
);
}
QString
autoDisarmParameter
(
Vehicle
*
vehicle
)
override
{
Q_UNUSED
(
vehicle
);
return
QStringLiteral
(
"COM_DISARM_LAND"
);
}
void
missionFlightSpeedInfo
(
Vehicle
*
vehicle
,
double
&
hoverSpeed
,
double
&
cruiseSpeed
)
override
;
protected:
protected:
typedef
struct
{
typedef
struct
{
...
...
src/MissionManager/CameraSection.cc
View file @
8f9befd8
...
@@ -20,8 +20,8 @@ const char* CameraSection::_cameraPhotoIntervalTimeName = "CameraPhotoInter
...
@@ -20,8 +20,8 @@ const char* CameraSection::_cameraPhotoIntervalTimeName = "CameraPhotoInter
QMap
<
QString
,
FactMetaData
*>
CameraSection
::
_metaDataMap
;
QMap
<
QString
,
FactMetaData
*>
CameraSection
::
_metaDataMap
;
CameraSection
::
CameraSection
(
QObject
*
parent
)
CameraSection
::
CameraSection
(
Vehicle
*
vehicle
,
QObject
*
parent
)
:
QObject
(
parent
)
:
Section
(
vehicle
,
parent
)
,
_available
(
false
)
,
_available
(
false
)
,
_settingsSpecified
(
false
)
,
_settingsSpecified
(
false
)
,
_specifyGimbal
(
false
)
,
_specifyGimbal
(
false
)
...
@@ -48,8 +48,8 @@ CameraSection::CameraSection(QObject* parent)
...
@@ -48,8 +48,8 @@ CameraSection::CameraSection(QObject* parent)
_cameraPhotoIntervalDistanceFact
.
setRawValue
(
_cameraPhotoIntervalDistanceFact
.
rawDefaultValue
());
_cameraPhotoIntervalDistanceFact
.
setRawValue
(
_cameraPhotoIntervalDistanceFact
.
rawDefaultValue
());
_cameraPhotoIntervalTimeFact
.
setRawValue
(
_cameraPhotoIntervalTimeFact
.
rawDefaultValue
());
_cameraPhotoIntervalTimeFact
.
setRawValue
(
_cameraPhotoIntervalTimeFact
.
rawDefaultValue
());
connect
(
this
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
CameraSection
::
_setDirtyAndUpdate
Mission
ItemCount
);
connect
(
this
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
CameraSection
::
_setDirtyAndUpdateItemCount
);
connect
(
&
_cameraActionFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirtyAndUpdate
Mission
ItemCount
);
connect
(
&
_cameraActionFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirtyAndUpdateItemCount
);
connect
(
&
_gimbalPitchFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirty
);
connect
(
&
_gimbalPitchFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirty
);
connect
(
&
_gimbalYawFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirty
);
connect
(
&
_gimbalYawFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirty
);
...
@@ -67,7 +67,7 @@ void CameraSection::setSpecifyGimbal(bool specifyGimbal)
...
@@ -67,7 +67,7 @@ void CameraSection::setSpecifyGimbal(bool specifyGimbal)
}
}
}
}
int
CameraSection
::
missionI
temCount
(
void
)
const
int
CameraSection
::
i
temCount
(
void
)
const
{
{
int
itemCount
=
0
;
int
itemCount
=
0
;
...
@@ -89,9 +89,9 @@ void CameraSection::setDirty(bool dirty)
...
@@ -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
)
{
if
(
_specifyGimbal
)
{
MissionItem
*
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MissionItem
*
item
=
new
MissionItem
(
nextSequenceNumber
++
,
...
@@ -188,7 +188,7 @@ void CameraSection::appendMissionItems(QList<MissionItem*>& items, QObject* miss
...
@@ -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
foundGimbal
=
false
;
bool
foundCameraAction
=
false
;
bool
foundCameraAction
=
false
;
...
@@ -196,6 +196,10 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
...
@@ -196,6 +196,10 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
qCDebug
(
CameraSectionLog
)
<<
"CameraSection::scanForCameraSection"
<<
visualItems
->
count
()
<<
scanIndex
;
qCDebug
(
CameraSectionLog
)
<<
"CameraSection::scanForCameraSection"
<<
visualItems
->
count
()
<<
scanIndex
;
if
(
!
_available
||
scanIndex
>=
visualItems
->
count
())
{
return
false
;
}
// Scan through the initial mission items for possible mission settings
// Scan through the initial mission items for possible mission settings
while
(
!
stopLooking
&&
visualItems
->
count
()
>
scanIndex
)
{
while
(
!
stopLooking
&&
visualItems
->
count
()
>
scanIndex
)
{
...
@@ -214,6 +218,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
...
@@ -214,6 +218,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
case
MAV_CMD_DO_MOUNT_CONTROL
:
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
)
{
if
(
!
foundGimbal
&&
missionItem
.
param2
()
==
0
&&
missionItem
.
param4
()
==
0
&&
missionItem
.
param5
()
==
0
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
MAV_MOUNT_MODE_MAVLINK_TARGETING
)
{
foundGimbal
=
true
;
foundGimbal
=
true
;
scanIndex
++
;
setSpecifyGimbal
(
true
);
setSpecifyGimbal
(
true
);
gimbalPitch
()
->
setRawValue
(
missionItem
.
param1
());
gimbalPitch
()
->
setRawValue
(
missionItem
.
param1
());
gimbalYaw
()
->
setRawValue
(
missionItem
.
param3
());
gimbalYaw
()
->
setRawValue
(
missionItem
.
param3
());
...
@@ -226,6 +231,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
...
@@ -226,6 +231,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
case
MAV_CMD_IMAGE_START_CAPTURE
:
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
)
{
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
;
foundCameraAction
=
true
;
scanIndex
++
;
cameraAction
()
->
setRawValue
(
TakePhotosIntervalTime
);
cameraAction
()
->
setRawValue
(
TakePhotosIntervalTime
);
cameraPhotoIntervalTime
()
->
setRawValue
(
missionItem
.
param1
());
cameraPhotoIntervalTime
()
->
setRawValue
(
missionItem
.
param1
());
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
...
@@ -245,6 +251,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
...
@@ -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
)
{
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
// We found a stop taking photos pair
foundCameraAction
=
true
;
foundCameraAction
=
true
;
scanIndex
+=
2
;
cameraAction
()
->
setRawValue
(
StopTakingPhotos
);
cameraAction
()
->
setRawValue
(
StopTakingPhotos
);
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
...
@@ -257,6 +264,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
...
@@ -257,6 +264,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
// We didn't find a stop taking photos pair, check for trigger distance
// We didn't find a stop taking photos pair, check for trigger distance
if
(
missionItem
.
param1
()
>
0
)
{
if
(
missionItem
.
param1
()
>
0
)
{
foundCameraAction
=
true
;
foundCameraAction
=
true
;
scanIndex
++
;
cameraAction
()
->
setRawValue
(
TakePhotoIntervalDistance
);
cameraAction
()
->
setRawValue
(
TakePhotoIntervalDistance
);
cameraPhotoIntervalDistance
()
->
setRawValue
(
missionItem
.
param1
());
cameraPhotoIntervalDistance
()
->
setRawValue
(
missionItem
.
param1
());
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
...
@@ -270,6 +278,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
...
@@ -270,6 +278,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
case
MAV_CMD_VIDEO_START_CAPTURE
:
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
)
{
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
;
foundCameraAction
=
true
;
scanIndex
++
;
cameraAction
()
->
setRawValue
(
TakeVideo
);
cameraAction
()
->
setRawValue
(
TakeVideo
);
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
}
}
...
@@ -279,6 +288,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
...
@@ -279,6 +288,7 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
case
MAV_CMD_VIDEO_STOP_CAPTURE
:
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
)
{
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
;
foundCameraAction
=
true
;
scanIndex
++
;
cameraAction
()
->
setRawValue
(
StopTakingVideo
);
cameraAction
()
->
setRawValue
(
StopTakingVideo
);
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
}
}
...
@@ -304,9 +314,9 @@ void CameraSection::_setDirty(void)
...
@@ -304,9 +314,9 @@ void CameraSection::_setDirty(void)
setDirty
(
true
);
setDirty
(
true
);
}
}
void
CameraSection
::
_setDirtyAndUpdate
Mission
ItemCount
(
void
)
void
CameraSection
::
_setDirtyAndUpdateItemCount
(
void
)
{
{
emit
missionItemCountChanged
(
missionI
temCount
());
emit
itemCountChanged
(
i
temCount
());
setDirty
(
true
);
setDirty
(
true
);
}
}
...
...
src/MissionManager/CameraSection.h
View file @
8f9befd8
...
@@ -7,21 +7,19 @@
...
@@ -7,21 +7,19 @@
*
*
****************************************************************************/
****************************************************************************/
#ifndef CameraSection_H
#pragma once
#define CameraSection_H
#include "Section.h"
#include "ComplexMissionItem.h"
#include "ComplexMissionItem.h"
#include "MissionItem.h"
#include "MissionItem.h"
#include "Fact.h"
#include "Fact.h"
Q_DECLARE_LOGGING_CATEGORY
(
CameraSectionLog
)
class
CameraSection
:
public
Section
class
CameraSection
:
public
QObject
{
{
Q_OBJECT
Q_OBJECT
public:
public:
CameraSection
(
QObject
*
parent
=
NULL
);
CameraSection
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
// These nume values must match the json meta data
// These nume values must match the json meta data
enum
CameraAction
{
enum
CameraAction
{
...
@@ -34,8 +32,6 @@ public:
...
@@ -34,8 +32,6 @@ public:
};
};
Q_ENUMS
(
CameraAction
)
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
(
bool
specifyGimbal
READ
specifyGimbal
WRITE
setSpecifyGimbal
NOTIFY
specifyGimbalChanged
)
Q_PROPERTY
(
Fact
*
gimbalPitch
READ
gimbalPitch
CONSTANT
)
Q_PROPERTY
(
Fact
*
gimbalPitch
READ
gimbalPitch
CONSTANT
)
Q_PROPERTY
(
Fact
*
gimbalYaw
READ
gimbalYaw
CONSTANT
)
Q_PROPERTY
(
Fact
*
gimbalYaw
READ
gimbalYaw
CONSTANT
)
...
@@ -43,8 +39,6 @@ public:
...
@@ -43,8 +39,6 @@ public:
Q_PROPERTY
(
Fact
*
cameraPhotoIntervalTime
READ
cameraPhotoIntervalTime
CONSTANT
)
Q_PROPERTY
(
Fact
*
cameraPhotoIntervalTime
READ
cameraPhotoIntervalTime
CONSTANT
)
Q_PROPERTY
(
Fact
*
cameraPhotoIntervalDistance
READ
cameraPhotoIntervalDistance
CONSTANT
)
Q_PROPERTY
(
Fact
*
cameraPhotoIntervalDistance
READ
cameraPhotoIntervalDistance
CONSTANT
)
bool
available
(
void
)
const
{
return
_available
;
}
void
setAvailable
(
bool
available
);
bool
specifyGimbal
(
void
)
const
{
return
_specifyGimbal
;
}
bool
specifyGimbal
(
void
)
const
{
return
_specifyGimbal
;
}
Fact
*
gimbalYaw
(
void
)
{
return
&
_gimbalYawFact
;
}
Fact
*
gimbalYaw
(
void
)
{
return
&
_gimbalYawFact
;
}
Fact
*
gimbalPitch
(
void
)
{
return
&
_gimbalPitchFact
;
}
Fact
*
gimbalPitch
(
void
)
{
return
&
_gimbalPitchFact
;
}
...
@@ -52,40 +46,28 @@ public:
...
@@ -52,40 +46,28 @@ public:
Fact
*
cameraPhotoIntervalTime
(
void
)
{
return
&
_cameraPhotoIntervalTimeFact
;
}
Fact
*
cameraPhotoIntervalTime
(
void
)
{
return
&
_cameraPhotoIntervalTimeFact
;
}
Fact
*
cameraPhotoIntervalDistance
(
void
)
{
return
&
_cameraPhotoIntervalDistanceFact
;
}
Fact
*
cameraPhotoIntervalDistance
(
void
)
{
return
&
_cameraPhotoIntervalDistanceFact
;
}
void
setSpecifyGimbal
(
bool
specifyGimbal
);
///< @return The gimbal yaw specified by this item, NaN if not specified
///< @return The gimbal yaw specified by this item, NaN if not specified
double
specifiedGimbalYaw
(
void
)
const
;
double
specifiedGimbalYaw
(
void
)
const
;
/// Scans the loaded items for the section items
// Overrides from Section
/// @param visualItems Item list
bool
available
(
void
)
const
override
{
return
_available
;
}
/// @param scanIndex Index to start scanning from
bool
dirty
(
void
)
const
override
{
return
_dirty
;
}
/// @return true: camera section found
void
setAvailable
(
bool
available
)
override
;
bool
scanForCameraSection
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
void
setDirty
(
bool
dirty
)
override
;
bool
scanForSection
(
QmlObjectListModel
*
visualItems
,
int
&
scanIndex
)
override
;
/// Appends the mission items associated with this section
void
appendSectionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
,
int
&
seqNum
)
override
;
/// @param items List to append to
int
itemCount
(
void
)
const
override
;
/// @param missionItemParent QObject parent for created MissionItems
bool
settingsSpecified
(
void
)
const
override
{
return
_settingsSpecified
;
}
/// @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
;
signals:
signals:
void
availableChanged
(
bool
available
);
void
settingsSpecifiedChanged
(
bool
settingsSpecified
);
void
dirtyChanged
(
bool
dirty
);
bool
specifyGimbalChanged
(
bool
specifyGimbal
);
bool
specifyGimbalChanged
(
bool
specifyGimbal
);
void
missionItemCountChanged
(
int
missionItemCount
);
void
specifiedGimbalYawChanged
(
double
gimbalYaw
);
void
specifiedGimbalYawChanged
(
double
gimbalYaw
);
private
slots
:
private
slots
:
void
_setDirty
(
void
);
void
_setDirty
(
void
);
void
_setDirtyAndUpdate
Mission
ItemCount
(
void
);
void
_setDirtyAndUpdateItemCount
(
void
);
void
_updateSpecifiedGimbalYaw
(
void
);
void
_updateSpecifiedGimbalYaw
(
void
);
private:
private:
...
@@ -107,5 +89,3 @@ private:
...
@@ -107,5 +89,3 @@ private:
static
const
char
*
_cameraPhotoIntervalDistanceName
;
static
const
char
*
_cameraPhotoIntervalDistanceName
;
static
const
char
*
_cameraPhotoIntervalTimeName
;
static
const
char
*
_cameraPhotoIntervalTimeName
;
};
};
#endif
src/MissionManager/MavCmdInfoCommon.json
View file @
8f9befd8
...
@@ -32,7 +32,6 @@
...
@@ -32,7 +32,6 @@
"specifiesCoordinate"
:
true
,
"specifiesCoordinate"
:
true
,
"friendlyEdit"
:
true
,
"friendlyEdit"
:
true
,
"category"
:
"Basic"
,
"category"
:
"Basic"
,
"cameraSection"
:
true
,
"param1"
:
{
"param1"
:
{
"label"
:
"Hold"
,
"label"
:
"Hold"
,
"units"
:
"secs"
,
"units"
:
"secs"
,
...
...
src/MissionManager/MissionCommandUIInfo.cc
View file @
8f9befd8
...
@@ -39,7 +39,6 @@ const char* MissionCommandUIInfo::_specifiesCoordinateJsonKey = "specifiesCoor
...
@@ -39,7 +39,6 @@ const char* MissionCommandUIInfo::_specifiesCoordinateJsonKey = "specifiesCoor
const
char
*
MissionCommandUIInfo
::
_specifiesAltitudeOnlyJsonKey
=
"specifiesAltitudeOnly"
;
const
char
*
MissionCommandUIInfo
::
_specifiesAltitudeOnlyJsonKey
=
"specifiesAltitudeOnly"
;
const
char
*
MissionCommandUIInfo
::
_unitsJsonKey
=
"units"
;
const
char
*
MissionCommandUIInfo
::
_unitsJsonKey
=
"units"
;
const
char
*
MissionCommandUIInfo
::
_commentJsonKey
=
"comment"
;
const
char
*
MissionCommandUIInfo
::
_commentJsonKey
=
"comment"
;
const
char
*
MissionCommandUIInfo
::
_cameraSectionJsonKey
=
"cameraSection"
;
const
char
*
MissionCommandUIInfo
::
_advancedCategory
=
"Advanced"
;
const
char
*
MissionCommandUIInfo
::
_advancedCategory
=
"Advanced"
;
MissionCmdParamInfo
::
MissionCmdParamInfo
(
QObject
*
parent
)
MissionCmdParamInfo
::
MissionCmdParamInfo
(
QObject
*
parent
)
...
@@ -165,15 +164,6 @@ bool MissionCommandUIInfo::specifiesAltitudeOnly(void) const
...
@@ -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
)
void
MissionCommandUIInfo
::
_overrideInfo
(
MissionCommandUIInfo
*
uiInfo
)
{
{
// Override info values
// Override info values
...
@@ -209,7 +199,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
...
@@ -209,7 +199,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
QStringList
allKeys
;
QStringList
allKeys
;
allKeys
<<
_idJsonKey
<<
_rawNameJsonKey
<<
_friendlyNameJsonKey
<<
_descriptionJsonKey
<<
_standaloneCoordinateJsonKey
<<
_specifiesCoordinateJsonKey
allKeys
<<
_idJsonKey
<<
_rawNameJsonKey
<<
_friendlyNameJsonKey
<<
_descriptionJsonKey
<<
_standaloneCoordinateJsonKey
<<
_specifiesCoordinateJsonKey
<<
_friendlyEditJsonKey
<<
_param1JsonKey
<<
_param2JsonKey
<<
_param3JsonKey
<<
_param4JsonKey
<<
_param5JsonKey
<<
_param6JsonKey
<<
_param7JsonKey
<<
_friendlyEditJsonKey
<<
_param1JsonKey
<<
_param2JsonKey
<<
_param3JsonKey
<<
_param4JsonKey
<<
_param5JsonKey
<<
_param6JsonKey
<<
_param7JsonKey
<<
_paramRemoveJsonKey
<<
_categoryJsonKey
<<
_
cameraSectionJsonKey
<<
_
specifiesAltitudeOnlyJsonKey
;
<<
_paramRemoveJsonKey
<<
_categoryJsonKey
<<
_specifiesAltitudeOnlyJsonKey
;
// Look for unknown keys in top level object
// Look for unknown keys in top level object
foreach
(
const
QString
&
key
,
jsonObject
.
keys
())
{
foreach
(
const
QString
&
key
,
jsonObject
.
keys
())
{
...
@@ -241,7 +231,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
...
@@ -241,7 +231,7 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
QList
<
QJsonValue
::
Type
>
types
;
QList
<
QJsonValue
::
Type
>
types
;
types
<<
QJsonValue
::
Double
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Bool
<<
QJsonValue
::
Bool
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
::
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
))
{
if
(
!
JsonHelper
::
validateKeyTypes
(
jsonObject
,
allKeys
,
types
,
internalError
))
{
errorString
=
_loadErrorString
(
internalError
);
errorString
=
_loadErrorString
(
internalError
);
return
false
;
return
false
;
...
@@ -275,9 +265,6 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
...
@@ -275,9 +265,6 @@ bool MissionCommandUIInfo::loadJsonInfo(const QJsonObject& jsonObject, bool requ
if
(
jsonObject
.
contains
(
_friendlyEditJsonKey
))
{
if
(
jsonObject
.
contains
(
_friendlyEditJsonKey
))
{
_infoMap
[
_friendlyEditJsonKey
]
=
jsonObject
.
value
(
_friendlyEditJsonKey
).
toVariant
();
_infoMap
[
_friendlyEditJsonKey
]
=
jsonObject
.
value
(
_friendlyEditJsonKey
).
toVariant
();
}
}
if
(
jsonObject
.
contains
(
_cameraSectionJsonKey
))
{
_infoMap
[
_cameraSectionJsonKey
]
=
jsonObject
.
value
(
_cameraSectionJsonKey
).
toVariant
();
}
if
(
jsonObject
.
contains
(
_paramRemoveJsonKey
))
{
if
(
jsonObject
.
contains
(
_paramRemoveJsonKey
))
{
QStringList
indexList
=
jsonObject
.
value
(
_paramRemoveJsonKey
).
toString
().
split
(
QStringLiteral
(
","
));
QStringList
indexList
=
jsonObject
.
value
(
_paramRemoveJsonKey
).
toString
().
split
(
QStringLiteral
(
","
));
foreach
(
const
QString
&
indexString
,
indexList
)
{
foreach
(
const
QString
&
indexString
,
indexList
)
{
...
...
src/MissionManager/MissionCommandUIInfo.h
View file @
8f9befd8
...
@@ -97,7 +97,6 @@ private:
...
@@ -97,7 +97,6 @@ private:
/// specifiesAltitudeOnly bool false true: Command specifies an altitude only (no coordinate)
/// 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)
/// 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
/// 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
/// 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
/// 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
/// param[1-7] object MissionCommandParamInfo object
...
@@ -120,7 +119,6 @@ public:
...
@@ -120,7 +119,6 @@ public:
Q_PROPERTY
(
bool
specifiesCoordinate
READ
specifiesCoordinate
CONSTANT
)
Q_PROPERTY
(
bool
specifiesCoordinate
READ
specifiesCoordinate
CONSTANT
)
Q_PROPERTY
(
bool
specifiesAltitudeOnly
READ
specifiesAltitudeOnly
CONSTANT
)
Q_PROPERTY
(
bool
specifiesAltitudeOnly
READ
specifiesAltitudeOnly
CONSTANT
)
Q_PROPERTY
(
int
command
READ
intCommand
CONSTANT
)
Q_PROPERTY
(
int
command
READ
intCommand
CONSTANT
)
Q_PROPERTY
(
bool
cameraSection
READ
cameraSection
CONSTANT
)
MAV_CMD
command
(
void
)
const
{
return
_command
;
}
MAV_CMD
command
(
void
)
const
{
return
_command
;
}
int
intCommand
(
void
)
const
{
return
(
int
)
_command
;
}
int
intCommand
(
void
)
const
{
return
(
int
)
_command
;
}
...
@@ -133,7 +131,6 @@ public:
...
@@ -133,7 +131,6 @@ public:
bool
isStandaloneCoordinate
(
void
)
const
;
bool
isStandaloneCoordinate
(
void
)
const
;
bool
specifiesCoordinate
(
void
)
const
;
bool
specifiesCoordinate
(
void
)
const
;
bool
specifiesAltitudeOnly
(
void
)
const
;
bool
specifiesAltitudeOnly
(
void
)
const
;
bool
cameraSection
(
void
)
const
;
/// Load the data in the object from the specified json
/// Load the data in the object from the specified json
/// @param jsonObject Json object to load from
/// @param jsonObject Json object to load from
...
@@ -192,7 +189,6 @@ private:
...
@@ -192,7 +189,6 @@ private:
static
const
char
*
_specifiesAltitudeOnlyJsonKey
;
static
const
char
*
_specifiesAltitudeOnlyJsonKey
;
static
const
char
*
_unitsJsonKey
;
static
const
char
*
_unitsJsonKey
;
static
const
char
*
_commentJsonKey
;
static
const
char
*
_commentJsonKey
;
static
const
char
*
_cameraSectionJsonKey
;
static
const
char
*
_advancedCategory
;
static
const
char
*
_advancedCategory
;
friend
class
MissionCommandTree
;
friend
class
MissionCommandTree
;
...
...
src/MissionManager/MissionController.cc
View file @
8f9befd8
...
@@ -1526,16 +1526,18 @@ void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualIte
...
@@ -1526,16 +1526,18 @@ void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualIte
qCDebug
(
MissionControllerLog
)
<<
"MissionController::_scanForAdditionalSettings count:scanIndex"
<<
visualItems
->
count
()
<<
scanIndex
;
qCDebug
(
MissionControllerLog
)
<<
"MissionController::_scanForAdditionalSettings count:scanIndex"
<<
visualItems
->
count
()
<<
scanIndex
;
MissionSettingsItem
*
settingsItem
=
qobject_cast
<
MissionSettingsItem
*>
(
visualItem
);
MissionSettingsItem
*
settingsItem
=
qobject_cast
<
MissionSettingsItem
*>
(
visualItem
);
if
(
settingsItem
&&
settingsItem
->
scanForMissionSettings
(
visualItems
,
scanIndex
,
vehicle
))
{
if
(
settingsItem
&&
settingsItem
->
scanForMissionSettings
(
visualItems
,
scanIndex
))
{
continue
;
continue
;
}
}
SimpleMissionItem
*
simpleItem
=
qobject_cast
<
SimpleMissionItem
*>
(
visualItem
);
SimpleMissionItem
*
simpleItem
=
qobject_cast
<
SimpleMissionItem
*>
(
visualItem
);
if
(
simpleItem
)
{
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 @
8f9befd8
...
@@ -7,14 +7,6 @@
...
@@ -7,14 +7,6 @@
"decimalPlaces"
:
1
,
"decimalPlaces"
:
1
,
"defaultValue"
:
0
"defaultValue"
:
0
},
},
{
"name"
:
"FlightSpeed"
,
"shortDescription"
:
"Flight speed for mission."
,
"type"
:
"double"
,
"units"
:
"m/s"
,
"min"
:
0
,
"decimalPlaces"
:
1
},
{
{
"name"
:
"MissionEndAction"
,
"name"
:
"MissionEndAction"
,
"shortDescription"
:
"The action to take when the mission completed."
,
"shortDescription"
:
"The action to take when the mission completed."
,
...
...
src/MissionManager/MissionSettingsItem.cc
View file @
8f9befd8
This diff is collapsed.
Click to expand it.
src/MissionManager/MissionSettingsItem.h
View file @
8f9befd8
...
@@ -15,6 +15,7 @@
...
@@ -15,6 +15,7 @@
#include "Fact.h"
#include "Fact.h"
#include "QGCLoggingCategory.h"
#include "QGCLoggingCategory.h"
#include "CameraSection.h"
#include "CameraSection.h"
#include "SpeedSection.h"
Q_DECLARE_LOGGING_CATEGORY
(
MissionSettingsComplexItemLog
)
Q_DECLARE_LOGGING_CATEGORY
(
MissionSettingsComplexItemLog
)
...
@@ -32,22 +33,19 @@ public:
...
@@ -32,22 +33,19 @@ public:
};
};
Q_ENUMS
(
MissionEndAction
)
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
*
missionEndAction
READ
missionEndAction
CONSTANT
)
Q_PROPERTY
(
Fact
*
plannedHomePositionAltitude
READ
plannedHomePositionAltitude
CONSTANT
)
Q_PROPERTY
(
Fact
*
plannedHomePositionAltitude
READ
plannedHomePositionAltitude
CONSTANT
)
Q_PROPERTY
(
QObject
*
cameraSection
READ
cameraSection
CONSTANT
)
Q_PROPERTY
(
QObject
*
cameraSection
READ
cameraSection
CONSTANT
)
Q_PROPERTY
(
QObject
*
speedSection
READ
speedSection
CONSTANT
)
Fact
*
plannedHomePositionAltitude
(
void
)
{
return
&
_plannedHomePositionAltitudeFact
;
}
Fact
*
plannedHomePositionAltitude
(
void
)
{
return
&
_plannedHomePositionAltitudeFact
;
}
Fact
*
missionFlightSpeed
(
void
)
{
return
&
_missionFlightSpeedFact
;
}
Fact
*
missionEndAction
(
void
)
{
return
&
_missionEndActionFact
;
}
Fact
*
missionEndAction
(
void
)
{
return
&
_missionEndActionFact
;
}
bool
specifyMissionFlightSpeed
(
void
)
const
{
return
_specifyMissionFlightSpeed
;
}
void
setSpecifyMissionFlightSpeed
(
bool
specifyMissionFlightSpeed
);
QObject
*
cameraSection
(
void
)
{
return
&
_cameraSection
;
}
QObject
*
cameraSection
(
void
)
{
return
&
_cameraSection
;
}
QObject
*
speedSection
(
void
)
{
return
&
_speedSection
;
}
/// Scans the loaded items for settings items
/// 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
/// Adds the optional mission end action to the list
/// @param items Mission items list to append to
/// @param items Mission items list to append to
...
@@ -77,10 +75,10 @@ public:
...
@@ -77,10 +75,10 @@ public:
QGeoCoordinate
coordinate
(
void
)
const
final
{
return
_plannedHomePositionCoordinate
;
}
QGeoCoordinate
coordinate
(
void
)
const
final
{
return
_plannedHomePositionCoordinate
;
}
QGeoCoordinate
exitCoordinate
(
void
)
const
final
{
return
_plannedHomePositionCoordinate
;
}
QGeoCoordinate
exitCoordinate
(
void
)
const
final
{
return
_plannedHomePositionCoordinate
;
}
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
double
specifiedFlightSpeed
(
void
)
final
;
double
specifiedGimbalYaw
(
void
)
final
;
double
specifiedGimbalYaw
(
void
)
final
;
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
{
Q_UNUSED
(
newAltitude
);
/* no action */
}
void
applyNewAltitude
(
double
newAltitude
)
final
{
Q_UNUSED
(
newAltitude
);
/* no action */
}
double
specifiedFlightSpeed
(
void
)
final
;
bool
coordinateHasRelativeAltitude
(
void
)
const
final
{
return
true
;
}
bool
coordinateHasRelativeAltitude
(
void
)
const
final
{
return
true
;
}
bool
exitCoordinateHasRelativeAltitude
(
void
)
const
final
{
return
true
;
}
bool
exitCoordinateHasRelativeAltitude
(
void
)
const
final
{
return
true
;
}
...
@@ -99,16 +97,15 @@ signals:
...
@@ -99,16 +97,15 @@ signals:
private
slots
:
private
slots
:
void
_setDirtyAndUpdateLastSequenceNumber
(
void
);
void
_setDirtyAndUpdateLastSequenceNumber
(
void
);
void
_setDirty
(
void
);
void
_setDirty
(
void
);
void
_
cameraSectionDirtyChanged
(
bool
dirty
);
void
_
sectionDirtyChanged
(
bool
dirty
);
void
_updateAltitudeInCoordinate
(
QVariant
value
);
void
_updateAltitudeInCoordinate
(
QVariant
value
);
private:
private:
bool
_specifyMissionFlightSpeed
;
QGeoCoordinate
_plannedHomePositionCoordinate
;
// Does not include altitde
QGeoCoordinate
_plannedHomePositionCoordinate
;
// Does not include altitde
Fact
_plannedHomePositionAltitudeFact
;
Fact
_plannedHomePositionAltitudeFact
;
Fact
_missionFlightSpeedFact
;
Fact
_missionEndActionFact
;
Fact
_missionEndActionFact
;
CameraSection
_cameraSection
;
CameraSection
_cameraSection
;
SpeedSection
_speedSection
;
int
_sequenceNumber
;
int
_sequenceNumber
;
bool
_dirty
;
bool
_dirty
;
...
@@ -116,7 +113,6 @@ private:
...
@@ -116,7 +113,6 @@ private:
static
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
static
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
static
const
char
*
_plannedHomePositionAltitudeName
;
static
const
char
*
_plannedHomePositionAltitudeName
;
static
const
char
*
_missionFlightSpeedName
;
static
const
char
*
_missionEndActionName
;
static
const
char
*
_missionEndActionName
;
};
};
...
...
src/MissionManager/Section.h
0 → 100644
View file @
8f9befd8
/****************************************************************************
*
* (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 @
8f9befd8
...
@@ -52,6 +52,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
...
@@ -52,6 +52,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
,
_rawEdit
(
false
)
,
_rawEdit
(
false
)
,
_dirty
(
false
)
,
_dirty
(
false
)
,
_ignoreDirtyChangeSignals
(
false
)
,
_ignoreDirtyChangeSignals
(
false
)
,
_speedSection
(
NULL
)
,
_cameraSection
(
NULL
)
,
_cameraSection
(
NULL
)
,
_commandTree
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
())
,
_commandTree
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
())
,
_altitudeRelativeToHomeFact
(
0
,
"Altitude is relative to home"
,
FactMetaData
::
valueTypeUint32
)
,
_altitudeRelativeToHomeFact
(
0
,
"Altitude is relative to home"
,
FactMetaData
::
valueTypeUint32
)
...
@@ -72,7 +73,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
...
@@ -72,7 +73,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
_setupMetaData
();
_setupMetaData
();
_connectSignals
();
_connectSignals
();
_update
CameraSection
();
_update
OptionalSections
();
setDefaultsForCommand
();
setDefaultsForCommand
();
_rebuildFacts
();
_rebuildFacts
();
...
@@ -90,6 +91,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
...
@@ -90,6 +91,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
,
_rawEdit
(
false
)
,
_rawEdit
(
false
)
,
_dirty
(
false
)
,
_dirty
(
false
)
,
_ignoreDirtyChangeSignals
(
false
)
,
_ignoreDirtyChangeSignals
(
false
)
,
_speedSection
(
NULL
)
,
_cameraSection
(
NULL
)
,
_cameraSection
(
NULL
)
,
_commandTree
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
())
,
_commandTree
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
())
,
_altitudeRelativeToHomeFact
(
0
,
"Altitude is relative to home"
,
FactMetaData
::
valueTypeUint32
)
,
_altitudeRelativeToHomeFact
(
0
,
"Altitude is relative to home"
,
FactMetaData
::
valueTypeUint32
)
...
@@ -110,7 +112,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
...
@@ -110,7 +112,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, const MissionItem& missio
_setupMetaData
();
_setupMetaData
();
_connectSignals
();
_connectSignals
();
_update
CameraSection
();
_update
OptionalSections
();
_syncFrameToAltitudeRelativeToHome
();
_syncFrameToAltitudeRelativeToHome
();
_rebuildFacts
();
_rebuildFacts
();
}
}
...
@@ -121,6 +123,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa
...
@@ -121,6 +123,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa
,
_rawEdit
(
false
)
,
_rawEdit
(
false
)
,
_dirty
(
false
)
,
_dirty
(
false
)
,
_ignoreDirtyChangeSignals
(
false
)
,
_ignoreDirtyChangeSignals
(
false
)
,
_speedSection
(
NULL
)
,
_cameraSection
(
NULL
)
,
_cameraSection
(
NULL
)
,
_commandTree
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
())
,
_commandTree
(
qgcApp
()
->
toolbox
()
->
missionCommandTree
())
,
_altitudeRelativeToHomeFact
(
0
,
"Altitude is relative to home"
,
FactMetaData
::
valueTypeUint32
)
,
_altitudeRelativeToHomeFact
(
0
,
"Altitude is relative to home"
,
FactMetaData
::
valueTypeUint32
)
...
@@ -136,7 +139,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa
...
@@ -136,7 +139,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa
_setupMetaData
();
_setupMetaData
();
_connectSignals
();
_connectSignals
();
_update
CameraSection
();
_update
OptionalSections
();
*
this
=
other
;
*
this
=
other
;
...
@@ -651,7 +654,7 @@ void SimpleMissionItem::setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command)
...
@@ -651,7 +654,7 @@ void SimpleMissionItem::setCommand(MavlinkQmlSingleton::Qml_MAV_CMD command)
{
{
if
((
MAV_CMD
)
command
!=
_missionItem
.
command
())
{
if
((
MAV_CMD
)
command
!=
_missionItem
.
command
())
{
_missionItem
.
setCommand
((
MAV_CMD
)
command
);
_missionItem
.
setCommand
((
MAV_CMD
)
command
);
_update
CameraSection
();
_update
OptionalSections
();
}
}
}
}
...
@@ -674,7 +677,11 @@ void SimpleMissionItem::setSequenceNumber(int sequenceNumber)
...
@@ -674,7 +677,11 @@ void SimpleMissionItem::setSequenceNumber(int sequenceNumber)
double
SimpleMissionItem
::
specifiedFlightSpeed
(
void
)
double
SimpleMissionItem
::
specifiedFlightSpeed
(
void
)
{
{
return
missionItem
().
specifiedFlightSpeed
();
if
(
_speedSection
->
specifyFlightSpeed
())
{
return
_speedSection
->
flightSpeed
()
->
rawValue
().
toDouble
();
}
else
{
return
missionItem
().
specifiedFlightSpeed
();
}
}
}
double
SimpleMissionItem
::
specifiedGimbalYaw
(
void
)
double
SimpleMissionItem
::
specifiedGimbalYaw
(
void
)
...
@@ -682,47 +689,59 @@ double SimpleMissionItem::specifiedGimbalYaw(void)
...
@@ -682,47 +689,59 @@ double SimpleMissionItem::specifiedGimbalYaw(void)
return
_cameraSection
->
available
()
?
_cameraSection
->
specifiedGimbalYaw
()
:
missionItem
().
specifiedGimbalYaw
();
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
;
bool
sectionFound
=
false
;
Q_UNUSED
(
vehicle
);
Q_UNUSED
(
vehicle
);
if
(
_cameraSection
->
available
())
{
if
(
_cameraSection
->
available
())
{
sectionFound
=
_cameraSection
->
scanForCameraSection
(
visualItems
,
scanIndex
);
sectionFound
|=
_cameraSection
->
scanForSection
(
visualItems
,
scanIndex
);
}
if
(
_speedSection
->
available
())
{
sectionFound
|=
_speedSection
->
scanForSection
(
visualItems
,
scanIndex
);
}
}
return
sectionFound
;
return
sectionFound
;
}
}
void
SimpleMissionItem
::
_update
CameraSection
(
void
)
void
SimpleMissionItem
::
_update
OptionalSections
(
void
)
{
{
// Remove previous sections
if
(
_cameraSection
)
{
if
(
_cameraSection
)
{
// Remove previous section
_cameraSection
->
deleteLater
();
_cameraSection
->
deleteLater
();
_cameraSection
=
NULL
;
_cameraSection
=
NULL
;
}
}
if
(
_speedSection
)
{
_speedSection
->
deleteLater
();
_speedSection
=
NULL
;
}
// Add new section
// Add new sections
_cameraSection
=
new
CameraSection
(
this
);
const
MissionCommandUIInfo
*
uiInfo
=
_commandTree
->
getUIInfo
(
_vehicle
,
(
MAV_CMD
)
command
());
_cameraSection
=
new
CameraSection
(
_vehicle
,
this
);
if
(
uiInfo
&&
uiInfo
->
cameraSection
())
{
_speedSection
=
new
SpeedSection
(
_vehicle
,
this
);
if
((
MAV_CMD
)
command
()
==
MAV_CMD_NAV_WAYPOINT
)
{
_cameraSection
->
setAvailable
(
true
);
_cameraSection
->
setAvailable
(
true
);
_speedSection
->
setAvailable
(
true
);
}
}
connect
(
_cameraSection
,
&
CameraSection
::
dirtyChanged
,
this
,
&
SimpleMissionItem
::
_cameraSectionDirtyChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
dirtyChanged
,
this
,
&
SimpleMissionItem
::
_sectionDirtyChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
availableChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
connect
(
_cameraSection
,
&
CameraSection
::
itemCountChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
connect
(
_cameraSection
,
&
CameraSection
::
missionItemCountChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
connect
(
_cameraSection
,
&
CameraSection
::
availableChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
availableChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
specifiedGimbalYawChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
specifiedGimbalYawChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_speedSection
,
&
CameraSection
::
dirtyChanged
,
this
,
&
SimpleMissionItem
::
_sectionDirtyChanged
);
connect
(
_speedSection
,
&
CameraSection
::
itemCountChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
emit
cameraSectionChanged
(
_cameraSection
);
emit
cameraSectionChanged
(
_cameraSection
);
emit
speedSectionChanged
(
_speedSection
);
}
}
int
SimpleMissionItem
::
lastSequenceNumber
(
void
)
const
int
SimpleMissionItem
::
lastSequenceNumber
(
void
)
const
{
{
return
sequenceNumber
()
+
(
_cameraSection
?
_cameraSection
->
missionI
temCount
()
:
0
);
return
sequenceNumber
()
+
(
_cameraSection
?
_cameraSection
->
itemCount
()
:
0
)
+
(
_speedSection
?
_speedSection
->
i
temCount
()
:
0
);
}
}
void
SimpleMissionItem
::
_updateLastSequenceNumber
(
void
)
void
SimpleMissionItem
::
_updateLastSequenceNumber
(
void
)
...
@@ -730,7 +749,7 @@ void SimpleMissionItem::_updateLastSequenceNumber(void)
...
@@ -730,7 +749,7 @@ void SimpleMissionItem::_updateLastSequenceNumber(void)
emit
lastSequenceNumberChanged
(
lastSequenceNumber
());
emit
lastSequenceNumberChanged
(
lastSequenceNumber
());
}
}
void
SimpleMissionItem
::
_
cameraS
ectionDirtyChanged
(
bool
dirty
)
void
SimpleMissionItem
::
_
s
ectionDirtyChanged
(
bool
dirty
)
{
{
if
(
dirty
)
{
if
(
dirty
)
{
setDirty
(
true
);
setDirty
(
true
);
...
@@ -744,7 +763,8 @@ void SimpleMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject*
...
@@ -744,7 +763,8 @@ void SimpleMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject*
items
.
append
(
new
MissionItem
(
missionItem
(),
missionItemParent
));
items
.
append
(
new
MissionItem
(
missionItem
(),
missionItemParent
));
seqNum
++
;
seqNum
++
;
_cameraSection
->
appendMissionItems
(
items
,
missionItemParent
,
seqNum
);
_cameraSection
->
appendSectionItems
(
items
,
missionItemParent
,
seqNum
);
_speedSection
->
appendSectionItems
(
items
,
missionItemParent
,
seqNum
);
}
}
void
SimpleMissionItem
::
applyNewAltitude
(
double
newAltitude
)
void
SimpleMissionItem
::
applyNewAltitude
(
double
newAltitude
)
...
...
src/MissionManager/SimpleMissionItem.h
View file @
8f9befd8
...
@@ -15,6 +15,7 @@
...
@@ -15,6 +15,7 @@
#include "MissionItem.h"
#include "MissionItem.h"
#include "MissionCommandTree.h"
#include "MissionCommandTree.h"
#include "CameraSection.h"
#include "CameraSection.h"
#include "SpeedSection.h"
/// A SimpleMissionItem is used to represent a single MissionItem to the ui.
/// A SimpleMissionItem is used to represent a single MissionItem to the ui.
class
SimpleMissionItem
:
public
VisualMissionItem
class
SimpleMissionItem
:
public
VisualMissionItem
...
@@ -31,12 +32,13 @@ public:
...
@@ -31,12 +32,13 @@ public:
const
SimpleMissionItem
&
operator
=
(
const
SimpleMissionItem
&
other
);
const
SimpleMissionItem
&
operator
=
(
const
SimpleMissionItem
&
other
);
Q_PROPERTY
(
QString
category
READ
category
NOTIFY
commandChanged
)
Q_PROPERTY
(
QString
category
READ
category
NOTIFY
commandChanged
)
Q_PROPERTY
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
READ
command
WRITE
setCommand
NOTIFY
commandChanged
)
Q_PROPERTY
(
bool
friendlyEditAllowed
READ
friendlyEditAllowed
NOTIFY
friendlyEditAllowedChanged
)
Q_PROPERTY
(
bool
friendlyEditAllowed
READ
friendlyEditAllowed
NOTIFY
friendlyEditAllowedChanged
)
Q_PROPERTY
(
bool
rawEdit
READ
rawEdit
WRITE
setRawEdit
NOTIFY
rawEditChanged
)
///< true: raw item editing with all params
Q_PROPERTY
(
bool
rawEdit
READ
rawEdit
WRITE
setRawEdit
NOTIFY
rawEditChanged
)
///< true: raw item editing with all params
Q_PROPERTY
(
bool
relativeAltitude
READ
relativeAltitude
NOTIFY
frameChanged
)
Q_PROPERTY
(
bool
relativeAltitude
READ
relativeAltitude
NOTIFY
frameChanged
)
Q_PROPERTY
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
READ
command
WRITE
setCommand
NOTIFY
commandChanged
)
/// Optional sections
/// Optional sections
Q_PROPERTY
(
QObject
*
speedSection
READ
speedSection
NOTIFY
speedSectionChanged
)
Q_PROPERTY
(
QObject
*
cameraSection
READ
cameraSection
NOTIFY
cameraSectionChanged
)
Q_PROPERTY
(
QObject
*
cameraSection
READ
cameraSection
NOTIFY
cameraSectionChanged
)
// These properties are used to display the editing ui
// These properties are used to display the editing ui
...
@@ -49,8 +51,8 @@ public:
...
@@ -49,8 +51,8 @@ public:
/// @param visualItems List of all visual items
/// @param visualItems List of all visual items
/// @param scanIndex Index to start scanning from
/// @param scanIndex Index to start scanning from
/// @param vehicle Vehicle associated with this mission
/// @param vehicle Vehicle associated with this mission
/// @return true: section found
/// @return true: section found
, scanIndex updated
bool
scanForSections
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
,
Vehicle
*
vehicle
);
bool
scanForSections
(
QmlObjectListModel
*
visualItems
,
int
&
scanIndex
,
Vehicle
*
vehicle
);
// Property accesors
// Property accesors
...
@@ -59,6 +61,7 @@ public:
...
@@ -59,6 +61,7 @@ public:
bool
friendlyEditAllowed
(
void
)
const
;
bool
friendlyEditAllowed
(
void
)
const
;
bool
rawEdit
(
void
)
const
;
bool
rawEdit
(
void
)
const
;
CameraSection
*
cameraSection
(
void
)
{
return
_cameraSection
;
}
CameraSection
*
cameraSection
(
void
)
{
return
_cameraSection
;
}
SpeedSection
*
speedSection
(
void
)
{
return
_speedSection
;
}
QmlObjectListModel
*
textFieldFacts
(
void
)
{
return
&
_textFieldFacts
;
}
QmlObjectListModel
*
textFieldFacts
(
void
)
{
return
&
_textFieldFacts
;
}
QmlObjectListModel
*
nanFacts
(
void
)
{
return
&
_nanFacts
;
}
QmlObjectListModel
*
nanFacts
(
void
)
{
return
&
_nanFacts
;
}
...
@@ -123,10 +126,11 @@ signals:
...
@@ -123,10 +126,11 @@ signals:
void
headingDegreesChanged
(
double
heading
);
void
headingDegreesChanged
(
double
heading
);
void
rawEditChanged
(
bool
rawEdit
);
void
rawEditChanged
(
bool
rawEdit
);
void
cameraSectionChanged
(
QObject
*
cameraSection
);
void
cameraSectionChanged
(
QObject
*
cameraSection
);
void
speedSectionChanged
(
QObject
*
cameraSection
);
private
slots
:
private
slots
:
void
_setDirtyFromSignal
(
void
);
void
_setDirtyFromSignal
(
void
);
void
_
cameraSectionDirtyChanged
(
bool
dirty
);
void
_
sectionDirtyChanged
(
bool
dirty
);
void
_sendCommandChanged
(
void
);
void
_sendCommandChanged
(
void
);
void
_sendCoordinateChanged
(
void
);
void
_sendCoordinateChanged
(
void
);
void
_sendFrameChanged
(
void
);
void
_sendFrameChanged
(
void
);
...
@@ -139,7 +143,7 @@ private slots:
...
@@ -139,7 +143,7 @@ private slots:
private:
private:
void
_connectSignals
(
void
);
void
_connectSignals
(
void
);
void
_setupMetaData
(
void
);
void
_setupMetaData
(
void
);
void
_update
CameraSection
(
void
);
void
_update
OptionalSections
(
void
);
void
_rebuildTextFieldFacts
(
void
);
void
_rebuildTextFieldFacts
(
void
);
void
_rebuildNaNFacts
(
void
);
void
_rebuildNaNFacts
(
void
);
void
_rebuildCheckboxFacts
(
void
);
void
_rebuildCheckboxFacts
(
void
);
...
@@ -150,6 +154,7 @@ private:
...
@@ -150,6 +154,7 @@ private:
bool
_dirty
;
bool
_dirty
;
bool
_ignoreDirtyChangeSignals
;
bool
_ignoreDirtyChangeSignals
;
SpeedSection
*
_speedSection
;
CameraSection
*
_cameraSection
;
CameraSection
*
_cameraSection
;
MissionCommandTree
*
_commandTree
;
MissionCommandTree
*
_commandTree
;
...
...
src/MissionManager/SpeedSection.FactMetaData.json
0 → 100644
View file @
8f9befd8
[
{
"name"
:
"FlightSpeed"
,
"shortDescription"
:
"Set the current flight speed"
,
"type"
:
"double"
,
"units"
:
"m/s"
,
"min"
:
0
,
"decimalPlaces"
:
1
,
"defaultValue"
:
0
}
]
src/MissionManager/SpeedSection.cc
0 → 100644
View file @
8f9befd8
/****************************************************************************
*
* (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.
*
****************************************************************************/
#include "SpeedSection.h"
#include "JsonHelper.h"
#include "FirmwarePlugin.h"
#include "SimpleMissionItem.h"
const
char
*
SpeedSection
::
_flightSpeedName
=
"FlightSpeed"
;
QMap
<
QString
,
FactMetaData
*>
SpeedSection
::
_metaDataMap
;
SpeedSection
::
SpeedSection
(
Vehicle
*
vehicle
,
QObject
*
parent
)
:
Section
(
vehicle
,
parent
)
,
_available
(
false
)
,
_dirty
(
false
)
,
_specifyFlightSpeed
(
false
)
,
_flightSpeedFact
(
0
,
_flightSpeedName
,
FactMetaData
::
valueTypeDouble
)
{
if
(
_metaDataMap
.
isEmpty
())
{
_metaDataMap
=
FactMetaData
::
createMapFromJsonFile
(
QStringLiteral
(
":/json/SpeedSection.FactMetaData.json"
),
NULL
/* metaDataParent */
);
}
double
hoverSpeed
,
cruiseSpeed
;
double
flightSpeed
=
0
;
_vehicle
->
firmwarePlugin
()
->
missionFlightSpeedInfo
(
_vehicle
,
hoverSpeed
,
cruiseSpeed
);
if
(
_vehicle
->
multiRotor
())
{
flightSpeed
=
hoverSpeed
;
}
else
if
(
_vehicle
->
fixedWing
())
{
flightSpeed
=
cruiseSpeed
;
}
_metaDataMap
[
_flightSpeedName
]
->
setRawDefaultValue
(
flightSpeed
);
_flightSpeedFact
.
setMetaData
(
_metaDataMap
[
_flightSpeedName
]);
_flightSpeedFact
.
setRawValue
(
flightSpeed
);
connect
(
this
,
&
SpeedSection
::
specifyFlightSpeedChanged
,
this
,
&
SpeedSection
::
_setDirtyAndUpdateItemCount
);
connect
(
this
,
&
SpeedSection
::
specifyFlightSpeedChanged
,
this
,
&
SpeedSection
::
settingsSpecifiedChanged
);
connect
(
&
_flightSpeedFact
,
&
Fact
::
valueChanged
,
this
,
&
SpeedSection
::
_setDirty
);
}
bool
SpeedSection
::
settingsSpecified
(
void
)
const
{
return
_specifyFlightSpeed
;
}
void
SpeedSection
::
setAvailable
(
bool
available
)
{
if
(
available
!=
_available
)
{
if
(
available
&&
(
_vehicle
->
multiRotor
()
||
_vehicle
->
fixedWing
()))
{
_available
=
available
;
emit
availableChanged
(
available
);
}
}
}
void
SpeedSection
::
_setDirty
(
void
)
{
setDirty
(
true
);
}
void
SpeedSection
::
_setDirtyAndUpdateItemCount
(
void
)
{
setDirty
(
true
);
emit
itemCountChanged
(
itemCount
());
}
void
SpeedSection
::
setDirty
(
bool
dirty
)
{
if
(
_dirty
!=
dirty
)
{
_dirty
=
dirty
;
emit
dirtyChanged
(
_dirty
);
}
}
void
SpeedSection
::
setSpecifyFlightSpeed
(
bool
specifyFlightSpeed
)
{
if
(
specifyFlightSpeed
!=
_specifyFlightSpeed
)
{
_specifyFlightSpeed
=
specifyFlightSpeed
;
emit
specifyFlightSpeedChanged
(
specifyFlightSpeed
);
}
}
int
SpeedSection
::
itemCount
(
void
)
const
{
return
_specifyFlightSpeed
?
1
:
0
;
}
void
SpeedSection
::
appendSectionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
,
int
&
seqNum
)
{
// IMPORTANT NOTE: If anything changes here you must also change SpeedSection::scanForSettings
if
(
_specifyFlightSpeed
)
{
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_DO_CHANGE_SPEED
,
MAV_FRAME_MISSION
,
_vehicle
->
multiRotor
()
?
1
/* groundspeed */
:
0
/* airspeed */
,
// Change airspeed or groundspeed
_flightSpeedFact
.
rawValue
().
toDouble
(),
-
1
,
// No throttle change
0
,
// Absolute speed change
0
,
0
,
0
,
// param 5-7 not used
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
items
.
append
(
item
);
}
}
bool
SpeedSection
::
scanForSection
(
QmlObjectListModel
*
visualItems
,
int
&
scanIndex
)
{
if
(
!
_available
||
scanIndex
>=
visualItems
->
count
())
{
return
false
;
}
SimpleMissionItem
*
item
=
visualItems
->
value
<
SimpleMissionItem
*>
(
scanIndex
);
if
(
!
item
)
{
// We hit a complex item, there can't be a speed setting
return
false
;
}
MissionItem
&
missionItem
=
item
->
missionItem
();
// See SpeedSection::appendMissionItems for specs on what consitutes a known speed setting
if
(
missionItem
.
command
()
==
MAV_CMD_DO_CHANGE_SPEED
&&
missionItem
.
param3
()
==
-
1
&&
missionItem
.
param4
()
==
0
&&
missionItem
.
param5
()
==
0
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
0
)
{
if
(
_vehicle
->
multiRotor
()
&&
missionItem
.
param1
()
!=
1
)
{
return
false
;
}
else
if
(
_vehicle
->
fixedWing
()
&&
missionItem
.
param1
()
!=
0
)
{
return
false
;
}
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
_flightSpeedFact
.
setRawValue
(
missionItem
.
param2
());
setSpecifyFlightSpeed
(
true
);
scanIndex
++
;
return
true
;
}
return
false
;
}
src/MissionManager/SpeedSection.h
0 → 100644
View file @
8f9befd8
/****************************************************************************
*
* (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 "Section.h"
#include "FactSystem.h"
#include "QmlObjectListModel.h"
class
SpeedSection
:
public
Section
{
Q_OBJECT
public:
SpeedSection
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
Q_PROPERTY
(
bool
specifyFlightSpeed
READ
specifyFlightSpeed
WRITE
setSpecifyFlightSpeed
NOTIFY
specifyFlightSpeedChanged
)
Q_PROPERTY
(
Fact
*
flightSpeed
READ
flightSpeed
CONSTANT
)
bool
specifyFlightSpeed
(
void
)
const
{
return
_specifyFlightSpeed
;
}
Fact
*
flightSpeed
(
void
)
{
return
&
_flightSpeedFact
;
}
void
setSpecifyFlightSpeed
(
bool
specifyFlightSpeed
);
// 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
;
signals:
void
specifyFlightSpeedChanged
(
bool
specifyFlightSpeed
);
private
slots
:
void
_setDirty
(
void
);
void
_setDirtyAndUpdateItemCount
(
void
);
private:
bool
_available
;
bool
_dirty
;
bool
_specifyFlightSpeed
;
Fact
_flightSpeedFact
;
static
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
static
const
char
*
_flightSpeedName
;
};
src/PlanView/MissionSettingsEditor.qml
View file @
8f9befd8
...
@@ -31,7 +31,8 @@ Rectangle {
...
@@ -31,7 +31,8 @@ Rectangle {
property
bool
_mobile
:
ScreenTools
.
isMobile
property
bool
_mobile
:
ScreenTools
.
isMobile
property
var
_savePath
:
QGroundControl
.
settingsManager
.
appSettings
.
missionSavePath
property
var
_savePath
:
QGroundControl
.
settingsManager
.
appSettings
.
missionSavePath
property
var
_fileExtension
:
QGroundControl
.
settingsManager
.
appSettings
.
missionFileExtension
property
var
_fileExtension
:
QGroundControl
.
settingsManager
.
appSettings
.
missionFileExtension
property
var
_appSettings
:
QGroundControl
.
settingsManager
.
appSettings
property
var
_appSettings
:
QGroundControl
.
settingsManager
.
appSettings
property
bool
_waypointsOnlyMode
:
QGroundControl
.
corePlugin
.
options
.
missionWaypointsOnly
readonly
property
string
_firmwareLabel
:
qsTr
(
"
Firmware
"
)
readonly
property
string
_firmwareLabel
:
qsTr
(
"
Firmware
"
)
readonly
property
string
_vehicleLabel
:
qsTr
(
"
Vehicle
"
)
readonly
property
string
_vehicleLabel
:
qsTr
(
"
Vehicle
"
)
...
@@ -112,12 +113,12 @@ Rectangle {
...
@@ -112,12 +113,12 @@ Rectangle {
id
:
flightSpeedCheckBox
id
:
flightSpeedCheckBox
text
:
qsTr
(
"
Flight speed
"
)
text
:
qsTr
(
"
Flight speed
"
)
visible
:
!
_missionVehicle
.
vtol
visible
:
!
_missionVehicle
.
vtol
checked
:
missionItem
.
spe
cifyMission
FlightSpeed
checked
:
missionItem
.
spe
edSection
.
specify
FlightSpeed
onClicked
:
missionItem
.
specifyMission
FlightSpeed
=
checked
onClicked
:
missionItem
.
speedSection
.
specify
FlightSpeed
=
checked
}
}
FactTextField
{
FactTextField
{
Layout.fillWidth
:
true
Layout.fillWidth
:
true
fact
:
missionItem
.
missionF
lightSpeed
fact
:
missionItem
.
speedSection
.
f
lightSpeed
visible
:
flightSpeedCheckBox
.
visible
visible
:
flightSpeedCheckBox
.
visible
enabled
:
flightSpeedCheckBox
.
checked
enabled
:
flightSpeedCheckBox
.
checked
}
}
...
@@ -138,7 +139,7 @@ Rectangle {
...
@@ -138,7 +139,7 @@ Rectangle {
SectionHeader
{
SectionHeader
{
id
:
vehicleInfoSectionHeader
id
:
vehicleInfoSectionHeader
text
:
qsTr
(
"
Vehicle Info
"
)
text
:
qsTr
(
"
Vehicle Info
"
)
visible
:
_offlineEditing
visible
:
_offlineEditing
&&
!
_waypointsOnlyMode
checked
:
false
checked
:
false
}
}
...
...
src/PlanView/SimpleItemEditor.qml
View file @
8f9befd8
...
@@ -138,6 +138,26 @@ Rectangle {
...
@@ -138,6 +138,26 @@ Rectangle {
}
}
}
}
RowLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
ScreenTools
.
defaultFontPixelWidth
visible
:
missionItem
.
speedSection
.
available
QGCCheckBox
{
id
:
flightSpeedCheckbox
text
:
qsTr
(
"
Flight Speed
"
)
checked
:
missionItem
.
speedSection
.
specifyFlightSpeed
onClicked
:
missionItem
.
speedSection
.
specifyFlightSpeed
=
checked
}
FactTextField
{
fact
:
missionItem
.
speedSection
.
flightSpeed
Layout.fillWidth
:
true
enabled
:
flightSpeedCheckbox
.
checked
}
}
Repeater
{
Repeater
{
model
:
missionItem
.
checkboxFacts
model
:
missionItem
.
checkboxFacts
...
...
src/QmlControls/MissionItemIndexLabel.qml
View file @
8f9befd8
...
@@ -78,7 +78,7 @@ Canvas {
...
@@ -78,7 +78,7 @@ Canvas {
color
:
"
white
"
color
:
"
white
"
opacity
:
0.5
opacity
:
0.5
radius
:
_labelRadius
radius
:
_labelRadius
visible
:
_label
.
length
!==
0
visible
:
_label
.
length
!==
0
&&
!
small
}
}
QGCLabel
{
QGCLabel
{
...
@@ -94,6 +94,7 @@ Canvas {
...
@@ -94,6 +94,7 @@ Canvas {
font.pointSize
:
ScreenTools
.
defaultFontPointSize
font.pointSize
:
ScreenTools
.
defaultFontPointSize
fontSizeMode
:
Text
.
HorizontalFit
fontSizeMode
:
Text
.
HorizontalFit
text
:
_label
text
:
_label
visible
:
labelControl
.
visible
}
}
Rectangle
{
Rectangle
{
...
...
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