Browse Source

Ardupilot: Add support for fixed wing airspeed change

QGC4.4
davidsastresas 2 years ago committed by Don Gagne
parent
commit
3733318c93
  1. 42
      src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
  2. 4
      src/FirmwarePlugin/APM/APMFirmwarePlugin.h

42
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc

@ -1133,3 +1133,45 @@ QMutex& APMFirmwarePlugin::_reencodeMavlinkChannelMutex() @@ -1133,3 +1133,45 @@ QMutex& APMFirmwarePlugin::_reencodeMavlinkChannelMutex()
static QMutex _mutex{};
return _mutex;
}
double APMFirmwarePlugin::maximumEquivalentAirspeed(Vehicle* vehicle)
{
QString airspeedMax("ARSPD_FBW_MAX");
if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, airspeedMax)) {
return vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, airspeedMax)->rawValue().toDouble();
}
return FirmwarePlugin::maximumEquivalentAirspeed(vehicle);
}
double APMFirmwarePlugin::minimumEquivalentAirspeed(Vehicle* vehicle)
{
QString airspeedMin("ARSPD_FBW_MIN");
if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, airspeedMin)) {
return vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, airspeedMin)->rawValue().toDouble();
}
return FirmwarePlugin::minimumEquivalentAirspeed(vehicle);
}
bool APMFirmwarePlugin::fixedWingAirSpeedLimitsAvailable(Vehicle* vehicle)
{
return vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "ARSPD_FBW_MIN") &&
vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "ARSPD_FBW_MAX");
}
void APMFirmwarePlugin::guidedModeChangeEquivalentAirspeed(Vehicle* vehicle, double airspeed_equiv)
{
vehicle->sendMavCommand(
vehicle->defaultComponentId(),
MAV_CMD_DO_CHANGE_SPEED,
true, // show error is fails
0, // 0: airspeed, 1: groundspeed
static_cast<float>(airspeed_equiv), // speed setpoint
-1, // throttle, no change
0 // 0: absolute speed, 1: relative to current
); // param 5-7 unused
}

4
src/FirmwarePlugin/APM/APMFirmwarePlugin.h

@ -80,6 +80,10 @@ public: @@ -80,6 +80,10 @@ public:
QString getHobbsMeter (Vehicle* vehicle) override;
bool hasGripper (const Vehicle* vehicle) const override;
const QVariantList& toolIndicators (const Vehicle* vehicle) override;
double maximumEquivalentAirspeed (Vehicle* vehicle) override;
double minimumEquivalentAirspeed (Vehicle* vehicle) override;
bool fixedWingAirSpeedLimitsAvailable(Vehicle* vehicle) override;
void guidedModeChangeEquivalentAirspeed(Vehicle* vehicle, double airspeed_equiv) override;
protected:
/// All access to singleton is through stack specific implementation

Loading…
Cancel
Save