Commit 9cb1ee6e authored by DonLakeFlyer's avatar DonLakeFlyer

Stop trying to pull from vehicle

Just use settings defaults
parent 8192004c
......@@ -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
}
}
......@@ -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;
......
......@@ -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);
......
......@@ -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);
......
......@@ -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();
}
}
......@@ -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 {
......
......@@ -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);
......
......@@ -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
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment