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
2a4261eb
Unverified
Commit
2a4261eb
authored
Mar 12, 2018
by
Don Gagne
Committed by
GitHub
Mar 12, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6195 from DonLakeFlyer/StableMerge
Stable merge
parents
05992691
7737cee8
Changes
15
Show whitespace changes
Inline
Side-by-side
Showing
15 changed files
with
123 additions
and
138 deletions
+123
-138
QGCInstaller.pri
QGCInstaller.pri
+1
-1
ParameterManager.cc
src/FactSystem/ParameterManager.cc
+41
-27
ParameterManager.h
src/FactSystem/ParameterManager.h
+8
-1
FirmwarePlugin.h
src/FirmwarePlugin/FirmwarePlugin.h
+4
-5
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+1
-1
GuidedActionConfirm.qml
src/FlightDisplay/GuidedActionConfirm.qml
+18
-0
GuidedActionsController.qml
src/FlightDisplay/GuidedActionsController.qml
+6
-1
attitudeDial.svg
src/FlightMap/Images/attitudeDial.svg
+23
-15
StructureScanComplexItem.cc
src/MissionManager/StructureScanComplexItem.cc
+16
-32
StructureScanComplexItem.h
src/MissionManager/StructureScanComplexItem.h
+0
-9
StructureScanComplexItemTest.cc
src/MissionManager/StructureScanComplexItemTest.cc
+1
-16
StructureScanComplexItemTest.h
src/MissionManager/StructureScanComplexItemTest.h
+0
-1
SurveyMissionItem.h
src/MissionManager/SurveyMissionItem.h
+1
-1
MissionSettingsEditor.qml
src/PlanView/MissionSettingsEditor.qml
+3
-1
StructureScanEditor.qml
src/PlanView/StructureScanEditor.qml
+0
-27
No files found.
QGCInstaller.pri
View file @
2a4261eb
...
@@ -26,12 +26,12 @@ installer {
...
@@ -26,12 +26,12 @@ installer {
# We cd to release directory so we can run macdeployqt without a path to the
# We cd to release directory so we can run macdeployqt without a path to the
# qgroundcontrol.app file. If you specify a path to the .app file the symbolic
# qgroundcontrol.app file. If you specify a path to the .app file the symbolic
# links to plugins will not be created correctly.
# links to plugins will not be created correctly.
QMAKE_POST_LINK += && mkdir -p $${DESTDIR}/package
QMAKE_POST_LINK += && cd $${DESTDIR} && $$dirname(QMAKE_QMAKE)/macdeployqt $${TARGET}.app -appstore-compliant -verbose=2 -qmldir=$${BASEDIR}/src
QMAKE_POST_LINK += && cd $${DESTDIR} && $$dirname(QMAKE_QMAKE)/macdeployqt $${TARGET}.app -appstore-compliant -verbose=2 -qmldir=$${BASEDIR}/src
# macdeploy is missing some relocations once in a while. "Fix" it:
# macdeploy is missing some relocations once in a while. "Fix" it:
QMAKE_POST_LINK += && python $$BASEDIR/tools/osxrelocator.py $${TARGET}.app/Contents @rpath @executable_path/../Frameworks -r > /dev/null 2>&1
QMAKE_POST_LINK += && python $$BASEDIR/tools/osxrelocator.py $${TARGET}.app/Contents @rpath @executable_path/../Frameworks -r > /dev/null 2>&1
# Create package
# Create package
QMAKE_POST_LINK += && hdiutil create /tmp/tmp.dmg -ov -volname "$${TARGET}-$${MAC_VERSION}" -fs HFS+ -srcfolder "$${DESTDIR}/"
QMAKE_POST_LINK += && hdiutil create /tmp/tmp.dmg -ov -volname "$${TARGET}-$${MAC_VERSION}" -fs HFS+ -srcfolder "$${DESTDIR}/"
QMAKE_POST_LINK += && mkdir -p $${DESTDIR}/package
QMAKE_POST_LINK += && hdiutil convert /tmp/tmp.dmg -format UDBZ -o $${DESTDIR}/package/$${TARGET}.dmg
QMAKE_POST_LINK += && hdiutil convert /tmp/tmp.dmg -format UDBZ -o $${DESTDIR}/package/$${TARGET}.dmg
QMAKE_POST_LINK += && rm /tmp/tmp.dmg
QMAKE_POST_LINK += && rm /tmp/tmp.dmg
}
}
...
...
src/FactSystem/ParameterManager.cc
View file @
2a4261eb
...
@@ -22,12 +22,9 @@
...
@@ -22,12 +22,9 @@
#include <QVariantAnimation>
#include <QVariantAnimation>
#include <QJsonArray>
#include <QJsonArray>
/* types for local parameter cache */
typedef
QPair
<
int
/* FactMetaData::ValueType_t */
,
QVariant
/* Fact::rawValue */
>
ParamTypeVal
;
typedef
QMap
<
QString
/* parameter name */
,
ParamTypeVal
>
CacheMapName2ParamTypeVal
;
QGC_LOGGING_CATEGORY
(
ParameterManagerVerbose1Log
,
"ParameterManagerVerbose1Log"
)
QGC_LOGGING_CATEGORY
(
ParameterManagerVerbose1Log
,
"ParameterManagerVerbose1Log"
)
QGC_LOGGING_CATEGORY
(
ParameterManagerVerbose2Log
,
"ParameterManagerVerbose2Log"
)
QGC_LOGGING_CATEGORY
(
ParameterManagerVerbose2Log
,
"ParameterManagerVerbose2Log"
)
QGC_LOGGING_CATEGORY
(
ParameterManagerDebugCacheFailureLog
,
"ParameterManagerDebugCacheFailureLog"
)
// Turn on to debug parameter cache crc misses
Fact
ParameterManager
::
_defaultFact
;
Fact
ParameterManager
::
_defaultFact
;
...
@@ -151,6 +148,24 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
...
@@ -151,6 +148,24 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
return
;
return
;
}
}
// Used to debug cache crc misses (turn on ParameterManagerDebugCacheFailureLog)
if
(
!
_initialLoadComplete
&&
!
_logReplay
&&
_debugCacheCRC
.
contains
(
componentId
)
&&
_debugCacheCRC
[
componentId
])
{
if
(
_debugCacheMap
[
componentId
].
contains
(
parameterName
))
{
const
ParamTypeVal
&
cacheParamTypeVal
=
_debugCacheMap
[
componentId
][
parameterName
];
size_t
dataSize
=
FactMetaData
::
typeToSize
(
static_cast
<
FactMetaData
::
ValueType_t
>
(
cacheParamTypeVal
.
first
));
const
void
*
cacheData
=
cacheParamTypeVal
.
second
.
constData
();
const
void
*
vehicleData
=
value
.
constData
();
if
(
memcmp
(
cacheData
,
vehicleData
,
dataSize
))
{
qDebug
()
<<
"Cache/Vehicle values differ for name:cache:actual"
<<
parameterName
<<
value
<<
cacheParamTypeVal
.
second
;
}
_debugCacheParamSeen
[
componentId
][
parameterName
]
=
true
;
}
else
{
qDebug
()
<<
"Parameter missing from cache"
<<
parameterName
;
}
}
_initialRequestTimeoutTimer
.
stop
();
_initialRequestTimeoutTimer
.
stop
();
_waitingParamTimeoutTimer
.
stop
();
_waitingParamTimeoutTimer
.
stop
();
...
@@ -340,11 +355,6 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
...
@@ -340,11 +355,6 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
_setupCategoryMap
();
_setupCategoryMap
();
}
}
if
(
_prevWaitingWriteParamNameCount
!=
0
&&
waitingWriteParamNameCount
==
0
)
{
// If all the writes just finished the vehicle is up to date, so persist.
_saveToEEPROM
();
}
// Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params
// Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params
// which invalidate the cache. The Solo also streams param updates in flight for things like gimbal values
// which invalidate the cache. The Solo also streams param updates in flight for things like gimbal values
// which in turn causes a perf problem with all the param cache updates.
// which in turn causes a perf problem with all the param cache updates.
...
@@ -875,22 +885,13 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian
...
@@ -875,22 +885,13 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian
_parameterSetMajorVersion
=
-
1
;
_parameterSetMajorVersion
=
-
1
;
_clearMetaData
();
_clearMetaData
();
qCInfo
(
ParameterManagerLog
)
<<
"Parameters cache match failed"
<<
qPrintable
(
QFileInfo
(
cacheFile
).
absoluteFilePath
());
qCInfo
(
ParameterManagerLog
)
<<
"Parameters cache match failed"
<<
qPrintable
(
QFileInfo
(
cacheFile
).
absoluteFilePath
());
if
(
ParameterManagerDebugCacheFailureLog
().
isDebugEnabled
())
{
_debugCacheCRC
[
componentId
]
=
true
;
_debugCacheMap
[
componentId
]
=
cacheMap
;
foreach
(
const
QString
&
name
,
cacheMap
.
keys
())
{
_debugCacheParamSeen
[
componentId
][
name
]
=
false
;
}
}
}
qgcApp
()
->
showMessage
(
tr
(
"Parameter cache CRC match failed"
));
void
ParameterManager
::
_saveToEEPROM
(
void
)
{
if
(
_saveRequired
)
{
_saveRequired
=
false
;
if
(
_vehicle
->
firmwarePlugin
()
->
isCapable
(
_vehicle
,
FirmwarePlugin
::
MavCmdPreflightStorageCapability
))
{
_vehicle
->
sendMavCommand
(
MAV_COMP_ID_ALL
,
MAV_CMD_PREFLIGHT_STORAGE
,
true
,
// showError
1
,
// Write parameters to EEPROM
-
1
);
// Don't do anything with mission storage
qCDebug
(
ParameterManagerLog
)
<<
_logVehiclePrefix
()
<<
"_saveToEEPROM"
;
}
else
{
qCDebug
(
ParameterManagerLog
)
<<
_logVehiclePrefix
()
<<
"_saveToEEPROM skipped due to FirmwarePlugin::isCapable"
;
}
}
}
}
}
}
...
@@ -1110,6 +1111,18 @@ void ParameterManager::_checkInitialLoadComplete(void)
...
@@ -1110,6 +1111,18 @@ void ParameterManager::_checkInitialLoadComplete(void)
// We aren't waiting for any more initial parameter updates, initial parameter loading is complete
// We aren't waiting for any more initial parameter updates, initial parameter loading is complete
_initialLoadComplete
=
true
;
_initialLoadComplete
=
true
;
// Parameter cache crc failure debugging
foreach
(
int
componentId
,
_debugCacheParamSeen
.
keys
())
{
if
(
!
_logReplay
&&
_debugCacheCRC
.
contains
(
componentId
)
&&
_debugCacheCRC
[
componentId
])
{
foreach
(
const
QString
&
paramName
,
_debugCacheParamSeen
[
componentId
].
keys
())
{
if
(
!
_debugCacheParamSeen
[
componentId
][
paramName
])
{
qDebug
()
<<
"Parameter in cache but not on vehicle componentId:Name"
<<
componentId
<<
paramName
;
}
}
}
}
_debugCacheCRC
.
clear
();
qCDebug
(
ParameterManagerLog
)
<<
_logVehiclePrefix
()
<<
"Initial load complete"
;
qCDebug
(
ParameterManagerLog
)
<<
_logVehiclePrefix
()
<<
"Initial load complete"
;
// Check for index based load failures
// Check for index based load failures
...
@@ -1423,6 +1436,7 @@ void ParameterManager::_loadOfflineEditingParams(void)
...
@@ -1423,6 +1436,7 @@ void ParameterManager::_loadOfflineEditingParams(void)
_setupCategoryMap
();
_setupCategoryMap
();
_parametersReady
=
true
;
_parametersReady
=
true
;
_initialLoadComplete
=
true
;
_initialLoadComplete
=
true
;
_debugCacheCRC
.
clear
();
}
}
void
ParameterManager
::
saveToJson
(
int
componentId
,
const
QStringList
&
paramsToSave
,
QJsonObject
&
saveObject
)
void
ParameterManager
::
saveToJson
(
int
componentId
,
const
QStringList
&
paramsToSave
,
QJsonObject
&
saveObject
)
...
...
src/FactSystem/ParameterManager.h
View file @
2a4261eb
...
@@ -30,6 +30,7 @@
...
@@ -30,6 +30,7 @@
Q_DECLARE_LOGGING_CATEGORY
(
ParameterManagerVerbose1Log
)
Q_DECLARE_LOGGING_CATEGORY
(
ParameterManagerVerbose1Log
)
Q_DECLARE_LOGGING_CATEGORY
(
ParameterManagerVerbose2Log
)
Q_DECLARE_LOGGING_CATEGORY
(
ParameterManagerVerbose2Log
)
Q_DECLARE_LOGGING_CATEGORY
(
ParameterManagerDebugCacheFailureLog
)
/// Connects to Parameter Manager to load/update Facts
/// Connects to Parameter Manager to load/update Facts
class
ParameterManager
:
public
QObject
class
ParameterManager
:
public
QObject
...
@@ -153,7 +154,6 @@ private:
...
@@ -153,7 +154,6 @@ private:
MAV_PARAM_TYPE
_factTypeToMavType
(
FactMetaData
::
ValueType_t
factType
);
MAV_PARAM_TYPE
_factTypeToMavType
(
FactMetaData
::
ValueType_t
factType
);
FactMetaData
::
ValueType_t
_mavTypeToFactType
(
MAV_PARAM_TYPE
mavType
);
FactMetaData
::
ValueType_t
_mavTypeToFactType
(
MAV_PARAM_TYPE
mavType
);
void
_saveToEEPROM
(
void
);
void
_checkInitialLoadComplete
(
void
);
void
_checkInitialLoadComplete
(
void
);
/// First mapping is by component id
/// First mapping is by component id
...
@@ -175,6 +175,13 @@ private:
...
@@ -175,6 +175,13 @@ private:
int
_parameterSetMajorVersion
;
///< Version for parameter set, -1 if not known
int
_parameterSetMajorVersion
;
///< Version for parameter set, -1 if not known
QObject
*
_parameterMetaData
;
///< Opaque data from FirmwarePlugin::loadParameterMetaDataCall
QObject
*
_parameterMetaData
;
///< Opaque data from FirmwarePlugin::loadParameterMetaDataCall
typedef
QPair
<
int
/* FactMetaData::ValueType_t */
,
QVariant
/* Fact::rawValue */
>
ParamTypeVal
;
typedef
QMap
<
QString
/* parameter name */
,
ParamTypeVal
>
CacheMapName2ParamTypeVal
;
QMap
<
int
/* component id */
,
bool
>
_debugCacheCRC
;
///< true: debug cache crc failure
QMap
<
int
/* component id */
,
CacheMapName2ParamTypeVal
>
_debugCacheMap
;
QMap
<
int
/* component id */
,
QMap
<
QString
/* param name */
,
bool
/* seen */
>>
_debugCacheParamSeen
;
// Wait counts from previous parameter update cycle
// Wait counts from previous parameter update cycle
int
_prevWaitingReadParamIndexCount
;
int
_prevWaitingReadParamIndexCount
;
int
_prevWaitingReadParamNameCount
;
int
_prevWaitingReadParamNameCount
;
...
...
src/FirmwarePlugin/FirmwarePlugin.h
View file @
2a4261eb
...
@@ -43,11 +43,10 @@ public:
...
@@ -43,11 +43,10 @@ public:
/// Set of optional capabilites which firmware may support
/// Set of optional capabilites which firmware may support
typedef
enum
{
typedef
enum
{
SetFlightModeCapability
=
1
<<
0
,
///< FirmwarePlugin::setFlightMode method is supported
SetFlightModeCapability
=
1
<<
0
,
///< FirmwarePlugin::setFlightMode method is supported
MavCmdPreflightStorageCapability
=
1
<<
1
,
///< MAV_CMD_PREFLIGHT_STORAGE is supported
PauseVehicleCapability
=
1
<<
1
,
///< Vehicle supports pausing at current location
PauseVehicleCapability
=
1
<<
2
,
///< Vehicle supports pausing at current location
GuidedModeCapability
=
1
<<
2
,
///< Vehicle supports guided mode commands
GuidedModeCapability
=
1
<<
3
,
///< Vehicle supports guided mode commands
OrbitModeCapability
=
1
<<
3
,
///< Vehicle supports orbit mode
OrbitModeCapability
=
1
<<
4
,
///< Vehicle supports orbit mode
TakeoffVehicleCapability
=
1
<<
4
,
///< Vehicle supports guided takeoff
TakeoffVehicleCapability
=
1
<<
5
,
///< Vehicle supports guided takeoff
}
FirmwareCapabilities
;
}
FirmwareCapabilities
;
/// Maps from on parameter name to another
/// Maps from on parameter name to another
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
2a4261eb
...
@@ -227,7 +227,7 @@ int PX4FirmwarePlugin::manualControlReservedButtonCount(void)
...
@@ -227,7 +227,7 @@ int PX4FirmwarePlugin::manualControlReservedButtonCount(void)
bool
PX4FirmwarePlugin
::
isCapable
(
const
Vehicle
*
vehicle
,
FirmwareCapabilities
capabilities
)
bool
PX4FirmwarePlugin
::
isCapable
(
const
Vehicle
*
vehicle
,
FirmwareCapabilities
capabilities
)
{
{
int
available
=
MavCmdPreflightStorageCapability
|
SetFlightModeCapability
|
PauseVehicleCapability
|
GuidedModeCapability
;
int
available
=
SetFlightModeCapability
|
PauseVehicleCapability
|
GuidedModeCapability
;
if
(
vehicle
->
multiRotor
()
||
vehicle
->
vtol
())
{
if
(
vehicle
->
multiRotor
()
||
vehicle
->
vtol
())
{
available
|=
TakeoffVehicleCapability
;
available
|=
TakeoffVehicleCapability
;
}
}
...
...
src/FlightDisplay/GuidedActionConfirm.qml
View file @
2a4261eb
...
@@ -42,10 +42,28 @@ Rectangle {
...
@@ -42,10 +42,28 @@ Rectangle {
if
(
hideTrigger
)
{
if
(
hideTrigger
)
{
hideTrigger
=
false
hideTrigger
=
false
altitudeSlider
.
visible
=
false
altitudeSlider
.
visible
=
false
visibleTimer
.
stop
()
visible
=
false
visible
=
false
}
}
}
}
function
show
(
immediate
)
{
if
(
immediate
)
{
visible
=
true
}
else
{
// We delay showing the confirmation for a small amount in order to any other state
// changes to propogate through the system. This way only the final state shows up.
visibleTimer
.
restart
()
}
}
Timer
{
id
:
visibleTimer
interval
:
1000
repeat
:
false
onTriggered
:
visible
=
true
}
QGCPalette
{
id
:
qgcPal
}
QGCPalette
{
id
:
qgcPal
}
DeadMouseArea
{
DeadMouseArea
{
...
...
src/FlightDisplay/GuidedActionsController.qml
View file @
2a4261eb
...
@@ -185,9 +185,11 @@ Item {
...
@@ -185,9 +185,11 @@ Item {
// Called when an action is about to be executed in order to confirm
// Called when an action is about to be executed in order to confirm
function
confirmAction
(
actionCode
,
actionData
)
{
function
confirmAction
(
actionCode
,
actionData
)
{
var
showImmediate
=
true
closeAll
()
closeAll
()
confirmDialog
.
action
=
actionCode
confirmDialog
.
action
=
actionCode
confirmDialog
.
actionData
=
actionData
confirmDialog
.
actionData
=
actionData
confirmDialog
.
hideTrigger
=
true
_actionData
=
actionData
_actionData
=
actionData
switch
(
actionCode
)
{
switch
(
actionCode
)
{
case
actionArm
:
case
actionArm
:
...
@@ -219,6 +221,7 @@ Item {
...
@@ -219,6 +221,7 @@ Item {
altitudeSlider
.
visible
=
true
altitudeSlider
.
visible
=
true
break
;
break
;
case
actionStartMission
:
case
actionStartMission
:
showImmediate
=
false
confirmDialog
.
title
=
startMissionTitle
confirmDialog
.
title
=
startMissionTitle
confirmDialog
.
message
=
startMissionMessage
confirmDialog
.
message
=
startMissionMessage
confirmDialog
.
hideTrigger
=
Qt
.
binding
(
function
()
{
return
!
showStartMission
})
confirmDialog
.
hideTrigger
=
Qt
.
binding
(
function
()
{
return
!
showStartMission
})
...
@@ -229,11 +232,13 @@ Item {
...
@@ -229,11 +232,13 @@ Item {
confirmDialog
.
hideTrigger
=
true
confirmDialog
.
hideTrigger
=
true
break
;
break
;
case
actionContinueMission
:
case
actionContinueMission
:
showImmediate
=
false
confirmDialog
.
title
=
continueMissionTitle
confirmDialog
.
title
=
continueMissionTitle
confirmDialog
.
message
=
continueMissionMessage
confirmDialog
.
message
=
continueMissionMessage
confirmDialog
.
hideTrigger
=
Qt
.
binding
(
function
()
{
return
!
showContinueMission
})
confirmDialog
.
hideTrigger
=
Qt
.
binding
(
function
()
{
return
!
showContinueMission
})
break
;
break
;
case
actionResumeMission
:
case
actionResumeMission
:
showImmediate
=
false
confirmDialog
.
title
=
resumeMissionTitle
confirmDialog
.
title
=
resumeMissionTitle
confirmDialog
.
message
=
resumeMissionMessage
confirmDialog
.
message
=
resumeMissionMessage
confirmDialog
.
hideTrigger
=
Qt
.
binding
(
function
()
{
return
!
showResumeMission
})
confirmDialog
.
hideTrigger
=
Qt
.
binding
(
function
()
{
return
!
showResumeMission
})
...
@@ -308,7 +313,7 @@ Item {
...
@@ -308,7 +313,7 @@ Item {
console
.
warn
(
"
Unknown actionCode
"
,
actionCode
)
console
.
warn
(
"
Unknown actionCode
"
,
actionCode
)
return
return
}
}
confirmDialog
.
visible
=
true
confirmDialog
.
show
(
showImmediate
)
}
}
// Executes the specified action
// Executes the specified action
...
...
src/FlightMap/Images/attitudeDial.svg
100644 → 100755
View file @
2a4261eb
<?xml version="1.0" encoding="utf-8"?>
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 18.1.1, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<!-- Generator: Adobe Illustrator 21.0.0, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg
version=
"1.1"
id=
"Layer_2"
xmlns=
"http://www.w3.org/2000/svg"
xmlns:xlink=
"http://www.w3.org/1999/xlink"
x=
"0px"
y=
"0px"
<svg
version=
"1.1"
xmlns=
"http://www.w3.org/2000/svg"
xmlns:xlink=
"http://www.w3.org/1999/xlink"
x=
"0px"
y=
"0px"
viewBox=
"0 0 288 288"
enable-background=
"new 0 0 288 288"
xml:space=
"preserve"
>
viewBox=
"0 0 288 288"
style=
"enable-background:new 0 0 288 288;"
xml:space=
"preserve"
>
<line
fill=
"none"
stroke=
"#FFFFFF"
stroke-width=
"4"
x1=
"143.999"
y1=
"36.793"
x2=
"143.999"
y2=
"18.793"
/>
<style
type=
"text/css"
>
<line
fill=
"none"
stroke=
"#FFFFFF"
stroke-width=
"4"
x1=
"171.739"
y1=
"40.458"
x2=
"176.398"
y2=
"23.072"
/>
.st0{fill:none;stroke:#FFFFFF;stroke-width:4;}
<line
fill=
"none"
stroke=
"#FFFFFF"
stroke-width=
"4"
x1=
"197.586"
y1=
"51.179"
x2=
"206.586"
y2=
"35.591"
/>
.st1{fill:none;stroke:#FFFFFF;stroke-miterlimit:10;}
<line
fill=
"none"
stroke=
"#FFFFFF"
stroke-width=
"4"
x1=
"219.777"
y1=
"68.224"
x2=
"232.505"
y2=
"55.496"
/>
</style>
<line
fill=
"none"
stroke=
"#FFFFFF"
stroke-width=
"4"
x1=
"236.801"
y1=
"90.432"
x2=
"252.389"
y2=
"81.432"
/>
<g
id=
"Layer_2"
>
<line
fill=
"none"
stroke=
"#FFFFFF"
stroke-width=
"4"
x1=
"116.254"
y1=
"40.431"
x2=
"111.596"
y2=
"23.045"
/>
<line
class=
"st0"
x1=
"144"
y1=
"45.8"
x2=
"144"
y2=
"18.8"
/>
<line
fill=
"none"
stroke=
"#FFFFFF"
stroke-width=
"4"
x1=
"90.397"
y1=
"51.127"
x2=
"81.397"
y2=
"35.539"
/>
<line
class=
"st0"
x1=
"171.7"
y1=
"40.5"
x2=
"176.4"
y2=
"23.1"
/>
<line
fill=
"none"
stroke=
"#FFFFFF"
stroke-width=
"4"
x1=
"68.189"
y1=
"68.151"
x2=
"55.461"
y2=
"55.423"
/>
<line
class=
"st0"
x1=
"197.6"
y1=
"51.2"
x2=
"206.6"
y2=
"35.6"
/>
<line
fill=
"none"
stroke=
"#FFFFFF"
stroke-width=
"4"
x1=
"51.144"
y1=
"90.342"
x2=
"35.556"
y2=
"81.342"
/>
<line
class=
"st0"
x1=
"219.8"
y1=
"68.2"
x2=
"232.5"
y2=
"55.5"
/>
<rect
x=
"135"
y=
"270"
fill=
"none"
width=
"18"
height=
"18"
/>
<line
class=
"st0"
x1=
"236.8"
y1=
"90.4"
x2=
"252.4"
y2=
"81.4"
/>
<line
class=
"st0"
x1=
"116.3"
y1=
"40.4"
x2=
"111.6"
y2=
"23"
/>
<line
class=
"st0"
x1=
"90.4"
y1=
"51.1"
x2=
"81.4"
y2=
"35.5"
/>
<line
class=
"st0"
x1=
"68.2"
y1=
"68.2"
x2=
"55.5"
y2=
"55.4"
/>
<line
class=
"st0"
x1=
"51.1"
y1=
"90.3"
x2=
"35.6"
y2=
"81.3"
/>
<rect
x=
"135"
y=
"270"
class=
"st1"
width=
"18"
height=
"18"
/>
</g>
<g
id=
"Layer_3"
>
</g>
</svg>
</svg>
src/MissionManager/StructureScanComplexItem.cc
View file @
2a4261eb
...
@@ -24,8 +24,6 @@ QGC_LOGGING_CATEGORY(StructureScanComplexItemLog, "StructureScanComplexItemLog")
...
@@ -24,8 +24,6 @@ QGC_LOGGING_CATEGORY(StructureScanComplexItemLog, "StructureScanComplexItemLog")
const
char
*
StructureScanComplexItem
::
_altitudeFactName
=
"Altitude"
;
const
char
*
StructureScanComplexItem
::
_altitudeFactName
=
"Altitude"
;
const
char
*
StructureScanComplexItem
::
_structureHeightFactName
=
"StructureHeight"
;
const
char
*
StructureScanComplexItem
::
_structureHeightFactName
=
"StructureHeight"
;
const
char
*
StructureScanComplexItem
::
_layersFactName
=
"Layers"
;
const
char
*
StructureScanComplexItem
::
_layersFactName
=
"Layers"
;
const
char
*
StructureScanComplexItem
::
_gimbalPitchFactName
=
"GimbalPitch"
;
const
char
*
StructureScanComplexItem
::
_gimbalYawFactName
=
"GimbalYaw"
;
const
char
*
StructureScanComplexItem
::
jsonComplexItemTypeValue
=
"StructureScan"
;
const
char
*
StructureScanComplexItem
::
jsonComplexItemTypeValue
=
"StructureScan"
;
const
char
*
StructureScanComplexItem
::
_jsonCameraCalcKey
=
"CameraCalc"
;
const
char
*
StructureScanComplexItem
::
_jsonCameraCalcKey
=
"CameraCalc"
;
...
@@ -46,8 +44,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
...
@@ -46,8 +44,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
,
_cameraCalc
(
vehicle
)
,
_cameraCalc
(
vehicle
)
,
_altitudeFact
(
0
,
_altitudeFactName
,
FactMetaData
::
valueTypeDouble
)
,
_altitudeFact
(
0
,
_altitudeFactName
,
FactMetaData
::
valueTypeDouble
)
,
_layersFact
(
0
,
_layersFactName
,
FactMetaData
::
valueTypeUint32
)
,
_layersFact
(
0
,
_layersFactName
,
FactMetaData
::
valueTypeUint32
)
,
_gimbalPitchFact
(
0
,
_gimbalPitchFactName
,
FactMetaData
::
valueTypeDouble
)
,
_gimbalYawFact
(
0
,
_gimbalYawFactName
,
FactMetaData
::
valueTypeDouble
)
{
{
_editorQml
=
"qrc:/qml/StructureScanEditor.qml"
;
_editorQml
=
"qrc:/qml/StructureScanEditor.qml"
;
...
@@ -57,20 +53,14 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
...
@@ -57,20 +53,14 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
_altitudeFact
.
setMetaData
(
_metaDataMap
[
_altitudeFactName
]);
_altitudeFact
.
setMetaData
(
_metaDataMap
[
_altitudeFactName
]);
_layersFact
.
setMetaData
(
_metaDataMap
[
_layersFactName
]);
_layersFact
.
setMetaData
(
_metaDataMap
[
_layersFactName
]);
_gimbalPitchFact
.
setMetaData
(
_metaDataMap
[
_gimbalPitchFactName
]);
_gimbalYawFact
.
setMetaData
(
_metaDataMap
[
_gimbalYawFactName
]);
_altitudeFact
.
setRawValue
(
_altitudeFact
.
rawDefaultValue
());
_altitudeFact
.
setRawValue
(
_altitudeFact
.
rawDefaultValue
());
_layersFact
.
setRawValue
(
_layersFact
.
rawDefaultValue
());
_layersFact
.
setRawValue
(
_layersFact
.
rawDefaultValue
());
_gimbalPitchFact
.
setRawValue
(
_gimbalPitchFact
.
rawDefaultValue
());
_gimbalYawFact
.
setRawValue
(
_gimbalYawFact
.
rawDefaultValue
());
_altitudeFact
.
setRawValue
(
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
defaultMissionItemAltitude
()
->
rawValue
());
_altitudeFact
.
setRawValue
(
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
defaultMissionItemAltitude
()
->
rawValue
());
connect
(
&
_altitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_setDirty
);
connect
(
&
_altitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_setDirty
);
connect
(
&
_layersFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_setDirty
);
connect
(
&
_layersFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_setDirty
);
connect
(
&
_gimbalPitchFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_setDirty
);
connect
(
&
_gimbalYawFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_setDirty
);
connect
(
&
_layersFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_recalcLayerInfo
);
connect
(
&
_layersFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_recalcLayerInfo
);
connect
(
&
_structureHeightFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_recalcLayerInfo
);
connect
(
&
_structureHeightFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_recalcLayerInfo
);
...
@@ -89,7 +79,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
...
@@ -89,7 +79,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
connect
(
&
_flightPolygon
,
&
QGCMapPolygon
::
pathChanged
,
this
,
&
StructureScanComplexItem
::
_flightPathChanged
);
connect
(
&
_flightPolygon
,
&
QGCMapPolygon
::
pathChanged
,
this
,
&
StructureScanComplexItem
::
_flightPathChanged
);
connect
(
_cameraCalc
.
distanceToSurface
(),
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_rebuildFlightPolygon
);
connect
(
_cameraCalc
.
distanceToSurface
(),
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_rebuildFlightPolygon
);
connect
(
&
_cameraCalc
,
&
CameraCalc
::
cameraNameChanged
,
this
,
&
StructureScanComplexItem
::
_resetGimbal
);
connect
(
&
_flightPolygon
,
&
QGCMapPolygon
::
pathChanged
,
this
,
&
StructureScanComplexItem
::
_recalcCameraShots
);
connect
(
&
_flightPolygon
,
&
QGCMapPolygon
::
pathChanged
,
this
,
&
StructureScanComplexItem
::
_recalcCameraShots
);
connect
(
_cameraCalc
.
adjustedFootprintSide
(),
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_recalcCameraShots
);
connect
(
_cameraCalc
.
adjustedFootprintSide
(),
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_recalcCameraShots
);
...
@@ -134,7 +123,7 @@ int StructureScanComplexItem::lastSequenceNumber(void) const
...
@@ -134,7 +123,7 @@ int StructureScanComplexItem::lastSequenceNumber(void) const
(
_layersFact
.
rawValue
().
toInt
()
*
(
_layersFact
.
rawValue
().
toInt
()
*
((
_flightPolygon
.
count
()
+
1
)
+
// 1 waypoint for each polygon vertex + 1 to go back to first polygon vertex for each layer
((
_flightPolygon
.
count
()
+
1
)
+
// 1 waypoint for each polygon vertex + 1 to go back to first polygon vertex for each layer
2
))
+
// Camera trigger start/stop for each layer
2
))
+
// Camera trigger start/stop for each layer
1
;
// Gimbal control command
2
;
// ROI_WPNEXT_OFFSET and ROI_NONE commands
}
}
void
StructureScanComplexItem
::
setDirty
(
bool
dirty
)
void
StructureScanComplexItem
::
setDirty
(
bool
dirty
)
...
@@ -154,8 +143,6 @@ void StructureScanComplexItem::save(QJsonArray& missionItems)
...
@@ -154,8 +143,6 @@ void StructureScanComplexItem::save(QJsonArray& missionItems)
saveObject
[
VisualMissionItem
::
jsonTypeKey
]
=
VisualMissionItem
::
jsonTypeComplexItemValue
;
saveObject
[
VisualMissionItem
::
jsonTypeKey
]
=
VisualMissionItem
::
jsonTypeComplexItemValue
;
saveObject
[
ComplexMissionItem
::
jsonComplexItemTypeKey
]
=
jsonComplexItemTypeValue
;
saveObject
[
ComplexMissionItem
::
jsonComplexItemTypeKey
]
=
jsonComplexItemTypeValue
;
saveObject
[
_gimbalPitchFactName
]
=
_gimbalPitchFact
.
rawValue
().
toDouble
();
saveObject
[
_gimbalYawFactName
]
=
_gimbalYawFact
.
rawValue
().
toDouble
();
saveObject
[
_altitudeFactName
]
=
_altitudeFact
.
rawValue
().
toDouble
();
saveObject
[
_altitudeFactName
]
=
_altitudeFact
.
rawValue
().
toDouble
();
saveObject
[
_structureHeightFactName
]
=
_structureHeightFact
.
rawValue
().
toDouble
();
saveObject
[
_structureHeightFactName
]
=
_structureHeightFact
.
rawValue
().
toDouble
();
saveObject
[
_jsonAltitudeRelativeKey
]
=
_altitudeRelative
;
saveObject
[
_jsonAltitudeRelativeKey
]
=
_altitudeRelative
;
...
@@ -186,8 +173,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
...
@@ -186,8 +173,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
{
VisualMissionItem
::
jsonTypeKey
,
QJsonValue
::
String
,
true
},
{
VisualMissionItem
::
jsonTypeKey
,
QJsonValue
::
String
,
true
},
{
ComplexMissionItem
::
jsonComplexItemTypeKey
,
QJsonValue
::
String
,
true
},
{
ComplexMissionItem
::
jsonComplexItemTypeKey
,
QJsonValue
::
String
,
true
},
{
QGCMapPolygon
::
jsonPolygonKey
,
QJsonValue
::
Array
,
true
},
{
QGCMapPolygon
::
jsonPolygonKey
,
QJsonValue
::
Array
,
true
},
{
_gimbalPitchFactName
,
QJsonValue
::
Double
,
true
},
{
_gimbalYawFactName
,
QJsonValue
::
Double
,
true
},
{
_altitudeFactName
,
QJsonValue
::
Double
,
true
},
{
_altitudeFactName
,
QJsonValue
::
Double
,
true
},
{
_structureHeightFactName
,
QJsonValue
::
Double
,
true
},
{
_structureHeightFactName
,
QJsonValue
::
Double
,
true
},
{
_jsonAltitudeRelativeKey
,
QJsonValue
::
Bool
,
true
},
{
_jsonAltitudeRelativeKey
,
QJsonValue
::
Bool
,
true
},
...
@@ -220,8 +205,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
...
@@ -220,8 +205,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
return
false
;
return
false
;
}
}
_gimbalPitchFact
.
setRawValue
(
complexObject
[
_gimbalPitchFactName
].
toDouble
());
_gimbalYawFact
.
setRawValue
(
complexObject
[
_gimbalYawFactName
].
toDouble
());
_altitudeFact
.
setRawValue
(
complexObject
[
_altitudeFactName
].
toDouble
());
_altitudeFact
.
setRawValue
(
complexObject
[
_altitudeFactName
].
toDouble
());
_layersFact
.
setRawValue
(
complexObject
[
_layersFactName
].
toDouble
());
_layersFact
.
setRawValue
(
complexObject
[
_layersFactName
].
toDouble
());
_altitudeRelative
=
complexObject
[
_jsonAltitudeRelativeKey
].
toBool
(
true
);
_altitudeRelative
=
complexObject
[
_jsonAltitudeRelativeKey
].
toBool
(
true
);
...
@@ -268,13 +251,11 @@ void StructureScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QO
...
@@ -268,13 +251,11 @@ void StructureScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QO
double
baseAltitude
=
_altitudeFact
.
rawValue
().
toDouble
();
double
baseAltitude
=
_altitudeFact
.
rawValue
().
toDouble
();
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_DO_
MOUNT_CONTROL
,
MAV_CMD_DO_
SET_ROI_WPNEXT_OFFSET
,
MAV_FRAME_MISSION
,
MAV_FRAME_MISSION
,
_gimbalPitchFact
.
rawValue
().
toDouble
(),
0
,
0
,
0
,
0
,
// param 1-4 not used
0
,
// Gimbal roll
0
,
0
,
// Pitch and Roll stay in standard orientation
_gimbalYawFact
.
rawValue
().
toDouble
(),
90
,
// 90 degreee yaw offset to point to structure
0
,
0
,
0
,
// param 4-6 not used
MAV_MOUNT_MODE_MAVLINK_TARGETING
,
true
,
// autoContinue
true
,
// autoContinue
false
,
// isCurrentItem
false
,
// isCurrentItem
missionItemParent
);
missionItemParent
);
...
@@ -349,6 +330,15 @@ void StructureScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QO
...
@@ -349,6 +330,15 @@ void StructureScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QO
missionItemParent
);
missionItemParent
);
items
.
append
(
item
);
items
.
append
(
item
);
}
}
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_DO_SET_ROI_NONE
,
MAV_FRAME_MISSION
,
0
,
0
,
0
,
0
,
0
,
0
,
0
,
// param 1-7 not used
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
items
.
append
(
item
);
}
}
int
StructureScanComplexItem
::
cameraShots
(
void
)
const
int
StructureScanComplexItem
::
cameraShots
(
void
)
const
...
@@ -447,12 +437,6 @@ void StructureScanComplexItem::_recalcCameraShots(void)
...
@@ -447,12 +437,6 @@ void StructureScanComplexItem::_recalcCameraShots(void)
_setCameraShots
(
cameraShots
*
_layersFact
.
rawValue
().
toInt
());
_setCameraShots
(
cameraShots
*
_layersFact
.
rawValue
().
toInt
());
}
}
void
StructureScanComplexItem
::
_resetGimbal
(
void
)
{
_gimbalPitchFact
.
setCookedValue
(
0
);
_gimbalYawFact
.
setCookedValue
(
90
);
}
void
StructureScanComplexItem
::
setAltitudeRelative
(
bool
altitudeRelative
)
void
StructureScanComplexItem
::
setAltitudeRelative
(
bool
altitudeRelative
)
{
{
if
(
altitudeRelative
!=
_altitudeRelative
)
{
if
(
altitudeRelative
!=
_altitudeRelative
)
{
...
...
src/MissionManager/StructureScanComplexItem.h
View file @
2a4261eb
...
@@ -28,8 +28,6 @@ public:
...
@@ -28,8 +28,6 @@ public:
StructureScanComplexItem
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
StructureScanComplexItem
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
Q_PROPERTY
(
CameraCalc
*
cameraCalc
READ
cameraCalc
CONSTANT
)
Q_PROPERTY
(
CameraCalc
*
cameraCalc
READ
cameraCalc
CONSTANT
)
Q_PROPERTY
(
Fact
*
gimbalPitch
READ
gimbalPitch
CONSTANT
)
Q_PROPERTY
(
Fact
*
gimbalYaw
READ
gimbalYaw
CONSTANT
)
Q_PROPERTY
(
Fact
*
altitude
READ
altitude
CONSTANT
)
Q_PROPERTY
(
Fact
*
altitude
READ
altitude
CONSTANT
)
Q_PROPERTY
(
Fact
*
structureHeight
READ
structureHeight
CONSTANT
)
Q_PROPERTY
(
Fact
*
structureHeight
READ
structureHeight
CONSTANT
)
Q_PROPERTY
(
Fact
*
layers
READ
layers
CONSTANT
)
Q_PROPERTY
(
Fact
*
layers
READ
layers
CONSTANT
)
...
@@ -47,8 +45,6 @@ public:
...
@@ -47,8 +45,6 @@ public:
bool
altitudeRelative
(
void
)
const
{
return
_altitudeRelative
;
}
bool
altitudeRelative
(
void
)
const
{
return
_altitudeRelative
;
}
int
cameraShots
(
void
)
const
;
int
cameraShots
(
void
)
const
;
Fact
*
gimbalPitch
(
void
)
{
return
&
_gimbalPitchFact
;
}
Fact
*
gimbalYaw
(
void
)
{
return
&
_gimbalYawFact
;
}
double
timeBetweenShots
(
void
);
double
timeBetweenShots
(
void
);
QGCMapPolygon
*
structurePolygon
(
void
)
{
return
&
_structurePolygon
;
}
QGCMapPolygon
*
structurePolygon
(
void
)
{
return
&
_structurePolygon
;
}
QGCMapPolygon
*
flightPolygon
(
void
)
{
return
&
_flightPolygon
;
}
QGCMapPolygon
*
flightPolygon
(
void
)
{
return
&
_flightPolygon
;
}
...
@@ -111,7 +107,6 @@ private slots:
...
@@ -111,7 +107,6 @@ private slots:
void
_updateCoordinateAltitudes
(
void
);
void
_updateCoordinateAltitudes
(
void
);
void
_rebuildFlightPolygon
(
void
);
void
_rebuildFlightPolygon
(
void
);
void
_recalcCameraShots
(
void
);
void
_recalcCameraShots
(
void
);
void
_resetGimbal
(
void
);
void
_recalcLayerInfo
(
void
);
void
_recalcLayerInfo
(
void
);
private:
private:
...
@@ -140,14 +135,10 @@ private:
...
@@ -140,14 +135,10 @@ private:
Fact
_altitudeFact
;
Fact
_altitudeFact
;
Fact
_structureHeightFact
;
Fact
_structureHeightFact
;
Fact
_layersFact
;
Fact
_layersFact
;
Fact
_gimbalPitchFact
;
Fact
_gimbalYawFact
;
static
const
char
*
_altitudeFactName
;
static
const
char
*
_altitudeFactName
;
static
const
char
*
_structureHeightFactName
;
static
const
char
*
_structureHeightFactName
;
static
const
char
*
_layersFactName
;
static
const
char
*
_layersFactName
;
static
const
char
*
_gimbalPitchFactName
;
static
const
char
*
_gimbalYawFactName
;
static
const
char
*
_jsonCameraCalcKey
;
static
const
char
*
_jsonCameraCalcKey
;
static
const
char
*
_jsonAltitudeRelativeKey
;
static
const
char
*
_jsonAltitudeRelativeKey
;
...
...
src/MissionManager/StructureScanComplexItemTest.cc
View file @
2a4261eb
...
@@ -59,7 +59,7 @@ void StructureScanComplexItemTest::_testDirty(void)
...
@@ -59,7 +59,7 @@ void StructureScanComplexItemTest::_testDirty(void)
// These facts should set dirty when changed
// These facts should set dirty when changed
QList
<
Fact
*>
rgFacts
;
QList
<
Fact
*>
rgFacts
;
rgFacts
<<
_structureScanItem
->
gimbalPitch
()
<<
_structureScanItem
->
gimbalYaw
()
<<
_structureScanItem
->
altitude
()
<<
_structureScanItem
->
layers
();
rgFacts
<<
_structureScanItem
->
altitude
()
<<
_structureScanItem
->
layers
();
foreach
(
Fact
*
fact
,
rgFacts
)
{
foreach
(
Fact
*
fact
,
rgFacts
)
{
qDebug
()
<<
fact
->
name
();
qDebug
()
<<
fact
->
name
();
QVERIFY
(
!
_structureScanItem
->
dirty
());
QVERIFY
(
!
_structureScanItem
->
dirty
());
...
@@ -93,8 +93,6 @@ void StructureScanComplexItemTest::_initItem(void)
...
@@ -93,8 +93,6 @@ void StructureScanComplexItemTest::_initItem(void)
}
}
_structureScanItem
->
cameraCalc
()
->
setCameraName
(
CameraCalc
::
manualCameraName
());
_structureScanItem
->
cameraCalc
()
->
setCameraName
(
CameraCalc
::
manualCameraName
());
_structureScanItem
->
gimbalPitch
()
->
setCookedValue
(
45
);
_structureScanItem
->
gimbalYaw
()
->
setCookedValue
(
45
);
_structureScanItem
->
layers
()
->
setCookedValue
(
2
);
_structureScanItem
->
layers
()
->
setCookedValue
(
2
);
_structureScanItem
->
setDirty
(
false
);
_structureScanItem
->
setDirty
(
false
);
...
@@ -112,8 +110,6 @@ void StructureScanComplexItemTest::_validateItem(StructureScanComplexItem* item)
...
@@ -112,8 +110,6 @@ void StructureScanComplexItemTest::_validateItem(StructureScanComplexItem* item)
}
}
QCOMPARE
(
_structureScanItem
->
cameraCalc
()
->
cameraName
()
,
CameraCalc
::
manualCameraName
());
QCOMPARE
(
_structureScanItem
->
cameraCalc
()
->
cameraName
()
,
CameraCalc
::
manualCameraName
());
QCOMPARE
(
item
->
gimbalPitch
()
->
cookedValue
().
toDouble
(),
45.0
);
QCOMPARE
(
item
->
gimbalYaw
()
->
cookedValue
().
toDouble
(),
45.0
);
QCOMPARE
(
item
->
layers
()
->
cookedValue
().
toInt
(),
2
);
QCOMPARE
(
item
->
layers
()
->
cookedValue
().
toInt
(),
2
);
}
}
...
@@ -132,17 +128,6 @@ void StructureScanComplexItemTest::_testSaveLoad(void)
...
@@ -132,17 +128,6 @@ void StructureScanComplexItemTest::_testSaveLoad(void)
newItem
->
deleteLater
();
newItem
->
deleteLater
();
}
}
void
StructureScanComplexItemTest
::
_testGimbalAngleUpdate
(
void
)
{
// This sets the item to CameraCalc::CameraSpecNone and non-standard gimbal angles
_initItem
();
// Switching to a camera specific setup should set gimbal angles to defaults
_structureScanItem
->
cameraCalc
()
->
setCameraName
(
CameraCalc
::
customCameraName
());
QCOMPARE
(
_structureScanItem
->
gimbalPitch
()
->
cookedValue
().
toDouble
(),
0.0
);
QCOMPARE
(
_structureScanItem
->
gimbalYaw
()
->
cookedValue
().
toDouble
(),
90.0
);
}
void
StructureScanComplexItemTest
::
_testItemCount
(
void
)
void
StructureScanComplexItemTest
::
_testItemCount
(
void
)
{
{
QList
<
MissionItem
*>
items
;
QList
<
MissionItem
*>
items
;
...
...
src/MissionManager/StructureScanComplexItemTest.h
View file @
2a4261eb
...
@@ -27,7 +27,6 @@ protected:
...
@@ -27,7 +27,6 @@ protected:
private
slots
:
private
slots
:
void
_testDirty
(
void
);
void
_testDirty
(
void
);
void
_testSaveLoad
(
void
);
void
_testSaveLoad
(
void
);
void
_testGimbalAngleUpdate
(
void
);
void
_testItemCount
(
void
);
void
_testItemCount
(
void
);
private:
private:
...
...
src/MissionManager/SurveyMissionItem.h
View file @
2a4261eb
...
@@ -296,7 +296,7 @@ private:
...
@@ -296,7 +296,7 @@ private:
static
const
char
*
_jsonFixedValueIsAltitudeKey
;
static
const
char
*
_jsonFixedValueIsAltitudeKey
;
static
const
char
*
_jsonRefly90DegreesKey
;
static
const
char
*
_jsonRefly90DegreesKey
;
static
const
int
_hoverAndCaptureDelaySeconds
=
2
;
static
const
int
_hoverAndCaptureDelaySeconds
=
4
;
};
};
#endif
#endif
src/PlanView/MissionSettingsEditor.qml
View file @
2a4261eb
...
@@ -36,6 +36,7 @@ Rectangle {
...
@@ -36,6 +36,7 @@ Rectangle {
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
property
bool
_waypointsOnlyMode
:
QGroundControl
.
corePlugin
.
options
.
missionWaypointsOnly
property
bool
_showCameraSection
:
!
_waypointsOnlyMode
||
QGroundControl
.
corePlugin
.
showAdvancedUI
readonly
property
string
_firmwareLabel
:
qsTr
(
"
Firmware
"
)
readonly
property
string
_firmwareLabel
:
qsTr
(
"
Firmware
"
)
readonly
property
string
_vehicleLabel
:
qsTr
(
"
Vehicle
"
)
readonly
property
string
_vehicleLabel
:
qsTr
(
"
Vehicle
"
)
...
@@ -91,6 +92,7 @@ Rectangle {
...
@@ -91,6 +92,7 @@ Rectangle {
CameraSection
{
CameraSection
{
id
:
cameraSection
id
:
cameraSection
checked
:
missionItem
.
cameraSection
.
settingsSpecified
checked
:
missionItem
.
cameraSection
.
settingsSpecified
visible
:
_showCameraSection
}
}
QGCLabel
{
QGCLabel
{
...
@@ -100,7 +102,7 @@ Rectangle {
...
@@ -100,7 +102,7 @@ Rectangle {
wrapMode
:
Text
.
WordWrap
wrapMode
:
Text
.
WordWrap
horizontalAlignment
:
Text
.
AlignHCenter
horizontalAlignment
:
Text
.
AlignHCenter
font.pointSize
:
ScreenTools
.
smallFontPointSize
font.pointSize
:
ScreenTools
.
smallFontPointSize
visible
:
cameraSection
.
checked
visible
:
_showCameraSection
&&
cameraSection
.
checked
}
}
SectionHeader
{
SectionHeader
{
...
...
src/PlanView/StructureScanEditor.qml
View file @
2a4261eb
...
@@ -81,33 +81,6 @@ Rectangle {
...
@@ -81,33 +81,6 @@ Rectangle {
sideDistanceLabel
:
qsTr
(
"
Trigger Distance
"
)
sideDistanceLabel
:
qsTr
(
"
Trigger Distance
"
)
}
}
GridLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
columnSpacing
:
ScreenTools
.
defaultFontPixelWidth
/
2
rowSpacing
:
0
columns
:
3
visible
:
missionItem
.
cameraCalc
.
isManualCamera
Item
{
width
:
1
;
height
:
1
}
QGCLabel
{
text
:
qsTr
(
"
Pitch
"
)
}
QGCLabel
{
text
:
qsTr
(
"
Yaw
"
)
}
QGCLabel
{
text
:
qsTr
(
"
Gimbal
"
)
Layout.fillWidth
:
true
}
FactTextField
{
fact
:
missionItem
.
gimbalPitch
implicitWidth
:
ScreenTools
.
defaultFontPixelWidth
*
9
}
FactTextField
{
fact
:
missionItem
.
gimbalYaw
implicitWidth
:
ScreenTools
.
defaultFontPixelWidth
*
9
}
}
SectionHeader
{
SectionHeader
{
id
:
scanHeader
id
:
scanHeader
text
:
qsTr
(
"
Scan
"
)
text
:
qsTr
(
"
Scan
"
)
...
...
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