From bc135e96a923026f5f7a1408bb38bfe58b71f117 Mon Sep 17 00:00:00 2001
From: Don Gagne <Don@laptop-3.local>
Date: Mon, 17 Apr 2017 19:01:05 -0700
Subject: [PATCH] Unit testing around gimbal visuals

Fixed found bugs
---
 src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc |  4 +--
 src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc        |  4 +--
 src/FlightMap/MapItems/MissionItemIndicator.qml    |  2 +-
 src/MissionManager/MissionControllerTest.cc        | 24 +++++++++++++++++
 src/MissionManager/MissionControllerTest.h         |  3 +++
 src/MissionManager/MissionSettingsItem.h           |  4 +--
 src/MissionManager/SimpleMissionItem.cc            | 12 +++++----
 src/MissionManager/SimpleMissionItemTest.cc        | 31 +++++++++++++++++++---
 src/MissionManager/SimpleMissionItemTest.h         |  5 ++--
 src/MissionManager/VisualMissionItem.h             |  2 --
 src/MissionManager/VisualMissionItemTest.cc        |  8 ++++++
 src/MissionManager/VisualMissionItemTest.h         |  3 +++
 12 files changed, 83 insertions(+), 19 deletions(-)

diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
index ca33b2e..57094a7 100644
--- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
@@ -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 false;
+    return true;
 }
 
 void ArduCopterFirmwarePlugin::missionFlightSpeedInfo(Vehicle* vehicle, double& hoverSpeed, double& cruiseSpeed)
diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
index 669fc01..ce62235 100644
--- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
+++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
@@ -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 false;
+    return true;
 }
 
 void PX4FirmwarePlugin::missionFlightSpeedInfo(Vehicle* vehicle, double& hoverSpeed, double& cruiseSpeed)
diff --git a/src/FlightMap/MapItems/MissionItemIndicator.qml b/src/FlightMap/MapItems/MissionItemIndicator.qml
index 440f2a0..d4f3f70 100644
--- a/src/FlightMap/MapItems/MissionItemIndicator.qml
+++ b/src/FlightMap/MapItems/MissionItemIndicator.qml
@@ -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
diff --git a/src/MissionManager/MissionControllerTest.cc b/src/MissionManager/MissionControllerTest.cc
index 0955a9d..d417708 100644
--- a/src/MissionManager/MissionControllerTest.cc
+++ b/src/MissionManager/MissionControllerTest.cc
@@ -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);
+    }
+}
diff --git a/src/MissionManager/MissionControllerTest.h b/src/MissionManager/MissionControllerTest.h
index 9e469a9..2cc2559 100644
--- a/src/MissionManager/MissionControllerTest.h
+++ b/src/MissionManager/MissionControllerTest.h
@@ -31,6 +31,9 @@ public:
 private slots:
     void cleanup(void);
 
+    void _testGimbalRecalc(void);
+
+private:
     void _testEmptyVehicleAPM(void);
     void _testEmptyVehiclePX4(void);
     void _testAddWayppointAPM(void);
diff --git a/src/MissionManager/MissionSettingsItem.h b/src/MissionManager/MissionSettingsItem.h
index 39e9e16..8679f49 100644
--- a/src/MissionManager/MissionSettingsItem.h
+++ b/src/MissionManager/MissionSettingsItem.h
@@ -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);
diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc
index c90b06f..bc982fa 100644
--- a/src/MissionManager/SimpleMissionItem.cc
+++ b/src/MissionManager/SimpleMissionItem.cc
@@ -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);
diff --git a/src/MissionManager/SimpleMissionItemTest.cc b/src/MissionManager/SimpleMissionItemTest.cc
index e36795c..6d2f9bb 100644
--- a/src/MissionManager/SimpleMissionItemTest.cc
+++ b/src/MissionManager/SimpleMissionItemTest.cc
@@ -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::_testCameraSectionSignals(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);
 }
diff --git a/src/MissionManager/SimpleMissionItemTest.h b/src/MissionManager/SimpleMissionItemTest.h
index e28178a..1572f2b 100644
--- a/src/MissionManager/SimpleMissionItemTest.h
+++ b/src/MissionManager/SimpleMissionItemTest.h
@@ -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,
diff --git a/src/MissionManager/VisualMissionItem.h b/src/MissionManager/VisualMissionItem.h
index b2cdba8..cb63d4a 100644
--- a/src/MissionManager/VisualMissionItem.h
+++ b/src/MissionManager/VisualMissionItem.h
@@ -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
diff --git a/src/MissionManager/VisualMissionItemTest.cc b/src/MissionManager/VisualMissionItemTest.cc
index eee77ca..43a0278 100644
--- a/src/MissionManager/VisualMissionItemTest.cc
+++ b/src/MissionManager/VisualMissionItemTest.cc
@@ -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;
+}
diff --git a/src/MissionManager/VisualMissionItemTest.h b/src/MissionManager/VisualMissionItemTest.h
index 30d4c19..3728bfe 100644
--- a/src/MissionManager/VisualMissionItemTest.h
+++ b/src/MissionManager/VisualMissionItemTest.h
@@ -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,