Commit 247f3ae3 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #5764 from DonLakeFlyer/ArduPlaneVTOL

ArduPlane VTOL indication comes from HEARBEAT
parents 16541062 404b076a
......@@ -162,9 +162,7 @@ bool APMFirmwarePlugin::isCapable(const Vehicle* vehicle, FirmwareCapabilities c
uint32_t available = SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability;
if (vehicle->multiRotor()) {
available |= TakeoffVehicleCapability;
} else if (vehicle->fixedWing() || vehicle->vtol()) {
// Due to the way ArduPilot marks a vtol aircraft, we don't know if something is a vtol at initial connection.
// So we always enabled takeoff for fixed wing.
} else if (vehicle->vtol()) {
available |= TakeoffVehicleCapability;
}
......@@ -887,18 +885,6 @@ void APMFirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitu
vehicle->sendMessageOnLink(vehicle->priorityLink(), msg);
}
bool APMFirmwarePlugin::isVtol(const Vehicle* vehicle) const
{
if (vehicle->fixedWing()) {
if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("Q_ENABLE")) &&
vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("Q_ENABLE"))->rawValue().toBool()) {
return true;
}
}
return false;
}
void APMFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle)
{
_guidedModeTakeoff(vehicle);
......
......@@ -74,7 +74,6 @@ public:
QList<MAV_CMD> supportedMissionCommands(void) override;
AutoPilotPlugin* autopilotPlugin (Vehicle* vehicle) override;
bool isVtol (const Vehicle* vehicle) const override;
bool isCapable (const Vehicle *vehicle, FirmwareCapabilities capabilities) override;
void setGuidedMode (Vehicle* vehicle, bool guidedMode) override;
void guidedModeTakeoff (Vehicle* vehicle) override;
......
......@@ -83,6 +83,13 @@ QString APMParameterMetaData::mavTypeToString(MAV_TYPE vehicleTypeEnum)
switch(vehicleTypeEnum) {
case MAV_TYPE_FIXED_WING:
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
vehicleName = "ArduPlane";
break;
case MAV_TYPE_QUADROTOR:
......@@ -111,13 +118,6 @@ QString APMParameterMetaData::mavTypeToString(MAV_TYPE vehicleTypeEnum)
case MAV_TYPE_FLAPPING_WING:
case MAV_TYPE_KITE:
case MAV_TYPE_ONBOARD_CONTROLLER:
case MAV_TYPE_VTOL_DUOROTOR:
case MAV_TYPE_VTOL_QUADROTOR:
case MAV_TYPE_VTOL_TILTROTOR:
case MAV_TYPE_VTOL_RESERVED2:
case MAV_TYPE_VTOL_RESERVED3:
case MAV_TYPE_VTOL_RESERVED4:
case MAV_TYPE_VTOL_RESERVED5:
case MAV_TYPE_GIMBAL:
case MAV_TYPE_ENUM_END:
default:
......
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