diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index 57094a7bd5c01ca1a53623e9d1f7a688067be82a..86221320c5dfaa39d9388384e58a339d95d8adc9 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -237,9 +237,13 @@ QString ArduCopterFirmwarePlugin::geoFenceRadiusParam(Vehicle* vehicle) bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const { - 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; + 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; } diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index ce622359f3d2bf86e039efd72d9370a93700c9da..65aa0ff451b5d6af7bb292a6eb9c844b50e57601 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -518,9 +518,13 @@ void PX4FirmwarePlugin::_handleAutopilotVersion(Vehicle* vehicle, mavlink_messag bool PX4FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const { - 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; + if (vehicle->isOfflineEditingVehicle()) { + return FirmwarePlugin::vehicleYawsToNextWaypointInMission(vehicle); + } else { + if (vehicle->multiRotor() && 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 true; } diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 5067ac73c07f57422fb2792319a8230761349e9a..d228ae3d87dd9790ae421f26cd9e80f7a8b38f24 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -1044,7 +1044,7 @@ void MissionController::_recalcMissionFlightStatus() } // Look for gimbal change - if (_controllerVehicle->vehicleYawsToNextWaypointInMission()) { + if (_managerVehicle->vehicleYawsToNextWaypointInMission()) { // We current only support gimbal display in this mode double gimbalYaw = item->specifiedGimbalYaw(); if (!qIsNaN(gimbalYaw)) { @@ -1371,7 +1371,7 @@ void MissionController::managerVehicleChanged(Vehicle* managerVehicle) _managerVehicle = managerVehicle; if (!_managerVehicle) { - qWarning() << "RallyPointController::managerVehicleChanged managerVehicle=NULL"; + qWarning() << "MissionController::managerVehicleChanged managerVehicle=NULL"; return; } diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc index bc982faa94277826f66f9f957fff06fa028b6b7e..9a63c2cfa277d73c7d193380d6805d4b1af8d9ce 100644 --- a/src/MissionManager/SimpleMissionItem.cc +++ b/src/MissionManager/SimpleMissionItem.cc @@ -446,6 +446,17 @@ void SimpleMissionItem::_rebuildNaNFacts(void) const MissionCmdParamInfo* paramInfo = uiInfo->getParamInfo(i); if (paramInfo && paramInfo->nanUnchanged()) { + // Show hide Heading field on waypoint based on vehicle yaw to next waypoint setting. This needs to come from the actual vehicle if it exists + // and not _vehicle which is always offline. + Vehicle* firmwareVehicle = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle(); + if (!firmwareVehicle) { + firmwareVehicle = _vehicle; + } + bool hideWaypointHeading = (command == MAV_CMD_NAV_WAYPOINT) && (i == 4) && firmwareVehicle->firmwarePlugin()->vehicleYawsToNextWaypointInMission(firmwareVehicle); + if (hideWaypointHeading) { + continue; + } + Fact* paramFact = rgParamFacts[i-1]; FactMetaData* paramMetaData = rgParamMetaData[i-1];