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
f4cf5aae
Unverified
Commit
f4cf5aae
authored
Jan 19, 2018
by
Don Gagne
Committed by
GitHub
Jan 19, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6050 from DonLakeFlyer/StructureScan
Remove disabled yawVehicleToStructure option
parents
0905b11b
6dce098a
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
12 additions
and
81 deletions
+12
-81
StructureScanComplexItem.cc
src/MissionManager/StructureScanComplexItem.cc
+12
-41
StructureScanComplexItem.h
src/MissionManager/StructureScanComplexItem.h
+0
-6
StructureScanComplexItemTest.cc
src/MissionManager/StructureScanComplexItemTest.cc
+0
-7
StructureScanEditor.qml
src/PlanView/StructureScanEditor.qml
+0
-27
No files found.
src/MissionManager/StructureScanComplexItem.cc
View file @
f4cf5aae
...
@@ -29,7 +29,6 @@ const char* StructureScanComplexItem::_gimbalYawFactName = "GimbalY
...
@@ -29,7 +29,6 @@ const char* StructureScanComplexItem::_gimbalYawFactName = "GimbalY
const
char
*
StructureScanComplexItem
::
jsonComplexItemTypeValue
=
"StructureScan"
;
const
char
*
StructureScanComplexItem
::
jsonComplexItemTypeValue
=
"StructureScan"
;
const
char
*
StructureScanComplexItem
::
_jsonCameraCalcKey
=
"CameraCalc"
;
const
char
*
StructureScanComplexItem
::
_jsonCameraCalcKey
=
"CameraCalc"
;
const
char
*
StructureScanComplexItem
::
_jsonAltitudeRelativeKey
=
"altitudeRelative"
;
const
char
*
StructureScanComplexItem
::
_jsonAltitudeRelativeKey
=
"altitudeRelative"
;
const
char
*
StructureScanComplexItem
::
_jsonYawVehicleToStructureKey
=
"yawVehicleToStructure"
;
QMap
<
QString
,
FactMetaData
*>
StructureScanComplexItem
::
_metaDataMap
;
QMap
<
QString
,
FactMetaData
*>
StructureScanComplexItem
::
_metaDataMap
;
...
@@ -44,7 +43,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
...
@@ -44,7 +43,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
,
_cameraShots
(
0
)
,
_cameraShots
(
0
)
,
_cameraMinTriggerInterval
(
0
)
,
_cameraMinTriggerInterval
(
0
)
,
_cameraCalc
(
vehicle
)
,
_cameraCalc
(
vehicle
)
,
_yawVehicleToStructure
(
false
)
,
_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
)
,
_gimbalPitchFact
(
0
,
_gimbalPitchFactName
,
FactMetaData
::
valueTypeDouble
)
...
@@ -76,7 +74,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
...
@@ -76,7 +74,6 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* pa
connect
(
this
,
&
StructureScanComplexItem
::
altitudeRelativeChanged
,
this
,
&
StructureScanComplexItem
::
_setDirty
);
connect
(
this
,
&
StructureScanComplexItem
::
altitudeRelativeChanged
,
this
,
&
StructureScanComplexItem
::
_setDirty
);
connect
(
this
,
&
StructureScanComplexItem
::
altitudeRelativeChanged
,
this
,
&
StructureScanComplexItem
::
coordinateHasRelativeAltitudeChanged
);
connect
(
this
,
&
StructureScanComplexItem
::
altitudeRelativeChanged
,
this
,
&
StructureScanComplexItem
::
coordinateHasRelativeAltitudeChanged
);
connect
(
this
,
&
StructureScanComplexItem
::
altitudeRelativeChanged
,
this
,
&
StructureScanComplexItem
::
exitCoordinateHasRelativeAltitudeChanged
);
connect
(
this
,
&
StructureScanComplexItem
::
altitudeRelativeChanged
,
this
,
&
StructureScanComplexItem
::
exitCoordinateHasRelativeAltitudeChanged
);
connect
(
this
,
&
StructureScanComplexItem
::
yawVehicleToStructureChanged
,
this
,
&
StructureScanComplexItem
::
_setDirty
);
connect
(
&
_altitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_updateCoordinateAltitudes
);
connect
(
&
_altitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
StructureScanComplexItem
::
_updateCoordinateAltitudes
);
...
@@ -155,7 +152,6 @@ void StructureScanComplexItem::save(QJsonArray& missionItems)
...
@@ -155,7 +152,6 @@ void StructureScanComplexItem::save(QJsonArray& missionItems)
saveObject
[
_altitudeFactName
]
=
_altitudeFact
.
rawValue
().
toDouble
();
saveObject
[
_altitudeFactName
]
=
_altitudeFact
.
rawValue
().
toDouble
();
saveObject
[
_jsonAltitudeRelativeKey
]
=
_altitudeRelative
;
saveObject
[
_jsonAltitudeRelativeKey
]
=
_altitudeRelative
;
saveObject
[
_layersFactName
]
=
_layersFact
.
rawValue
().
toDouble
();
saveObject
[
_layersFactName
]
=
_layersFact
.
rawValue
().
toDouble
();
saveObject
[
_jsonYawVehicleToStructureKey
]
=
_yawVehicleToStructure
;
QJsonObject
cameraCalcObject
;
QJsonObject
cameraCalcObject
;
_cameraCalc
.
save
(
cameraCalcObject
);
_cameraCalc
.
save
(
cameraCalcObject
);
...
@@ -188,7 +184,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
...
@@ -188,7 +184,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
{
_jsonAltitudeRelativeKey
,
QJsonValue
::
Bool
,
false
},
{
_jsonAltitudeRelativeKey
,
QJsonValue
::
Bool
,
false
},
{
_layersFactName
,
QJsonValue
::
Double
,
true
},
{
_layersFactName
,
QJsonValue
::
Double
,
true
},
{
_jsonCameraCalcKey
,
QJsonValue
::
Object
,
true
},
{
_jsonCameraCalcKey
,
QJsonValue
::
Object
,
true
},
{
_jsonYawVehicleToStructureKey
,
QJsonValue
::
Bool
,
true
},
};
};
if
(
!
JsonHelper
::
validateKeys
(
complexObject
,
keyInfoList
,
errorString
))
{
if
(
!
JsonHelper
::
validateKeys
(
complexObject
,
keyInfoList
,
errorString
))
{
return
false
;
return
false
;
...
@@ -221,7 +216,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
...
@@ -221,7 +216,6 @@ bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequen
_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
);
_yawVehicleToStructure
=
complexObject
[
_jsonYawVehicleToStructureKey
].
toBool
(
true
);
if
(
!
_structurePolygon
.
loadFromJson
(
complexObject
,
true
/* required */
,
errorString
))
{
if
(
!
_structurePolygon
.
loadFromJson
(
complexObject
,
true
/* required */
,
errorString
))
{
_structurePolygon
.
clear
();
_structurePolygon
.
clear
();
...
@@ -264,33 +258,18 @@ void StructureScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QO
...
@@ -264,33 +258,18 @@ void StructureScanComplexItem::appendMissionItems(QList<MissionItem*>& items, QO
int
seqNum
=
_sequenceNumber
;
int
seqNum
=
_sequenceNumber
;
double
baseAltitude
=
_altitudeFact
.
rawValue
().
toDouble
();
double
baseAltitude
=
_altitudeFact
.
rawValue
().
toDouble
();
if
(
_yawVehicleToStructure
)
{
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_DO_MOUNT_CONTROL
,
MAV_CMD_CONDITION_YAW
,
MAV_FRAME_MISSION
,
MAV_FRAME_MISSION
,
_gimbalPitchFact
.
rawValue
().
toDouble
(),
90.0
,
// Target angle
0
,
// Gimbal roll
0
,
// Use default turn rate
_gimbalYawFact
.
rawValue
().
toDouble
(),
1
,
// Clockwise turn
0
,
0
,
0
,
// param 4-6 not used
0
,
// Absolute angle specified
MAV_MOUNT_MODE_MAVLINK_TARGETING
,
0
,
0
,
0
,
// param 5-7 not used
true
,
// autoContinue
true
,
// autoContinue
false
,
// isCurrentItem
false
,
// isCurrentItem
missionItemParent
);
missionItemParent
);
items
.
append
(
item
);
items
.
append
(
item
);
}
else
{
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_DO_MOUNT_CONTROL
,
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
,
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
items
.
append
(
item
);
}
for
(
int
layer
=
0
;
layer
<
_layersFact
.
rawValue
().
toInt
();
layer
++
)
{
for
(
int
layer
=
0
;
layer
<
_layersFact
.
rawValue
().
toInt
();
layer
++
)
{
bool
addTriggerStart
=
true
;
bool
addTriggerStart
=
true
;
...
@@ -470,11 +449,3 @@ void StructureScanComplexItem::setAltitudeRelative(bool altitudeRelative)
...
@@ -470,11 +449,3 @@ void StructureScanComplexItem::setAltitudeRelative(bool altitudeRelative)
emit
altitudeRelativeChanged
(
altitudeRelative
);
emit
altitudeRelativeChanged
(
altitudeRelative
);
}
}
}
}
void
StructureScanComplexItem
::
setYawVehicleToStructure
(
bool
yawVehicleToStructure
)
{
if
(
yawVehicleToStructure
!=
_yawVehicleToStructure
)
{
_yawVehicleToStructure
=
yawVehicleToStructure
;
emit
yawVehicleToStructureChanged
(
yawVehicleToStructure
);
}
}
src/MissionManager/StructureScanComplexItem.h
View file @
f4cf5aae
...
@@ -38,7 +38,6 @@ public:
...
@@ -38,7 +38,6 @@ public:
Q_PROPERTY
(
double
cameraMinTriggerInterval
MEMBER
_cameraMinTriggerInterval
NOTIFY
cameraMinTriggerIntervalChanged
)
Q_PROPERTY
(
double
cameraMinTriggerInterval
MEMBER
_cameraMinTriggerInterval
NOTIFY
cameraMinTriggerIntervalChanged
)
Q_PROPERTY
(
QGCMapPolygon
*
structurePolygon
READ
structurePolygon
CONSTANT
)
Q_PROPERTY
(
QGCMapPolygon
*
structurePolygon
READ
structurePolygon
CONSTANT
)
Q_PROPERTY
(
QGCMapPolygon
*
flightPolygon
READ
flightPolygon
CONSTANT
)
Q_PROPERTY
(
QGCMapPolygon
*
flightPolygon
READ
flightPolygon
CONSTANT
)
Q_PROPERTY
(
bool
yawVehicleToStructure
READ
yawVehicleToStructure
WRITE
setYawVehicleToStructure
NOTIFY
yawVehicleToStructureChanged
)
///< true: vehicle yaws to point to structure, false: gimbal yaws to point to structure
CameraCalc
*
cameraCalc
(
void
)
{
return
&
_cameraCalc
;
}
CameraCalc
*
cameraCalc
(
void
)
{
return
&
_cameraCalc
;
}
Fact
*
altitude
(
void
)
{
return
&
_altitudeFact
;
}
Fact
*
altitude
(
void
)
{
return
&
_altitudeFact
;
}
...
@@ -51,10 +50,8 @@ public:
...
@@ -51,10 +50,8 @@ public:
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
;
}
bool
yawVehicleToStructure
(
void
)
const
{
return
_yawVehicleToStructure
;
}
void
setAltitudeRelative
(
bool
altitudeRelative
);
void
setAltitudeRelative
(
bool
altitudeRelative
);
void
setYawVehicleToStructure
(
bool
yawVehicleToStructure
);
Q_INVOKABLE
void
rotateEntryPoint
(
void
);
Q_INVOKABLE
void
rotateEntryPoint
(
void
);
...
@@ -102,7 +99,6 @@ signals:
...
@@ -102,7 +99,6 @@ signals:
void
timeBetweenShotsChanged
(
void
);
void
timeBetweenShotsChanged
(
void
);
void
cameraMinTriggerIntervalChanged
(
double
cameraMinTriggerInterval
);
void
cameraMinTriggerIntervalChanged
(
double
cameraMinTriggerInterval
);
void
altitudeRelativeChanged
(
bool
altitudeRelative
);
void
altitudeRelativeChanged
(
bool
altitudeRelative
);
void
yawVehicleToStructureChanged
(
bool
yawVehicleToStructure
);
private
slots
:
private
slots
:
void
_setDirty
(
void
);
void
_setDirty
(
void
);
...
@@ -135,7 +131,6 @@ private:
...
@@ -135,7 +131,6 @@ private:
double
_cameraMinTriggerInterval
;
double
_cameraMinTriggerInterval
;
double
_cruiseSpeed
;
double
_cruiseSpeed
;
CameraCalc
_cameraCalc
;
CameraCalc
_cameraCalc
;
bool
_yawVehicleToStructure
;
static
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
static
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
...
@@ -151,7 +146,6 @@ private:
...
@@ -151,7 +146,6 @@ private:
static
const
char
*
_jsonCameraCalcKey
;
static
const
char
*
_jsonCameraCalcKey
;
static
const
char
*
_jsonAltitudeRelativeKey
;
static
const
char
*
_jsonAltitudeRelativeKey
;
static
const
char
*
_jsonYawVehicleToStructureKey
;
friend
class
StructureScanComplexItemTest
;
friend
class
StructureScanComplexItemTest
;
};
};
...
...
src/MissionManager/StructureScanComplexItemTest.cc
View file @
f4cf5aae
...
@@ -81,13 +81,6 @@ void StructureScanComplexItemTest::_testDirty(void)
...
@@ -81,13 +81,6 @@ void StructureScanComplexItemTest::_testDirty(void)
QVERIFY
(
_multiSpy
->
pullBoolFromSignalIndex
(
dirtyChangedIndex
));
QVERIFY
(
_multiSpy
->
pullBoolFromSignalIndex
(
dirtyChangedIndex
));
_structureScanItem
->
setDirty
(
false
);
_structureScanItem
->
setDirty
(
false
);
_multiSpy
->
clearAllSignals
();
_multiSpy
->
clearAllSignals
();
QVERIFY
(
!
_structureScanItem
->
dirty
());
_structureScanItem
->
setYawVehicleToStructure
(
!
_structureScanItem
->
yawVehicleToStructure
());
QVERIFY
(
_multiSpy
->
checkSignalByMask
(
dirtyChangedMask
));
QVERIFY
(
_multiSpy
->
pullBoolFromSignalIndex
(
dirtyChangedIndex
));
_structureScanItem
->
setDirty
(
false
);
_multiSpy
->
clearAllSignals
();
}
}
void
StructureScanComplexItemTest
::
_initItem
(
void
)
void
StructureScanComplexItemTest
::
_initItem
(
void
)
...
...
src/PlanView/StructureScanEditor.qml
View file @
f4cf5aae
...
@@ -48,11 +48,6 @@ Rectangle {
...
@@ -48,11 +48,6 @@ Rectangle {
QGCPalette
{
id
:
qgcPal
;
colorGroupEnabled
:
true
}
QGCPalette
{
id
:
qgcPal
;
colorGroupEnabled
:
true
}
ExclusiveGroup
{
id
:
yawRadiosGroup
onCurrentChanged
:
missionItem
.
yawVehicleToStructure
=
yawVehicleRadio
.
checked
}
Column
{
Column
{
id
:
editorColumn
id
:
editorColumn
anchors.margins
:
_margin
anchors.margins
:
_margin
...
@@ -151,28 +146,6 @@ Rectangle {
...
@@ -151,28 +146,6 @@ Rectangle {
}
}
}
}
QGCLabel
{
text
:
qsTr
(
"
Point camera to structure using:
"
)
}
RowLayout
{
spacing
:
_margin
QGCRadioButton
{
id
:
yawVehicleRadio
text
:
qsTr
(
"
Vehicle yaw
"
)
exclusiveGroup
:
yawRadiosGroup
checked
:
!!
missionItem
.
yawVehicleToStructure
enabled
:
false
}
QGCRadioButton
{
text
:
qsTr
(
"
Gimbal yaw
"
)
exclusiveGroup
:
yawRadiosGroup
checked
:
!
missionItem
.
yawVehicleToStructure
enabled
:
false
}
}
Item
{
Item
{
height
:
ScreenTools
.
defaultFontPixelHeight
/
2
height
:
ScreenTools
.
defaultFontPixelHeight
/
2
width
:
1
width
:
1
...
...
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