diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index 3af285e00b90a4e924184072459b985780fee982..0ae992bd7a454840d2687ec97d6a1593b5609085 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -134,19 +134,6 @@ bool ArduCopterFirmwarePlugin::multiRotorXConfig(Vehicle* vehicle) return vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "FRAME")->rawValue().toInt() != 0; } -bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const -{ - if (vehicle->isOfflineEditingVehicle()) { - return FirmwarePlugin::vehicleYawsToNextWaypointInMission(vehicle); - } else { - if (vehicle->multiRotor() && 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 true; -} - #if 0 // Follow me not ready for Stable void ArduCopterFirmwarePlugin::sendGCSMotionReport(Vehicle* vehicle, FollowMe::GCSMotionReport& motionReport, uint8_t estimatationCapabilities) diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h index 05c596994f8964498e2efd3c2f051cd7b679817e..0294872c65f87d6073cb3ec156b5d923c802e6f2 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h @@ -71,7 +71,6 @@ public: QString landFlightMode (void) const override { return QStringLiteral("Land"); } QString takeControlFlightMode (void) const override { return QStringLiteral("Loiter"); } QString followFlightMode (void) const override { return QStringLiteral("Follow"); } - bool vehicleYawsToNextWaypointInMission (const Vehicle* vehicle) const override; QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); } bool supportsSmartRTL (void) const override { return true; } #if 0 diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 3a4e07807badb0dd3cd516010cec6c7a3335dc38..1b992dfe6cf0006ba1f690a9f42df2ab27ad05d4 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -698,11 +698,6 @@ QMap* FirmwarePlugin::factGroups(void) { return nullptr; } -bool FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const -{ - return vehicle->multiRotor() ? false : true; -} - bool FirmwarePlugin::_armVehicleAndValidate(Vehicle* vehicle) { if (vehicle->armed()) { diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index a6d0f8c5378de98da20ac57f17fbf2000ea6a8e5..8f2f626f1c9d290f7e869e1bb8a233ccdd74583a 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -297,9 +297,6 @@ public: /// Returns a pointer to a dictionary of firmware-specific FactGroups virtual QMap* factGroups(void); - /// @true: When flying a mission the vehicle is always facing towards the next waypoint - virtual bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const; - /// Returns the data needed to do battery consumption calculations /// @param[out] mAhBattery Battery milliamp-hours rating (0 for no battery data available) /// @param[out] hoverAmps Current draw in amps during hover diff --git a/src/MissionManager/MavCmdInfoMultiRotor.json b/src/MissionManager/MavCmdInfoMultiRotor.json index b2f3607868f20555145dfdf151c93ebec18b75bb..abd97e5a79c325bfa5b452b04848f2c93ce4424f 100644 --- a/src/MissionManager/MavCmdInfoMultiRotor.json +++ b/src/MissionManager/MavCmdInfoMultiRotor.json @@ -9,6 +9,11 @@ "comment": "MAV_CMD_NAV_LOITER_UNLIM", "paramRemove": "3" }, + { + "id": 18, + "comment": "MAV_CMD_NAV_LOITER_TURNS", + "paramRemove": "1,2,3,4" + }, { "id": 19, "comment": "MAV_CMD_NAV_LOITER_TIME", diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index 0248e0d3dc6c62f8c0ed65b828e80f34200edf7d..2d491fa09a226df074df273a26f899a4408e2dea 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -501,10 +501,6 @@ void SimpleMissionItem::_rebuildNaNFacts(void) if (!firmwareVehicle) { firmwareVehicle = _controllerVehicle; } - bool hideWaypointHeading = (command == MAV_CMD_NAV_WAYPOINT || command == MAV_CMD_NAV_TAKEOFF) && (i == 4) && firmwareVehicle->firmwarePlugin()->vehicleYawsToNextWaypointInMission(firmwareVehicle); - if (hideWaypointHeading) { - continue; - } Fact* paramFact = rgParamFacts[i-1]; FactMetaData* paramMetaData = rgParamMetaData[i-1]; diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 9128684a85c36501feca8dc921ba98fb31128cb4..617baebe1be4945c4ef5cb654fbc9a33fac680a5 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -3835,11 +3835,6 @@ const QVariantList& Vehicle::staticCameraList() const return emptyList; } -bool Vehicle::vehicleYawsToNextWaypointInMission() const -{ - return _firmwarePlugin->vehicleYawsToNextWaypointInMission(this); -} - void Vehicle::_setupAutoDisarmSignalling() { QString param = _firmwarePlugin->autoDisarmParameter(this); diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 73162690caa47f64275efe256a5c523e09b08657..407a2650bbd38a6fe6028f012db5fe64f18466fc 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -1125,9 +1125,6 @@ public: QGCCameraManager* dynamicCameras () { return _cameras; } QString hobbsMeter (); - /// @true: When flying a mission the vehicle is always facing towards the next waypoint - bool vehicleYawsToNextWaypointInMission() const; - /// The vehicle is responsible for making the initial request for the Plan. /// @return: true: initial request is complete, false: initial request is still in progress; bool initialPlanRequestComplete() const { return _initialPlanRequestComplete; }