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
52f51265
Commit
52f51265
authored
Dec 14, 2017
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Carry over speed/gimbal for defaults from previous items
parent
4ed2e7e2
Changes
22
Hide whitespace changes
Inline
Side-by-side
Showing
22 changed files
with
226 additions
and
55 deletions
+226
-55
CameraSection.cc
src/MissionManager/CameraSection.cc
+27
-3
CameraSection.h
src/MissionManager/CameraSection.h
+7
-0
CameraSectionTest.cc
src/MissionManager/CameraSectionTest.cc
+36
-5
CameraSectionTest.h
src/MissionManager/CameraSectionTest.h
+20
-17
FixedWingLandingComplexItem.h
src/MissionManager/FixedWingLandingComplexItem.h
+1
-0
MissionController.cc
src/MissionManager/MissionController.cc
+10
-6
MissionController.h
src/MissionManager/MissionController.h
+1
-0
MissionItem.cc
src/MissionManager/MissionItem.cc
+22
-0
MissionItem.h
src/MissionManager/MissionItem.h
+7
-2
MissionSettingsItem.cc
src/MissionManager/MissionSettingsItem.cc
+8
-2
MissionSettingsItem.h
src/MissionManager/MissionSettingsItem.h
+1
-0
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+28
-4
SimpleMissionItem.h
src/MissionManager/SimpleMissionItem.h
+2
-0
SpeedSection.cc
src/MissionManager/SpeedSection.cc
+12
-7
SpeedSection.h
src/MissionManager/SpeedSection.h
+1
-1
SpeedSectionTest.cc
src/MissionManager/SpeedSectionTest.cc
+27
-1
SpeedSectionTest.h
src/MissionManager/SpeedSectionTest.h
+7
-6
StructureScanComplexItem.h
src/MissionManager/StructureScanComplexItem.h
+1
-0
SurveyMissionItem.h
src/MissionManager/SurveyMissionItem.h
+1
-0
VisualMissionItem.h
src/MissionManager/VisualMissionItem.h
+4
-1
VisualMissionItemTest.cc
src/MissionManager/VisualMissionItemTest.cc
+1
-0
VisualMissionItemTest.h
src/MissionManager/VisualMissionItemTest.h
+2
-0
No files found.
src/MissionManager/CameraSection.cc
View file @
52f51265
...
...
@@ -59,8 +59,8 @@ CameraSection::CameraSection(Vehicle* vehicle, QObject* parent)
connect
(
&
_cameraActionFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_cameraActionChanged
);
connect
(
&
_gimbalPitchFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_
setDirty
);
connect
(
&
_gimbalYawFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_
setDirty
);
connect
(
&
_gimbalPitchFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_
dirtyIfSpecified
);
connect
(
&
_gimbalYawFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_
dirtyIfSpecified
);
connect
(
&
_cameraPhotoIntervalDistanceFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirty
);
connect
(
&
_cameraPhotoIntervalTimeFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirty
);
connect
(
&
_cameraModeFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_setDirty
);
...
...
@@ -68,7 +68,9 @@ CameraSection::CameraSection(Vehicle* vehicle, QObject* parent)
connect
(
this
,
&
CameraSection
::
specifyCameraModeChanged
,
this
,
&
CameraSection
::
_setDirty
);
connect
(
this
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
CameraSection
::
_updateSpecifiedGimbalYaw
);
connect
(
this
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
CameraSection
::
_updateSpecifiedGimbalPitch
);
connect
(
&
_gimbalYawFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_updateSpecifiedGimbalYaw
);
connect
(
&
_gimbalPitchFact
,
&
Fact
::
valueChanged
,
this
,
&
CameraSection
::
_updateSpecifiedGimbalPitch
);
}
void
CameraSection
::
setSpecifyGimbal
(
bool
specifyGimbal
)
...
...
@@ -491,9 +493,23 @@ double CameraSection::specifiedGimbalYaw(void) const
return
_specifyGimbal
?
_gimbalYawFact
.
rawValue
().
toDouble
()
:
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
CameraSection
::
specifiedGimbalPitch
(
void
)
const
{
return
_specifyGimbal
?
_gimbalPitchFact
.
rawValue
().
toDouble
()
:
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
void
CameraSection
::
_updateSpecifiedGimbalYaw
(
void
)
{
emit
specifiedGimbalYawChanged
(
specifiedGimbalYaw
());
if
(
_specifyGimbal
)
{
emit
specifiedGimbalYawChanged
(
specifiedGimbalYaw
());
}
}
void
CameraSection
::
_updateSpecifiedGimbalPitch
(
void
)
{
if
(
_specifyGimbal
)
{
emit
specifiedGimbalPitchChanged
(
specifiedGimbalPitch
());
}
}
void
CameraSection
::
_updateSettingsSpecified
(
void
)
...
...
@@ -521,3 +537,11 @@ bool CameraSection::cameraModeSupported(void) const
{
return
_vehicle
->
firmwarePlugin
()
->
supportedMissionCommands
().
contains
(
MAV_CMD_SET_CAMERA_MODE
);
}
void
CameraSection
::
_dirtyIfSpecified
(
void
)
{
// We only set the dirty bit if specify gimbal it set. This allows us to change defaults without affecting dirty.
if
(
_specifyGimbal
)
{
setDirty
(
true
);
}
}
src/MissionManager/CameraSection.h
View file @
52f51265
...
...
@@ -61,6 +61,10 @@ public:
///< @return The gimbal yaw specified by this item, NaN if not specified
double
specifiedGimbalYaw
(
void
)
const
;
///< Signals specifiedGimbalPitchChanged
///< @return The gimbal pitch specified by this item, NaN if not specified
double
specifiedGimbalPitch
(
void
)
const
;
// Overrides from Section
bool
available
(
void
)
const
override
{
return
_available
;
}
bool
dirty
(
void
)
const
override
{
return
_dirty
;
}
...
...
@@ -75,14 +79,17 @@ signals:
bool
specifyGimbalChanged
(
bool
specifyGimbal
);
bool
specifyCameraModeChanged
(
bool
specifyCameraMode
);
void
specifiedGimbalYawChanged
(
double
gimbalYaw
);
void
specifiedGimbalPitchChanged
(
double
gimbalPitch
);
private
slots
:
void
_setDirty
(
void
);
void
_setDirtyAndUpdateItemCount
(
void
);
void
_updateSpecifiedGimbalYaw
(
void
);
void
_updateSpecifiedGimbalPitch
(
void
);
void
_specifyChanged
(
void
);
void
_updateSettingsSpecified
(
void
);
void
_cameraActionChanged
(
void
);
void
_dirtyIfSpecified
(
void
);
private:
bool
_scanGimbal
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
...
...
src/MissionManager/CameraSectionTest.cc
View file @
52f51265
...
...
@@ -36,6 +36,7 @@ void CameraSectionTest::init(void)
rgCameraSignals
[
specifyGimbalChangedIndex
]
=
SIGNAL
(
specifyGimbalChanged
(
bool
));
rgCameraSignals
[
specifiedGimbalYawChangedIndex
]
=
SIGNAL
(
specifiedGimbalYawChanged
(
double
));
rgCameraSignals
[
specifiedGimbalPitchChangedIndex
]
=
SIGNAL
(
specifiedGimbalPitchChanged
(
double
));
rgCameraSignals
[
specifyCameraModeChangedIndex
]
=
SIGNAL
(
specifyCameraModeChanged
(
bool
));
_cameraSection
=
_simpleItem
->
cameraSection
();
...
...
@@ -206,22 +207,32 @@ void CameraSectionTest::_testDirty(void)
_cameraSection
->
setDirty
(
false
);
_spySection
->
clearAllSignals
();
// Check the remaining items that should set dirty bit
// dirty SHOULD NOT change if pitch or yaw is changed while specifyGimbal IS NOT set
_cameraSection
->
setSpecifyGimbal
(
false
);
_cameraSection
->
setDirty
(
false
);
_spySection
->
clearAllSignals
();
_cameraSection
->
gimbalPitch
()
->
setRawValue
(
_cameraSection
->
gimbalPitch
()
->
rawValue
().
toDouble
()
+
1
);
_cameraSection
->
gimbalYaw
()
->
setRawValue
(
_cameraSection
->
gimbalYaw
()
->
rawValue
().
toDouble
()
+
1
);
QVERIFY
(
_spySection
->
checkNoSignalByMask
(
dirtyChangedMask
));
QCOMPARE
(
_cameraSection
->
dirty
(),
false
);
// dirty SHOULD change if pitch or yaw is changed while specifyGimbal IS set
_cameraSection
->
setSpecifyGimbal
(
true
);
_cameraSection
->
setDirty
(
false
);
_spySection
->
clearAllSignals
();
_cameraSection
->
gimbalPitch
()
->
setRawValue
(
_cameraSection
->
gimbalPitch
()
->
rawValue
().
toDouble
()
+
1
);
QVERIFY
(
_spySection
->
checkSignalByMask
(
dirtyChangedMask
));
QCOMPARE
(
_spySection
->
pullBoolFromSignalIndex
(
dirtyChangedIndex
),
true
);
QCOMPARE
(
_cameraSection
->
dirty
(),
true
);
_cameraSection
->
setDirty
(
false
);
_spySection
->
clearAllSignals
();
_cameraSection
->
gimbalYaw
()
->
setRawValue
(
_cameraSection
->
gimbalPitch
()
->
rawValue
().
toDouble
()
+
1
);
_cameraSection
->
gimbalYaw
()
->
setRawValue
(
_cameraSection
->
gimbalYaw
()
->
rawValue
().
toDouble
()
+
1
);
QVERIFY
(
_spySection
->
checkSignalByMask
(
dirtyChangedMask
));
QCOMPARE
(
_spySection
->
pullBoolFromSignalIndex
(
dirtyChangedIndex
),
true
);
QCOMPARE
(
_cameraSection
->
dirty
(),
true
);
_cameraSection
->
setDirty
(
false
);
_spySection
->
clearAllSignals
();
// Check the remaining items that should set dirty bit
_cameraSection
->
cameraAction
()
->
setRawValue
(
_cameraSection
->
cameraAction
()
->
rawValue
().
toInt
()
+
1
);
QVERIFY
(
_spySection
->
checkSignalByMask
(
dirtyChangedMask
));
QCOMPARE
(
_spySection
->
pullBoolFromSignalIndex
(
dirtyChangedIndex
),
true
);
...
...
@@ -1081,3 +1092,23 @@ void CameraSectionTest::_testScanForMultipleItems(void)
}
}
}
void
CameraSectionTest
::
_testSpecifiedGimbalValuesChanged
(
void
)
{
// specifiedGimbal[Yaw|Pitch]Changed SHOULD NOT signal if values are changed when specifyGimbal IS NOT set
_cameraSection
->
setSpecifyGimbal
(
false
);
_spyCamera
->
clearAllSignals
();
_cameraSection
->
gimbalYaw
()
->
setRawValue
(
_cameraSection
->
gimbalYaw
()
->
rawValue
().
toDouble
()
+
1
);
QVERIFY
(
_spyCamera
->
checkNoSignalByMask
(
specifiedGimbalYawChangedMask
));
_cameraSection
->
gimbalPitch
()
->
setRawValue
(
_cameraSection
->
gimbalPitch
()
->
rawValue
().
toDouble
()
+
1
);
QVERIFY
(
_spyCamera
->
checkNoSignalByMask
(
specifiedGimbalPitchChangedMask
));
// specifiedGimbal[Yaw|Pitch]Changed SHOULD signal if values are changed when specifyGimbal IS set
_cameraSection
->
setSpecifyGimbal
(
true
);
_spyCamera
->
clearAllSignals
();
_cameraSection
->
gimbalYaw
()
->
setRawValue
(
_cameraSection
->
gimbalYaw
()
->
rawValue
().
toDouble
()
+
1
);
QVERIFY
(
_spyCamera
->
checkSignalByMask
(
specifiedGimbalYawChangedMask
));
_spyCamera
->
clearAllSignals
();
_cameraSection
->
gimbalPitch
()
->
setRawValue
(
_cameraSection
->
gimbalPitch
()
->
rawValue
().
toDouble
()
+
1
);
QVERIFY
(
_spyCamera
->
checkSignalByMask
(
specifiedGimbalPitchChangedMask
));
}
src/MissionManager/CameraSectionTest.h
View file @
52f51265
...
...
@@ -24,20 +24,21 @@ public:
void
cleanup
(
void
)
override
;
private
slots
:
void
_testDirty
(
void
);
void
_testSettingsAvailable
(
void
);
void
_checkAvailable
(
void
);
void
_testItemCount
(
void
);
void
_testAppendSectionItems
(
void
);
void
_testScanForGimbalSection
(
void
);
void
_testScanForPhotoIntervalTimeSection
(
void
);
void
_testScanForPhotoIntervalDistanceSection
(
void
);
void
_testScanForStartVideoSection
(
void
);
void
_testScanForStopVideoSection
(
void
);
void
_testScanForStopImageSection
(
void
);
void
_testScanForCameraModeSection
(
void
);
void
_testScanForTakePhotoSection
(
void
);
void
_testScanForMultipleItems
(
void
);
void
_testDirty
(
void
);
void
_testSettingsAvailable
(
void
);
void
_checkAvailable
(
void
);
void
_testItemCount
(
void
);
void
_testAppendSectionItems
(
void
);
void
_testScanForGimbalSection
(
void
);
void
_testScanForPhotoIntervalTimeSection
(
void
);
void
_testScanForPhotoIntervalDistanceSection
(
void
);
void
_testScanForStartVideoSection
(
void
);
void
_testScanForStopVideoSection
(
void
);
void
_testScanForStopImageSection
(
void
);
void
_testScanForCameraModeSection
(
void
);
void
_testScanForTakePhotoSection
(
void
);
void
_testScanForMultipleItems
(
void
);
void
_testSpecifiedGimbalValuesChanged
(
void
);
private:
void
_createSpy
(
CameraSection
*
cameraSection
,
MultiSignalSpy
**
cameraSpy
);
...
...
@@ -47,14 +48,16 @@ private:
enum
{
specifyGimbalChangedIndex
=
0
,
specifiedGimbalYawChangedIndex
,
specifiedGimbalPitchChangedIndex
,
specifyCameraModeChangedIndex
,
maxSignalIndex
,
};
enum
{
specifyGimbalChangedMask
=
1
<<
specifyGimbalChangedIndex
,
specifiedGimbalYawChangedMask
=
1
<<
specifiedGimbalYawChangedIndex
,
specifyCameraModeChangedMask
=
1
<<
specifyCameraModeChangedIndex
,
specifyGimbalChangedMask
=
1
<<
specifyGimbalChangedIndex
,
specifiedGimbalYawChangedMask
=
1
<<
specifiedGimbalYawChangedIndex
,
specifiedGimbalPitchChangedMask
=
1
<<
specifiedGimbalPitchChangedIndex
,
specifyCameraModeChangedMask
=
1
<<
specifyCameraModeChangedIndex
,
};
static
const
size_t
cCameraSignals
=
maxSignalIndex
;
...
...
src/MissionManager/FixedWingLandingComplexItem.h
View file @
52f51265
...
...
@@ -77,6 +77,7 @@ public:
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
double
specifiedFlightSpeed
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalYaw
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalPitch
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
;
...
...
src/MissionManager/MissionController.cc
View file @
52f51265
...
...
@@ -91,6 +91,7 @@ void MissionController::_resetMissionFlightStatus(void)
_missionFlightStatus
.
vehicleSpeed
=
_controllerVehicle
->
multiRotor
()
||
_managerVehicle
->
vtol
()
?
_missionFlightStatus
.
hoverSpeed
:
_missionFlightStatus
.
cruiseSpeed
;
_missionFlightStatus
.
vehicleYaw
=
0.0
;
_missionFlightStatus
.
gimbalYaw
=
std
::
numeric_limits
<
double
>::
quiet_NaN
();
_missionFlightStatus
.
gimbalPitch
=
std
::
numeric_limits
<
double
>::
quiet_NaN
();
// Battery information
...
...
@@ -355,6 +356,7 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
newItem
->
missionItem
().
setParam7
(
prevAltitude
);
}
}
newItem
->
setMissionFlightStatus
(
_missionFlightStatus
);
_visualItems
->
insert
(
i
,
newItem
);
_recalcAll
();
...
...
@@ -1227,12 +1229,13 @@ void MissionController::_recalcMissionFlightStatus()
}
// Look for gimbal change
if
(
_managerVehicle
->
vehicleYawsToNextWaypointInMission
())
{
// We current only support gimbal display in this mode
double
gimbalYaw
=
item
->
specifiedGimbalYaw
();
if
(
!
qIsNaN
(
gimbalYaw
))
{
_missionFlightStatus
.
gimbalYaw
=
gimbalYaw
;
}
double
gimbalYaw
=
item
->
specifiedGimbalYaw
();
if
(
!
qIsNaN
(
gimbalYaw
))
{
_missionFlightStatus
.
gimbalYaw
=
gimbalYaw
;
}
double
gimbalPitch
=
item
->
specifiedGimbalPitch
();
if
(
!
qIsNaN
(
gimbalPitch
))
{
_missionFlightStatus
.
gimbalPitch
=
gimbalPitch
;
}
if
(
i
==
0
)
{
...
...
@@ -1511,6 +1514,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem)
connect
(
visualItem
,
&
VisualMissionItem
::
exitCoordinateHasRelativeAltitudeChanged
,
this
,
&
MissionController
::
_recalcWaypointLines
);
connect
(
visualItem
,
&
VisualMissionItem
::
specifiedFlightSpeedChanged
,
this
,
&
MissionController
::
_recalcMissionFlightStatus
);
connect
(
visualItem
,
&
VisualMissionItem
::
specifiedGimbalYawChanged
,
this
,
&
MissionController
::
_recalcMissionFlightStatus
);
connect
(
visualItem
,
&
VisualMissionItem
::
specifiedGimbalPitchChanged
,
this
,
&
MissionController
::
_recalcMissionFlightStatus
);
connect
(
visualItem
,
&
VisualMissionItem
::
terrainAltitudeChanged
,
this
,
&
MissionController
::
_recalcMissionFlightStatus
);
connect
(
visualItem
,
&
VisualMissionItem
::
lastSequenceNumberChanged
,
this
,
&
MissionController
::
_recalcSequence
);
...
...
src/MissionManager/MissionController.h
View file @
52f51265
...
...
@@ -54,6 +54,7 @@ public:
double
vehicleSpeed
;
///< Either cruise or hover speed based on vehicle type and vtol state
double
vehicleYaw
;
double
gimbalYaw
;
///< NaN signals yaw was never changed
double
gimbalPitch
;
///< NaN signals pitch was never changed
int
mAhBattery
;
///< 0 for not available
double
hoverAmps
;
///< Amp consumption during hover
double
cruiseAmps
;
///< Amp consumption during cruise
...
...
src/MissionManager/MissionItem.cc
View file @
52f51265
...
...
@@ -52,6 +52,7 @@ MissionItem::MissionItem(QObject* parent)
setAutoContinue
(
true
);
connect
(
&
_param1Fact
,
&
Fact
::
rawValueChanged
,
this
,
&
MissionItem
::
_param1Changed
);
connect
(
&
_param2Fact
,
&
Fact
::
rawValueChanged
,
this
,
&
MissionItem
::
_param2Changed
);
connect
(
&
_param3Fact
,
&
Fact
::
rawValueChanged
,
this
,
&
MissionItem
::
_param3Changed
);
}
...
...
@@ -442,6 +443,27 @@ double MissionItem::specifiedGimbalYaw(void) const
return
gimbalYaw
;
}
double
MissionItem
::
specifiedGimbalPitch
(
void
)
const
{
double
gimbalPitch
=
std
::
numeric_limits
<
double
>::
quiet_NaN
();
if
(
_commandFact
.
rawValue
().
toInt
()
==
MAV_CMD_DO_MOUNT_CONTROL
&&
_param7Fact
.
rawValue
().
toInt
()
==
MAV_MOUNT_MODE_MAVLINK_TARGETING
)
{
gimbalPitch
=
_param1Fact
.
rawValue
().
toDouble
();
}
return
gimbalPitch
;
}
void
MissionItem
::
_param1Changed
(
QVariant
value
)
{
Q_UNUSED
(
value
);
double
gimbalPitch
=
specifiedGimbalPitch
();
if
(
!
qIsNaN
(
gimbalPitch
))
{
emit
specifiedGimbalPitchChanged
(
gimbalPitch
);
}
}
void
MissionItem
::
_param2Changed
(
QVariant
value
)
{
Q_UNUSED
(
value
);
...
...
src/MissionManager/MissionItem.h
View file @
52f51265
...
...
@@ -82,6 +82,9 @@ public:
/// @return Flight gimbal yaw change value if this item supports it. If not it returns NaN.
double
specifiedGimbalYaw
(
void
)
const
;
/// @return Flight gimbal pitch change value if this item supports it. If not it returns NaN.
double
specifiedGimbalPitch
(
void
)
const
;
void
setCommand
(
MAV_CMD
command
);
void
setSequenceNumber
(
int
sequenceNumber
);
void
setIsCurrentItem
(
bool
isCurrentItem
);
...
...
@@ -107,10 +110,12 @@ signals:
void
sequenceNumberChanged
(
int
sequenceNumber
);
void
specifiedFlightSpeedChanged
(
double
flightSpeed
);
void
specifiedGimbalYawChanged
(
double
gimbalYaw
);
void
specifiedGimbalPitchChanged
(
double
gimbalPitch
);
private
slots
:
void
_param2Changed
(
QVariant
value
);
void
_param3Changed
(
QVariant
value
);
void
_param1Changed
(
QVariant
value
);
void
_param2Changed
(
QVariant
value
);
void
_param3Changed
(
QVariant
value
);
private:
bool
_convertJsonV1ToV2
(
const
QJsonObject
&
json
,
QJsonObject
&
v2Json
,
QString
&
errorString
);
...
...
src/MissionManager/MissionSettingsItem.cc
View file @
52f51265
...
...
@@ -63,8 +63,9 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
connect
(
&
_cameraSection
,
&
CameraSection
::
dirtyChanged
,
this
,
&
MissionSettingsItem
::
_sectionDirtyChanged
);
connect
(
&
_speedSection
,
&
SpeedSection
::
dirtyChanged
,
this
,
&
MissionSettingsItem
::
_sectionDirtyChanged
);
connect
(
&
_cameraSection
,
&
CameraSection
::
specifiedGimbalYawChanged
,
this
,
&
MissionSettingsItem
::
specifiedGimbalYawChanged
);
connect
(
&
_speedSection
,
&
SpeedSection
::
specifiedFlightSpeedChanged
,
this
,
&
MissionSettingsItem
::
specifiedFlightSpeedChanged
);
connect
(
&
_cameraSection
,
&
CameraSection
::
specifiedGimbalYawChanged
,
this
,
&
MissionSettingsItem
::
specifiedGimbalYawChanged
);
connect
(
&
_cameraSection
,
&
CameraSection
::
specifiedGimbalPitchChanged
,
this
,
&
MissionSettingsItem
::
specifiedGimbalPitchChanged
);
connect
(
&
_speedSection
,
&
SpeedSection
::
specifiedFlightSpeedChanged
,
this
,
&
MissionSettingsItem
::
specifiedFlightSpeedChanged
);
}
int
MissionSettingsItem
::
lastSequenceNumber
(
void
)
const
...
...
@@ -259,6 +260,11 @@ double MissionSettingsItem::specifiedGimbalYaw(void)
return
_cameraSection
.
specifyGimbal
()
?
_cameraSection
.
gimbalYaw
()
->
rawValue
().
toDouble
()
:
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
MissionSettingsItem
::
specifiedGimbalPitch
(
void
)
{
return
_cameraSection
.
specifyGimbal
()
?
_cameraSection
.
gimbalPitch
()
->
rawValue
().
toDouble
()
:
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
void
MissionSettingsItem
::
_updateAltitudeInCoordinate
(
QVariant
value
)
{
double
newAltitude
=
value
.
toDouble
();
...
...
src/MissionManager/MissionSettingsItem.h
View file @
52f51265
...
...
@@ -73,6 +73,7 @@ public:
QGeoCoordinate
exitCoordinate
(
void
)
const
final
{
return
_plannedHomePositionCoordinate
;
}
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
double
specifiedGimbalYaw
(
void
)
final
;
double
specifiedGimbalPitch
(
void
)
final
;
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
{
Q_UNUSED
(
newAltitude
);
/* no action */
}
double
specifiedFlightSpeed
(
void
)
final
;
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
52f51265
...
...
@@ -717,6 +717,11 @@ double SimpleMissionItem::specifiedGimbalYaw(void)
return
_cameraSection
->
available
()
?
_cameraSection
->
specifiedGimbalYaw
()
:
missionItem
().
specifiedGimbalYaw
();
}
double
SimpleMissionItem
::
specifiedGimbalPitch
(
void
)
{
return
_cameraSection
->
available
()
?
_cameraSection
->
specifiedGimbalPitch
()
:
missionItem
().
specifiedGimbalPitch
();
}
bool
SimpleMissionItem
::
scanForSections
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
,
Vehicle
*
vehicle
)
{
bool
sectionFound
=
false
;
...
...
@@ -754,10 +759,12 @@ void SimpleMissionItem::_updateOptionalSections(void)
_speedSection
->
setAvailable
(
true
);
}
connect
(
_cameraSection
,
&
CameraSection
::
dirtyChanged
,
this
,
&
SimpleMissionItem
::
_sectionDirtyChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
itemCountChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
connect
(
_cameraSection
,
&
CameraSection
::
availableChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
specifiedGimbalYawChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
dirtyChanged
,
this
,
&
SimpleMissionItem
::
_sectionDirtyChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
itemCountChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
connect
(
_cameraSection
,
&
CameraSection
::
availableChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
availableChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalPitchChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
specifiedGimbalPitchChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalPitchChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
specifiedGimbalYawChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_speedSection
,
&
SpeedSection
::
dirtyChanged
,
this
,
&
SimpleMissionItem
::
_sectionDirtyChanged
);
connect
(
_speedSection
,
&
SpeedSection
::
itemCountChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
...
...
@@ -813,3 +820,20 @@ void SimpleMissionItem::applyNewAltitude(double newAltitude)
}
}
}
void
SimpleMissionItem
::
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
{
// If user has not already set speed/gimbal, set defaults from previous items.
VisualMissionItem
::
setMissionFlightStatus
(
missionFlightStatus
);
if
(
_speedSection
->
available
()
&&
!
_speedSection
->
specifyFlightSpeed
()
&&
!
qFuzzyCompare
(
_speedSection
->
flightSpeed
()
->
rawValue
().
toDouble
(),
missionFlightStatus
.
vehicleSpeed
))
{
_speedSection
->
flightSpeed
()
->
setRawValue
(
missionFlightStatus
.
vehicleSpeed
);
}
if
(
_cameraSection
->
available
()
&&
!
_cameraSection
->
specifyGimbal
())
{
if
(
!
qIsNaN
(
missionFlightStatus
.
gimbalYaw
)
&&
!
qFuzzyCompare
(
_cameraSection
->
gimbalYaw
()
->
rawValue
().
toDouble
(),
missionFlightStatus
.
gimbalYaw
))
{
_cameraSection
->
gimbalYaw
()
->
setRawValue
(
missionFlightStatus
.
gimbalYaw
);
}
if
(
!
qIsNaN
(
missionFlightStatus
.
gimbalPitch
)
&&
!
qFuzzyCompare
(
_cameraSection
->
gimbalPitch
()
->
rawValue
().
toDouble
(),
missionFlightStatus
.
gimbalPitch
))
{
_cameraSection
->
gimbalPitch
()
->
setRawValue
(
missionFlightStatus
.
gimbalPitch
);
}
}
}
src/MissionManager/SimpleMissionItem.h
View file @
52f51265
...
...
@@ -102,9 +102,11 @@ public:
int
sequenceNumber
(
void
)
const
final
{
return
_missionItem
.
sequenceNumber
();
}
double
specifiedFlightSpeed
(
void
)
final
;
double
specifiedGimbalYaw
(
void
)
final
;
double
specifiedGimbalPitch
(
void
)
final
;
QString
mapVisualQML
(
void
)
const
final
{
return
QStringLiteral
(
"SimpleItemMapVisual.qml"
);
}
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
;
void
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
final
;
bool
coordinateHasRelativeAltitude
(
void
)
const
final
{
return
_missionItem
.
relativeAltitude
();
}
bool
exitCoordinateHasRelativeAltitude
(
void
)
const
final
{
return
coordinateHasRelativeAltitude
();
}
...
...
src/MissionManager/SpeedSection.cc
View file @
52f51265
...
...
@@ -39,7 +39,7 @@ SpeedSection::SpeedSection(Vehicle* vehicle, QObject* parent)
_flightSpeedFact
.
setRawValue
(
flightSpeed
);
connect
(
this
,
&
SpeedSection
::
specifyFlightSpeedChanged
,
this
,
&
SpeedSection
::
settingsSpecifiedChanged
);
connect
(
&
_flightSpeedFact
,
&
Fact
::
valueChanged
,
this
,
&
SpeedSection
::
_
setDirty
);
connect
(
&
_flightSpeedFact
,
&
Fact
::
valueChanged
,
this
,
&
SpeedSection
::
_
flightSpeedChanged
);
connect
(
this
,
&
SpeedSection
::
specifyFlightSpeedChanged
,
this
,
&
SpeedSection
::
_updateSpecifiedFlightSpeed
);
connect
(
&
_flightSpeedFact
,
&
Fact
::
valueChanged
,
this
,
&
SpeedSection
::
_updateSpecifiedFlightSpeed
);
...
...
@@ -60,11 +60,6 @@ void SpeedSection::setAvailable(bool available)
}
}
void
SpeedSection
::
_setDirty
(
void
)
{
setDirty
(
true
);
}
void
SpeedSection
::
setDirty
(
bool
dirty
)
{
if
(
_dirty
!=
dirty
)
{
...
...
@@ -146,6 +141,16 @@ double SpeedSection::specifiedFlightSpeed(void) const
void
SpeedSection
::
_updateSpecifiedFlightSpeed
(
void
)
{
emit
specifiedFlightSpeedChanged
(
specifiedFlightSpeed
());
if
(
_specifyFlightSpeed
)
{
emit
specifiedFlightSpeedChanged
(
specifiedFlightSpeed
());
}
}
void
SpeedSection
::
_flightSpeedChanged
(
void
)
{
// We only set the dirty bit if specify flight speed it set. This allows us to change defaults for flight speed
// without affecting dirty.
if
(
_specifyFlightSpeed
)
{
setDirty
(
true
);
}
}
src/MissionManager/SpeedSection.h
View file @
52f51265
...
...
@@ -46,8 +46,8 @@ signals:
void
specifiedFlightSpeedChanged
(
double
flightSpeed
);
private
slots
:
void
_setDirty
(
void
);
void
_updateSpecifiedFlightSpeed
(
void
);
void
_flightSpeedChanged
(
void
);
private:
bool
_available
;
...
...
src/MissionManager/SpeedSectionTest.cc
View file @
52f51265
...
...
@@ -73,7 +73,18 @@ void SpeedSectionTest::_testDirty(void)
QCOMPARE
(
_speedSection
->
dirty
(),
false
);
_spySection
->
clearAllSignals
();
// Check the remaining items that should set dirty bit
// Flight speed change should only signal if specifyFlightSpeed is set
_speedSection
->
setSpecifyFlightSpeed
(
false
);
_speedSection
->
setDirty
(
false
);
_spySection
->
clearAllSignals
();
_speedSection
->
flightSpeed
()
->
setRawValue
(
_speedSection
->
flightSpeed
()
->
rawValue
().
toDouble
()
+
1
);
QVERIFY
(
_spySection
->
checkNoSignalByMask
(
dirtyChangedMask
));
QCOMPARE
(
_speedSection
->
dirty
(),
false
);
_speedSection
->
setSpecifyFlightSpeed
(
true
);
_speedSection
->
setDirty
(
false
);
_spySection
->
clearAllSignals
();
_speedSection
->
flightSpeed
()
->
setRawValue
(
_speedSection
->
flightSpeed
()
->
rawValue
().
toDouble
()
+
1
);
QVERIFY
(
_spySection
->
checkSignalByMask
(
dirtyChangedMask
));
QCOMPARE
(
_spySection
->
pullBoolFromSignalIndex
(
dirtyChangedIndex
),
true
);
...
...
@@ -264,3 +275,18 @@ void SpeedSectionTest::_testScanForSection(void)
visualItems
.
clear
();
scanIndex
=
0
;
}
void
SpeedSectionTest
::
_testSpecifiedFlightSpeedChanged
(
void
)
{
// specifiedFlightSpeedChanged SHOULD NOT signal if flight speed is changed when specifyFlightSpeed IS NOT set
_speedSection
->
setSpecifyFlightSpeed
(
false
);
_spySpeed
->
clearAllSignals
();
_speedSection
->
flightSpeed
()
->
setRawValue
(
_speedSection
->
flightSpeed
()
->
rawValue
().
toDouble
()
+
1
);
QVERIFY
(
_spySpeed
->
checkNoSignalByMask
(
specifiedFlightSpeedChangedMask
));
// specifiedFlightSpeedChanged SHOULD signal if flight speed is changed when specifyFlightSpeed IS set
_speedSection
->
setSpecifyFlightSpeed
(
true
);
_spySpeed
->
clearAllSignals
();
_speedSection
->
flightSpeed
()
->
setRawValue
(
_speedSection
->
flightSpeed
()
->
rawValue
().
toDouble
()
+
1
);
QVERIFY
(
_spySpeed
->
checkSignalByMask
(
specifiedFlightSpeedChangedMask
));
}
src/MissionManager/SpeedSectionTest.h
View file @
52f51265
...
...
@@ -24,12 +24,13 @@ public:
void
cleanup
(
void
)
override
;
private
slots
:
void
_testDirty
(
void
);
void
_testSettingsAvailable
(
void
);
void
_checkAvailable
(
void
);
void
_testItemCount
(
void
);
void
_testAppendSectionItems
(
void
);
void
_testScanForSection
(
void
);
void
_testDirty
(
void
);
void
_testSettingsAvailable
(
void
);
void
_checkAvailable
(
void
);
void
_testItemCount
(
void
);
void
_testAppendSectionItems
(
void
);
void
_testScanForSection
(
void
);
void
_testSpecifiedFlightSpeedChanged
(
void
);
private:
void
_createSpy
(
SpeedSection
*
speedSection
,
MultiSignalSpy
**
speedSpy
);
...
...
src/MissionManager/StructureScanComplexItem.h
View file @
52f51265
...
...
@@ -81,6 +81,7 @@ public:
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
double
specifiedFlightSpeed
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalYaw
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalPitch
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
;
...
...
src/MissionManager/SurveyMissionItem.h
View file @
52f51265
...
...
@@ -117,6 +117,7 @@ public:
int
sequenceNumber
(
void
)
const
final
{
return
_sequenceNumber
;
}
double
specifiedFlightSpeed
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalYaw
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalPitch
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
;
...
...
src/MissionManager/VisualMissionItem.h
View file @
52f51265
...
...
@@ -65,7 +65,8 @@ public:
Q_PROPERTY
(
QString
mapVisualQML
READ
mapVisualQML
CONSTANT
)
///< QMl code for map visuals
Q_PROPERTY
(
QmlObjectListModel
*
childItems
READ
childItems
CONSTANT
)
Q_PROPERTY
(
double
specifiedFlightSpeed
READ
specifiedFlightSpeed
NOTIFY
specifiedFlightSpeedChanged
)
///< NaN if this item does not specify flight speed
Q_PROPERTY
(
double
specifiedGimbalYaw
READ
specifiedGimbalYaw
NOTIFY
specifiedGimbalYawChanged
)
///< NaN if this item goes not specify gimbal yaw
Q_PROPERTY
(
double
specifiedGimbalYaw
READ
specifiedGimbalYaw
NOTIFY
specifiedGimbalYawChanged
)
///< Gimbal yaw, NaN for not specified
Q_PROPERTY
(
double
specifiedGimbalPitch
READ
specifiedGimbalPitch
NOTIFY
specifiedGimbalPitchChanged
)
///< Gimbal pitch, NaN for not specified
Q_PROPERTY
(
double
missionGimbalYaw
READ
missionGimbalYaw
NOTIFY
missionGimbalYawChanged
)
///< Current gimbal yaw state at this point in mission
Q_PROPERTY
(
double
missionVehicleYaw
READ
missionVehicleYaw
NOTIFY
missionVehicleYawChanged
)
///< Expected vehicle yaw at this point in mission
...
...
@@ -116,6 +117,7 @@ public:
virtual
int
sequenceNumber
(
void
)
const
=
0
;
virtual
double
specifiedFlightSpeed
(
void
)
=
0
;
virtual
double
specifiedGimbalYaw
(
void
)
=
0
;
virtual
double
specifiedGimbalPitch
(
void
)
=
0
;
/// Update item to mission flight status at point where this item appears in mission.
/// IMPORTANT: Overrides must call base class implementation
...
...
@@ -173,6 +175,7 @@ signals:
void
specifiesAltitudeOnlyChanged
(
void
);
void
specifiedFlightSpeedChanged
(
void
);
void
specifiedGimbalYawChanged
(
void
);
void
specifiedGimbalPitchChanged
(
void
);
void
lastSequenceNumberChanged
(
int
sequenceNumber
);
void
missionGimbalYawChanged
(
double
missionGimbalYaw
);
void
missionVehicleYawChanged
(
double
missionVehicleYaw
);
...
...
src/MissionManager/VisualMissionItemTest.cc
View file @
52f51265
...
...
@@ -43,6 +43,7 @@ void VisualMissionItemTest::init(void)
rgVisualItemSignals
[
specifiesAltitudeOnlyChangedIndex
]
=
SIGNAL
(
specifiesAltitudeOnlyChanged
());
rgVisualItemSignals
[
specifiedFlightSpeedChangedIndex
]
=
SIGNAL
(
specifiedFlightSpeedChanged
());
rgVisualItemSignals
[
specifiedGimbalYawChangedIndex
]
=
SIGNAL
(
specifiedGimbalYawChanged
());
rgVisualItemSignals
[
specifiedGimbalPitchChangedIndex
]
=
SIGNAL
(
specifiedGimbalPitchChanged
());
rgVisualItemSignals
[
lastSequenceNumberChangedIndex
]
=
SIGNAL
(
lastSequenceNumberChanged
(
int
));
rgVisualItemSignals
[
missionGimbalYawChangedIndex
]
=
SIGNAL
(
missionGimbalYawChanged
(
double
));
rgVisualItemSignals
[
missionVehicleYawChangedIndex
]
=
SIGNAL
(
missionVehicleYawChanged
(
double
));
...
...
src/MissionManager/VisualMissionItemTest.h
View file @
52f51265
...
...
@@ -49,6 +49,7 @@ protected:
specifiesAltitudeOnlyChangedIndex
,
specifiedFlightSpeedChangedIndex
,
specifiedGimbalYawChangedIndex
,
specifiedGimbalPitchChangedIndex
,
lastSequenceNumberChangedIndex
,
missionGimbalYawChangedIndex
,
missionVehicleYawChangedIndex
,
...
...
@@ -77,6 +78,7 @@ protected:
specifiesAltitudeOnlyChangedMask
=
1
<<
specifiesAltitudeOnlyChangedIndex
,
specifiedFlightSpeedChangedMask
=
1
<<
specifiedFlightSpeedChangedIndex
,
specifiedGimbalYawChangedMask
=
1
<<
specifiedGimbalYawChangedIndex
,
specifiedGimbalPitchChangedMask
=
1
<<
specifiedGimbalPitchChangedIndex
,
lastSequenceNumberChangedMask
=
1
<<
lastSequenceNumberChangedIndex
,
missionGimbalYawChangedMask
=
1
<<
missionGimbalYawChangedIndex
,
missionVehicleYawChangedMask
=
1
<<
missionVehicleYawChangedIndex
,
...
...
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