diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index 2ce96ceaecbba39fb4a4f66e411e838a1917d91a..dba4a5f1155cae5fe0440563486246ee201d011a 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -247,17 +247,3 @@ bool ArduCopterFirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* } return true; } - -void ArduCopterFirmwarePlugin::missionFlightSpeedInfo(Vehicle* vehicle, double& hoverSpeed, double& cruiseSpeed) -{ - QString hoverSpeedParam("WPNAV_SPEED"); - - // First pull settings defaults - FirmwarePlugin::missionFlightSpeedInfo(vehicle, hoverSpeed, cruiseSpeed); - - cruiseSpeed = 0; - if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, hoverSpeedParam)) { - Fact* speed = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, hoverSpeedParam); - hoverSpeed = speed->rawValue().toDouble() / 100; // cm/s -> m/s - } -} diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h index 5f35bfa15d53f2c92a040deeb2f510d4b923586b..345fdb232e35d043fff0161d3b861e6203254ef7 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.h @@ -76,7 +76,6 @@ public: QString takeControlFlightMode(void) const override { return QString("Stablize"); } bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const final; QString autoDisarmParameter(Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral("DISARM_DELAY"); } - void missionFlightSpeedInfo(Vehicle* vehicle, double& hoverSpeed, double& cruiseSpeed) override; private: static bool _remapParamNameIntialized; diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 056dd4eec601d2abf3535e54d08214fe1c119b6b..ecc9ff8bae4feae409f8ed4519e7362703be9e96 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -466,16 +466,6 @@ QString FirmwarePlugin::autoDisarmParameter(Vehicle* vehicle) return QString(); } -void FirmwarePlugin::missionFlightSpeedInfo(Vehicle* vehicle, double& hoverSpeed, double& cruiseSpeed) -{ - Q_UNUSED(vehicle); - - // Best we can do is use settings - AppSettings* appSettings = qgcApp()->toolbox()->settingsManager()->appSettings(); - hoverSpeed = appSettings->offlineEditingHoverSpeed()->rawValue().toDouble(); - cruiseSpeed = appSettings->offlineEditingCruiseSpeed()->rawValue().toDouble(); -} - bool FirmwarePlugin::hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitchSupported, bool& yawSupported) { Q_UNUSED(vehicle); diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index 7f8ee7d98ef25b2161057401c04b9def24a943c3..1d438c23ead5a7dbaeb3f002fa4df7c285f7158a 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -282,11 +282,6 @@ public: /// @param[out] cruiseAmps Current draw in amps during cruise virtual void batteryConsumptionData(Vehicle* vehicle, int& mAhBattery, double& hoverAmps, double& cruiseAmps) const; - /// Returns the default mission flight speeds. - /// @param[out] hoverSpeed Flight speed for vehicle flying in multi-rotor mode. 0 for none, or not available. - /// @param[out] cruiseSpeed Flight speed for vehicle flying in fixed wing forward flight mode. 0 for none, or not available. - virtual void missionFlightSpeedInfo(Vehicle* vehicle, double& hoverSpeed, double& cruiseSpeed); - // Returns the parameter which control auto-disarm. Assume == 0 means no auto disarm virtual QString autoDisarmParameter(Vehicle* vehicle); diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index aa271e14c4277683400c3e3f88fa39a2ea419148..b04dcc3315ffa6a3250f97c286c238a1ddb10f51 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -547,21 +547,3 @@ bool PX4FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicl } return true; } - -void PX4FirmwarePlugin::missionFlightSpeedInfo(Vehicle* vehicle, double& hoverSpeed, double& cruiseSpeed) -{ - QString hoverSpeedParam("MPC_XY_CRUISE"); - QString cruiseSpeedParam("FW_AIRSPD_TRIM"); - - // First pull settings defaults - FirmwarePlugin::missionFlightSpeedInfo(vehicle, hoverSpeed, cruiseSpeed); - - if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, hoverSpeedParam)) { - Fact* speed = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, hoverSpeedParam); - hoverSpeed = speed->rawValue().toDouble(); - } - if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, cruiseSpeedParam)) { - Fact* speed = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, cruiseSpeedParam); - cruiseSpeed = speed->rawValue().toDouble(); - } -} diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index 67f9caf8ea7b9b910581541341d7f1e165897c6e..0eb139c72d71025bd1b1203073f41663eb534009 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -68,7 +68,6 @@ public: QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); } bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const override; QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("COM_DISARM_LAND"); } - void missionFlightSpeedInfo (Vehicle* vehicle, double& hoverSpeed, double& cruiseSpeed) override; protected: typedef struct { diff --git a/src/MissionManager/SpeedSection.cc b/src/MissionManager/SpeedSection.cc index 5c45c31a7f95f4fb71487b7650a6f0b670d6902c..7979690ebb87834ecd6a8570f8ad4d4b9370d0fa 100644 --- a/src/MissionManager/SpeedSection.cc +++ b/src/MissionManager/SpeedSection.cc @@ -27,14 +27,11 @@ SpeedSection::SpeedSection(Vehicle* vehicle, QObject* parent) _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/SpeedSection.FactMetaData.json"), NULL /* metaDataParent */); } - double hoverSpeed, cruiseSpeed; double flightSpeed = 0; - - _vehicle->firmwarePlugin()->missionFlightSpeedInfo(_vehicle, hoverSpeed, cruiseSpeed); if (_vehicle->multiRotor()) { - flightSpeed = hoverSpeed; - } else if (_vehicle->fixedWing()) { - flightSpeed = cruiseSpeed; + flightSpeed = _vehicle->defaultHoverSpeed(); + } else { + flightSpeed = _vehicle->defaultCruiseSpeed(); } _metaDataMap[_flightSpeedName]->setRawDefaultValue(flightSpeed); diff --git a/src/Settings/App.SettingsGroup.json b/src/Settings/App.SettingsGroup.json index 6686a1b779b44d0a541904e2e5a69dda5b5793c4..30e9d4520c17330db6a263d3c5b354763c044376 100644 --- a/src/Settings/App.SettingsGroup.json +++ b/src/Settings/App.SettingsGroup.json @@ -5,7 +5,7 @@ "type": "uint32", "enumStrings": "ArduPilot,PX4 Pro,Mavlink Generic", "enumValues": "3,12,0", - "defaultValue": 3 + "defaultValue": 12 }, { "name": "OfflineEditingVehicleType", @@ -13,14 +13,14 @@ "type": "uint32", "enumStrings": "Fixed Wing,Multi-Rotor,VTOL,Rover,Sub", "enumValues": "1,2,19,10,12", - "defaultValue": 1 + "defaultValue": 2 }, { "name": "OfflineEditingCruiseSpeed", "shortDescription": "Offline editing cruise speed", "longDescription": "This value defines the cruising speed for forward flight vehicles for use in calculating mission duration when not connected to a vehicle.", "type": "double", - "defaultValue": 16.0, + "defaultValue": 15.0, "min": 1.0, "units": "m/s", "decimalPlaces": 2 @@ -30,7 +30,7 @@ "shortDescription": "Offline editing hover speed", "longDescription": "This value defines the cruising speed for multi-rotor vehicles for use in calculating mission duration when not connected to a vehicle.", "type": "double", - "defaultValue": 4.0, + "defaultValue": 5.0, "min": 1.0, "units": "m/s", "decimalPlaces": 2