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
83a63f85
Commit
83a63f85
authored
Apr 17, 2017
by
Don Gagne
Committed by
GitHub
Apr 17, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #5007 from DonLakeFlyer/UniTestGimbal
Unit testing around gimbal visuals
parents
56f40014
bc135e96
Changes
12
Hide whitespace changes
Inline
Side-by-side
Showing
12 changed files
with
83 additions
and
19 deletions
+83
-19
ArduCopterFirmwarePlugin.cc
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+2
-2
PX4FirmwarePlugin.cc
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+2
-2
MissionItemIndicator.qml
src/FlightMap/MapItems/MissionItemIndicator.qml
+1
-1
MissionControllerTest.cc
src/MissionManager/MissionControllerTest.cc
+24
-0
MissionControllerTest.h
src/MissionManager/MissionControllerTest.h
+3
-0
MissionSettingsItem.h
src/MissionManager/MissionSettingsItem.h
+2
-2
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+7
-5
SimpleMissionItemTest.cc
src/MissionManager/SimpleMissionItemTest.cc
+28
-3
SimpleMissionItemTest.h
src/MissionManager/SimpleMissionItemTest.h
+3
-2
VisualMissionItem.h
src/MissionManager/VisualMissionItem.h
+0
-2
VisualMissionItemTest.cc
src/MissionManager/VisualMissionItemTest.cc
+8
-0
VisualMissionItemTest.h
src/MissionManager/VisualMissionItemTest.h
+3
-0
No files found.
src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
View file @
83a63f85
...
...
@@ -237,11 +237,11 @@ QString ArduCopterFirmwarePlugin::geoFenceRadiusParam(Vehicle* vehicle)
bool
ArduCopterFirmwarePlugin
::
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
{
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"WP_YAW_BEHAVIOR"
)))
{
if
(
!
vehicle
->
isOfflineEditingVehicle
()
&&
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"WP_YAW_BEHAVIOR"
)))
{
Fact
*
yawMode
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"WP_YAW_BEHAVIOR"
));
return
yawMode
&&
yawMode
->
rawValue
().
toInt
()
!=
0
;
}
return
fals
e
;
return
tru
e
;
}
void
ArduCopterFirmwarePlugin
::
missionFlightSpeedInfo
(
Vehicle
*
vehicle
,
double
&
hoverSpeed
,
double
&
cruiseSpeed
)
...
...
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
View file @
83a63f85
...
...
@@ -518,11 +518,11 @@ void PX4FirmwarePlugin::_handleAutopilotVersion(Vehicle* vehicle, mavlink_messag
bool
PX4FirmwarePlugin
::
vehicleYawsToNextWaypointInMission
(
const
Vehicle
*
vehicle
)
const
{
if
(
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"MIS_YAWMODE"
)))
{
if
(
!
vehicle
->
isOfflineEditingVehicle
()
&&
vehicle
->
parameterManager
()
->
parameterExists
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"MIS_YAWMODE"
)))
{
Fact
*
yawMode
=
vehicle
->
parameterManager
()
->
getParameter
(
FactSystem
::
defaultComponentId
,
QStringLiteral
(
"MIS_YAWMODE"
));
return
yawMode
&&
yawMode
->
rawValue
().
toInt
()
==
1
;
}
return
fals
e
;
return
tru
e
;
}
void
PX4FirmwarePlugin
::
missionFlightSpeedInfo
(
Vehicle
*
vehicle
,
double
&
hoverSpeed
,
double
&
cruiseSpeed
)
...
...
src/FlightMap/MapItems/MissionItemIndicator.qml
View file @
83a63f85
...
...
@@ -35,7 +35,7 @@ MapQuickItem {
index
:
missionItem
?
missionItem
.
sequenceNumber
:
0
gimbalYaw
:
missionItem
.
missionGimbalYaw
vehicleYaw
:
missionItem
.
missionVehicleYaw
showGimbalYaw
:
missionItem
.
showMissionGimbalYaw
showGimbalYaw
:
!
isNaN
(
missionItem
.
missionGimbalYaw
)
onClicked
:
_item
.
clicked
()
property
bool
_isCurrentItem
:
missionItem
?
missionItem
.
isCurrentItem
:
false
...
...
src/MissionManager/MissionControllerTest.cc
View file @
83a63f85
...
...
@@ -200,3 +200,27 @@ void MissionControllerTest::_setupVisualItemSignals(VisualMissionItem* visualIte
Q_CHECK_PTR
(
_multiSpyMissionItem
);
QCOMPARE
(
_multiSpyMissionItem
->
init
(
visualItem
,
_rgVisualItemSignals
,
_cVisualItemSignals
),
true
);
}
void
MissionControllerTest
::
_testGimbalRecalc
(
void
)
{
_initForFirmwareType
(
MAV_AUTOPILOT_PX4
);
_missionController
->
insertSimpleMissionItem
(
QGeoCoordinate
(
0
,
0
),
1
);
_missionController
->
insertSimpleMissionItem
(
QGeoCoordinate
(
0
,
0
),
2
);
_missionController
->
insertSimpleMissionItem
(
QGeoCoordinate
(
0
,
0
),
3
);
_missionController
->
insertSimpleMissionItem
(
QGeoCoordinate
(
0
,
0
),
4
);
// No specific gimbal yaw set yet
for
(
int
i
=
1
;
i
<
_missionController
->
visualItems
()
->
count
();
i
++
)
{
VisualMissionItem
*
visualItem
=
_missionController
->
visualItems
()
->
value
<
VisualMissionItem
*>
(
i
);
QVERIFY
(
qIsNaN
(
visualItem
->
missionGimbalYaw
()));
}
// Specify gimbal yaw on settings item should generate yaw on all items
MissionSettingsItem
*
settingsItem
=
_missionController
->
visualItems
()
->
value
<
MissionSettingsItem
*>
(
0
);
settingsItem
->
cameraSection
()
->
setSpecifyGimbal
(
true
);
settingsItem
->
cameraSection
()
->
gimbalYaw
()
->
setRawValue
(
0.0
);
for
(
int
i
=
1
;
i
<
_missionController
->
visualItems
()
->
count
();
i
++
)
{
VisualMissionItem
*
visualItem
=
_missionController
->
visualItems
()
->
value
<
VisualMissionItem
*>
(
i
);
QCOMPARE
(
visualItem
->
missionGimbalYaw
(),
0.0
);
}
}
src/MissionManager/MissionControllerTest.h
View file @
83a63f85
...
...
@@ -31,6 +31,9 @@ public:
private
slots
:
void
cleanup
(
void
);
void
_testGimbalRecalc
(
void
);
private:
void
_testEmptyVehicleAPM
(
void
);
void
_testEmptyVehiclePX4
(
void
);
void
_testAddWayppointAPM
(
void
);
...
...
src/MissionManager/MissionSettingsItem.h
View file @
83a63f85
...
...
@@ -33,8 +33,8 @@ public:
Fact
*
plannedHomePositionAltitude
(
void
)
{
return
&
_plannedHomePositionAltitudeFact
;
}
QObject
*
cameraSection
(
void
)
{
return
&
_cameraSection
;
}
QObject
*
speedSection
(
void
)
{
return
&
_speedSection
;
}
CameraSection
*
cameraSection
(
void
)
{
return
&
_cameraSection
;
}
SpeedSection
*
speedSection
(
void
)
{
return
&
_speedSection
;
}
/// Scans the loaded items for settings items
bool
scanForMissionSettings
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
83a63f85
...
...
@@ -80,9 +80,9 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, QObject* parent)
connect
(
&
_missionItem
,
&
MissionItem
::
specifiedFlightSpeedChanged
,
this
,
&
SimpleMissionItem
::
specifiedFlightSpeedChanged
);
connect
(
this
,
&
SimpleMissionItem
::
sequenceNumberChanged
,
this
,
&
SimpleMissionItem
::
lastSequenceNumberChanged
);
connect
(
this
,
&
SimpleMissionItem
::
cameraSectionChanged
,
this
,
&
SimpleMissionItem
::
_setDirtyFromSignal
);
connect
(
this
,
&
SimpleMissionItem
::
cameraSectionChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
connect
(
this
,
&
SimpleMissionItem
::
sequenceNumberChanged
,
this
,
&
SimpleMissionItem
::
lastSequenceNumberChanged
);
connect
(
this
,
&
SimpleMissionItem
::
cameraSectionChanged
,
this
,
&
SimpleMissionItem
::
_setDirtyFromSignal
);
connect
(
this
,
&
SimpleMissionItem
::
cameraSectionChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
}
SimpleMissionItem
::
SimpleMissionItem
(
Vehicle
*
vehicle
,
const
MissionItem
&
missionItem
,
QObject
*
parent
)
...
...
@@ -736,8 +736,10 @@ void SimpleMissionItem::_updateOptionalSections(void)
connect
(
_cameraSection
,
&
CameraSection
::
specifyGimbalChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_cameraSection
,
&
CameraSection
::
specifiedGimbalYawChanged
,
this
,
&
SimpleMissionItem
::
specifiedGimbalYawChanged
);
connect
(
_speedSection
,
&
CameraSection
::
dirtyChanged
,
this
,
&
SimpleMissionItem
::
_sectionDirtyChanged
);
connect
(
_speedSection
,
&
CameraSection
::
itemCountChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
connect
(
_speedSection
,
&
SpeedSection
::
dirtyChanged
,
this
,
&
SimpleMissionItem
::
_sectionDirtyChanged
);
connect
(
_speedSection
,
&
SpeedSection
::
itemCountChanged
,
this
,
&
SimpleMissionItem
::
_updateLastSequenceNumber
);
connect
(
_speedSection
,
&
SpeedSection
::
specifyFlightSpeedChanged
,
this
,
&
SimpleMissionItem
::
specifiedFlightSpeedChanged
);
connect
(
_speedSection
->
flightSpeed
(),
&
Fact
::
rawValueChanged
,
this
,
&
SimpleMissionItem
::
specifiedFlightSpeedChanged
);
emit
cameraSectionChanged
(
_cameraSection
);
emit
speedSectionChanged
(
_speedSection
);
...
...
src/MissionManager/SimpleMissionItemTest.cc
View file @
83a63f85
...
...
@@ -107,8 +107,7 @@ void SimpleMissionItemTest::init(void)
_spySimpleItem
=
new
MultiSignalSpy
();
QCOMPARE
(
_spySimpleItem
->
init
(
_simpleItem
,
rgSimpleItemSignals
,
cSimpleItemSignals
),
true
);
_spyVisualItem
=
new
MultiSignalSpy
();
QCOMPARE
(
_spyVisualItem
->
init
(
_simpleItem
,
rgVisualItemSignals
,
cVisualItemSignals
),
true
);
VisualMissionItemTest
::
_createSpy
(
_simpleItem
,
&
_spyVisualItem
);
}
void
SimpleMissionItemTest
::
cleanup
(
void
)
...
...
@@ -257,7 +256,33 @@ void SimpleMissionItemTest::_testSignals(void)
QVERIFY
(
_spyVisualItem
->
checkSignalsByMask
(
commandNameChangedMask
|
dirtyChangedMask
|
coordinateChangedMask
));
}
void
SimpleMissionItemTest
::
_testCameraSection
Signals
(
void
)
void
SimpleMissionItemTest
::
_testCameraSection
(
void
)
{
// No gimbal yaw to start with
QVERIFY
(
qIsNaN
(
_simpleItem
->
specifiedGimbalYaw
()));
QVERIFY
(
qIsNaN
(
_simpleItem
->
missionGimbalYaw
()));
QCOMPARE
(
_simpleItem
->
dirty
(),
false
);
double
gimbalYaw
=
10.1234
;
_simpleItem
->
cameraSection
()
->
setSpecifyGimbal
(
true
);
_simpleItem
->
cameraSection
()
->
gimbalYaw
()
->
setRawValue
(
gimbalYaw
);
QCOMPARE
(
_simpleItem
->
specifiedGimbalYaw
(),
gimbalYaw
);
QVERIFY
(
qIsNaN
(
_simpleItem
->
missionGimbalYaw
()));
QCOMPARE
(
_spyVisualItem
->
checkSignalsByMask
(
specifiedGimbalYawChangedMask
),
true
);
QCOMPARE
(
_simpleItem
->
dirty
(),
true
);
}
void
SimpleMissionItemTest
::
_testSpeedSection
(
void
)
{
// No flight speed
QVERIFY
(
qIsNaN
(
_simpleItem
->
specifiedFlightSpeed
()));
QCOMPARE
(
_simpleItem
->
dirty
(),
false
);
double
flightSpeed
=
10.1234
;
_simpleItem
->
speedSection
()
->
setSpecifyFlightSpeed
(
true
);
_simpleItem
->
speedSection
()
->
flightSpeed
()
->
setRawValue
(
flightSpeed
);
QCOMPARE
(
_simpleItem
->
specifiedFlightSpeed
(),
flightSpeed
);
QCOMPARE
(
_spyVisualItem
->
checkSignalsByMask
(
specifiedFlightSpeedChangedMask
),
true
);
QCOMPARE
(
_simpleItem
->
dirty
(),
true
);
}
src/MissionManager/SimpleMissionItemTest.h
View file @
83a63f85
...
...
@@ -25,10 +25,11 @@ public:
private
slots
:
void
_testSignals
(
void
);
void
_testCameraSectionSignals
(
void
);
void
_testEditorFacts
(
void
);
void
_testDefaultValues
(
void
);
void
_testCameraSection
(
void
);
void
_testSpeedSection
(
void
);
private:
enum
{
commandChangedIndex
=
0
,
...
...
src/MissionManager/VisualMissionItem.h
View file @
83a63f85
...
...
@@ -67,7 +67,6 @@ public:
Q_PROPERTY
(
double
specifiedGimbalYaw
READ
specifiedGimbalYaw
NOTIFY
specifiedGimbalYawChanged
)
///< NaN if this item goes not specify gimbal yaw
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
Q_PROPERTY
(
double
showMissionGimbalYaw
READ
showMissionGimbalYaw
NOTIFY
missionGimbalYawChanged
)
///< true: Show gimbal yaw position on map indicators
// The following properties are calculated/set by the MissionController recalc methods
...
...
@@ -143,7 +142,6 @@ public:
double
missionGimbalYaw
(
void
)
const
{
return
_missionGimbalYaw
;
}
double
missionVehicleYaw
(
void
)
const
{
return
_missionVehicleYaw
;
}
bool
showMissionGimbalYaw
(
void
)
const
{
return
!
qIsNaN
(
_missionGimbalYaw
);
}
void
setMissionVehicleYaw
(
double
vehicleYaw
);
static
const
char
*
jsonTypeKey
;
///< Json file attribute which specifies the item type
...
...
src/MissionManager/VisualMissionItemTest.cc
View file @
83a63f85
...
...
@@ -56,3 +56,11 @@ void VisualMissionItemTest::cleanup(void)
delete
_offlineVehicle
;
UnitTest
::
cleanup
();
}
void
VisualMissionItemTest
::
_createSpy
(
SimpleMissionItem
*
simpleItem
,
MultiSignalSpy
**
visualSpy
)
{
*
visualSpy
=
NULL
;
MultiSignalSpy
*
spy
=
new
MultiSignalSpy
();
QCOMPARE
(
spy
->
init
(
simpleItem
,
rgVisualItemSignals
,
cVisualItemSignals
),
true
);
*
visualSpy
=
spy
;
}
src/MissionManager/VisualMissionItemTest.h
View file @
83a63f85
...
...
@@ -12,6 +12,7 @@
#include "UnitTest.h"
#include "TCPLink.h"
#include "MultiSignalSpy.h"
#include "SimpleMissionItem.h"
#include <QGeoCoordinate>
...
...
@@ -27,6 +28,8 @@ public:
void
cleanup
(
void
)
override
;
protected:
void
_createSpy
(
SimpleMissionItem
*
simpleItem
,
MultiSignalSpy
**
visualSpy
);
enum
{
altDifferenceChangedIndex
=
0
,
altPercentChangedIndex
,
...
...
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