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
1b3ac79f
Unverified
Commit
1b3ac79f
authored
Feb 06, 2018
by
Don Gagne
Committed by
GitHub
Feb 06, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6119 from DonLakeFlyer/StructureScanROI_WPNEXT_OFFSET
Switch to using ROI_WPNEXT_OFFSET
parents
24e27d25
11df383e
Changes
5
Show whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
17 additions
and
85 deletions
+17
-85
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
StructureScanEditor.qml
src/PlanView/StructureScanEditor.qml
+0
-27
No files found.
src/MissionManager/StructureScanComplexItem.cc
View file @
1b3ac79f
...
...
@@ -24,8 +24,6 @@ QGC_LOGGING_CATEGORY(StructureScanComplexItemLog, "StructureScanComplexItemLog")
const
char
*
StructureScanComplexItem
::
_altitudeFactName
=
"Altitude"
;
const
char
*
StructureScanComplexItem
::
_structureHeightFactName
=
"StructureHeight"
;
const
char
*
StructureScanComplexItem
::
_layersFactName
=
"Layers"
;
const
char
*
StructureScanComplexItem
::
_gimbalPitchFactName
=
"GimbalPitch"
;
const
char
*
StructureScanComplexItem
::
_gimbalYawFactName
=
"GimbalYaw"
;
const
char
*
StructureScanComplexItem
::
jsonComplexItemTypeValue
=
"StructureScan"
;
const
char
*
StructureScanComplexItem
::
_jsonCameraCalcKey
=
"CameraCalc"
;
...
...
@@ -46,8 +44,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
,
_cameraCalc
(
vehicle
)
,
_altitudeFact
(
0
,
_altitudeFactName
,
FactMetaData
::
valueTypeDouble
)
,
_layersFact
(
0
,
_layersFactName
,
FactMetaData
::
valueTypeUint32
)
,
_gimbalPitchFact
(
0
,
_gimbalPitchFactName
,
FactMetaData
::
valueTypeDouble
)
,
_gimbalYawFact
(
0
,
_gimbalYawFactName
,
FactMetaData
::
valueTypeDouble
)
{
_editorQml
=
"qrc:/qml/StructureScanEditor.qml"
;
...
...
@@ -57,20 +53,14 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
_altitudeFact
.
setMetaData
(
_metaDataMap
[
_altitudeFactName
]);
_layersFact
.
setMetaData
(
_metaDataMap
[
_layersFactName
]);
_gimbalPitchFact
.
setMetaData
(
_metaDataMap
[
_gimbalPitchFactName
]);
_gimbalYawFact
.
setMetaData
(
_metaDataMap
[
_gimbalYawFactName
]);
_altitudeFact
.
setRawValue
(
_altitudeFact
.
rawDefaultValue
());
_layersFact
.
setRawValue
(
_layersFact
.
rawDefaultValue
());
_gimbalPitchFact
.
setRawValue
(
_gimbalPitchFact
.
rawDefaultValue
());
_gimbalYawFact
.
setRawValue
(
_gimbalYawFact
.
rawDefaultValue
());
_altitudeFact
.
setRawValue
(
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
defaultMissionItemAltitude
()
->
rawValue
());
connect
(
&
_altitudeFact
,
&
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
(
&
_structureHeightFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_recalcLayerInfo
);
...
...
@@ -89,7 +79,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
connect
(
&
_flightPolygon
,
&
QGCMapPolygon
::
pathChanged
,
this
,
&
StructureScanComplexItem
::
_flightPathChanged
);
connect
(
_cameraCalc
.
distanceToSurface
(),
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_rebuildFlightPolygon
);
connect
(
&
_cameraCalc
,
&
CameraCalc
::
cameraNameChanged
,
this
,
&
StructureScanComplexItem
::
_resetGimbal
);
connect
(
&
_flightPolygon
,
&
QGCMapPolygon
::
pathChanged
,
this
,
&
StructureScanComplexItem
::
_recalcCameraShots
);
connect
(
_cameraCalc
.
adjustedFootprintSide
(),
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_recalcCameraShots
);
...
...
@@ -134,7 +123,7 @@ int StructureScanComplexItem::lastSequenceNumber(void) const
(
_layersFact
.
rawValue
().
toInt
()
*
((
_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
1
;
// Gimbal control command
2
;
// ROI_WPNEXT_OFFSET and ROI_NONE commands
}
void
StructureScanComplexItem
::
setDirty
(
bool
dirty
)
...
...
@@ -154,8 +143,6 @@ void StructureScanComplexItem::save(QJsonArray& missionItems)
saveObject
[
VisualMissionItem
::
jsonTypeKey
]
=
VisualMissionItem
::
jsonTypeComplexItemValue
;
saveObject
[
ComplexMissionItem
::
jsonComplexItemTypeKey
]
=
jsonComplexItemTypeValue
;
saveObject
[
_gimbalPitchFactName
]
=
_gimbalPitchFact
.
rawValue
().
toDouble
();
saveObject
[
_gimbalYawFactName
]
=
_gimbalYawFact
.
rawValue
().
toDouble
();
saveObject
[
_altitudeFactName
]
=
_altitudeFact
.
rawValue
().
toDouble
();
saveObject
[
_structureHeightFactName
]
=
_structureHeightFact
.
rawValue
().
toDouble
();
saveObject
[
_jsonAltitudeRelativeKey
]
=
_altitudeRelative
;
...
...
@@ -186,8 +173,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
{
VisualMissionItem
::
jsonTypeKey
,
QJsonValue
::
String
,
true
},
{
ComplexMissionItem
::
jsonComplexItemTypeKey
,
QJsonValue
::
String
,
true
},
{
QGCMapPolygon
::
jsonPolygonKey
,
QJsonValue
::
Array
,
true
},
{
_gimbalPitchFactName
,
QJsonValue
::
Double
,
true
},
{
_gimbalYawFactName
,
QJsonValue
::
Double
,
true
},
{
_altitudeFactName
,
QJsonValue
::
Double
,
true
},
{
_structureHeightFactName
,
QJsonValue
::
Double
,
true
},
{
_jsonAltitudeRelativeKey
,
QJsonValue
::
Bool
,
true
},
...
...
@@ -220,8 +205,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
return
false
;
}
_gimbalPitchFact
.
setRawValue
(
complexObject
[
_gimbalPitchFactName
].
toDouble
());
_gimbalYawFact
.
setRawValue
(
complexObject
[
_gimbalYawFactName
].
toDouble
());
_altitudeFact
.
setRawValue
(
complexObject
[
_altitudeFactName
].
toDouble
());
_layersFact
.
setRawValue
(
complexObject
[
_layersFactName
].
toDouble
());
_altitudeRelative
=
complexObject
[
_jsonAltitudeRelativeKey
].
toBool
(
true
);
...
...
@@ -268,13 +251,11 @@ void StructureScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QO
double
baseAltitude
=
_altitudeFact
.
rawValue
().
toDouble
();
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_DO_
MOUNT_CONTROL
,
MAV_CMD_DO_
SET_ROI_WPNEXT_OFFSET
,
MAV_FRAME_MISSION
,
_gimbalPitchFact
.
rawValue
().
toDouble
(),
0
,
// Gimbal roll
_gimbalYawFact
.
rawValue
().
toDouble
(),
0
,
0
,
0
,
// param 4-6 not used
MAV_MOUNT_MODE_MAVLINK_TARGETING
,
0
,
0
,
0
,
0
,
// param 1-4 not used
0
,
0
,
// Pitch and Roll stay in standard orientation
90
,
// 90 degreee yaw offset to point to structure
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
...
...
@@ -349,6 +330,15 @@ void StructureScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QO
missionItemParent
);
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
...
...
@@ -447,12 +437,6 @@ void StructureScanComplexItem::_recalcCameraShots(void)
_setCameraShots
(
cameraShots
*
_layersFact
.
rawValue
().
toInt
());
}
void
StructureScanComplexItem
::
_resetGimbal
(
void
)
{
_gimbalPitchFact
.
setCookedValue
(
0
);
_gimbalYawFact
.
setCookedValue
(
90
);
}
void
StructureScanComplexItem
::
setAltitudeRelative
(
bool
altitudeRelative
)
{
if
(
altitudeRelative
!=
_altitudeRelative
)
{
...
...
src/MissionManager/StructureScanComplexItem.h
View file @
1b3ac79f
...
...
@@ -28,8 +28,6 @@ public:
StructureScanComplexItem
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
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
*
structureHeight
READ
structureHeight
CONSTANT
)
Q_PROPERTY
(
Fact
*
layers
READ
layers
CONSTANT
)
...
...
@@ -47,8 +45,6 @@ public:
bool
altitudeRelative
(
void
)
const
{
return
_altitudeRelative
;
}
int
cameraShots
(
void
)
const
;
Fact
*
gimbalPitch
(
void
)
{
return
&
_gimbalPitchFact
;
}
Fact
*
gimbalYaw
(
void
)
{
return
&
_gimbalYawFact
;
}
double
timeBetweenShots
(
void
);
QGCMapPolygon
*
structurePolygon
(
void
)
{
return
&
_structurePolygon
;
}
QGCMapPolygon
*
flightPolygon
(
void
)
{
return
&
_flightPolygon
;
}
...
...
@@ -111,7 +107,6 @@ private slots:
void
_updateCoordinateAltitudes
(
void
);
void
_rebuildFlightPolygon
(
void
);
void
_recalcCameraShots
(
void
);
void
_resetGimbal
(
void
);
void
_recalcLayerInfo
(
void
);
private:
...
...
@@ -140,14 +135,10 @@ private:
Fact
_altitudeFact
;
Fact
_structureHeightFact
;
Fact
_layersFact
;
Fact
_gimbalPitchFact
;
Fact
_gimbalYawFact
;
static
const
char
*
_altitudeFactName
;
static
const
char
*
_structureHeightFactName
;
static
const
char
*
_layersFactName
;
static
const
char
*
_gimbalPitchFactName
;
static
const
char
*
_gimbalYawFactName
;
static
const
char
*
_jsonCameraCalcKey
;
static
const
char
*
_jsonAltitudeRelativeKey
;
...
...
src/MissionManager/StructureScanComplexItemTest.cc
View file @
1b3ac79f
...
...
@@ -59,7 +59,7 @@ void StructureScanComplexItemTest::_testDirty(void)
// These facts should set dirty when changed
QList
<
Fact
*>
rgFacts
;
rgFacts
<<
_structureScanItem
->
gimbalPitch
()
<<
_structureScanItem
->
gimbalYaw
()
<<
_structureScanItem
->
altitude
()
<<
_structureScanItem
->
layers
();
rgFacts
<<
_structureScanItem
->
altitude
()
<<
_structureScanItem
->
layers
();
foreach
(
Fact
*
fact
,
rgFacts
)
{
qDebug
()
<<
fact
->
name
();
QVERIFY
(
!
_structureScanItem
->
dirty
());
...
...
@@ -93,8 +93,6 @@ void StructureScanComplexItemTest::_initItem(void)
}
_structureScanItem
->
cameraCalc
()
->
setCameraName
(
CameraCalc
::
manualCameraName
());
_structureScanItem
->
gimbalPitch
()
->
setCookedValue
(
45
);
_structureScanItem
->
gimbalYaw
()
->
setCookedValue
(
45
);
_structureScanItem
->
layers
()
->
setCookedValue
(
2
);
_structureScanItem
->
setDirty
(
false
);
...
...
@@ -112,8 +110,6 @@ void StructureScanComplexItemTest::_validateItem(StructureScanComplexItem* item)
}
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
);
}
...
...
@@ -132,17 +128,6 @@ void StructureScanComplexItemTest::_testSaveLoad(void)
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
)
{
QList
<
MissionItem
*>
items
;
...
...
src/MissionManager/StructureScanComplexItemTest.h
View file @
1b3ac79f
...
...
@@ -27,7 +27,6 @@ protected:
private
slots
:
void
_testDirty
(
void
);
void
_testSaveLoad
(
void
);
void
_testGimbalAngleUpdate
(
void
);
void
_testItemCount
(
void
);
private:
...
...
src/PlanView/StructureScanEditor.qml
View file @
1b3ac79f
...
...
@@ -81,33 +81,6 @@ Rectangle {
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
{
id
:
scanHeader
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