Commit cec81a75 authored by DonLakeFlyer's avatar DonLakeFlyer

Rework guided takeoff to be a capability bit

parent 47a9895a
...@@ -530,3 +530,19 @@ bool FirmwarePlugin::hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitc ...@@ -530,3 +530,19 @@ bool FirmwarePlugin::hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitc
yawSupported = false; yawSupported = false;
return false; return false;
} }
bool FirmwarePlugin::isVtol(const Vehicle* vehicle) const
{
switch (vehicle->vehicleType()) {
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:
return true;
default:
return false;
}
}
...@@ -45,6 +45,7 @@ public: ...@@ -45,6 +45,7 @@ public:
PauseVehicleCapability = 1 << 2, ///< Vehicle supports pausing at current location PauseVehicleCapability = 1 << 2, ///< Vehicle supports pausing at current location
GuidedModeCapability = 1 << 3, ///< Vehicle supports guided mode commands GuidedModeCapability = 1 << 3, ///< Vehicle supports guided mode commands
OrbitModeCapability = 1 << 4, ///< Vehicle supports orbit mode OrbitModeCapability = 1 << 4, ///< Vehicle supports orbit mode
TakeoffVehicleCapability = 1 << 5, ///< Vehicle supports guided takeoff
} FirmwareCapabilities; } FirmwareCapabilities;
/// Maps from on parameter name to another /// Maps from on parameter name to another
...@@ -286,6 +287,9 @@ public: ...@@ -286,6 +287,9 @@ public:
/// @return true: vehicle has gimbal, false: gimbal support unknown /// @return true: vehicle has gimbal, false: gimbal support unknown
virtual bool hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitchSupported, bool& yawSupported); virtual bool hasGimbal(Vehicle* vehicle, bool& rollSupported, bool& pitchSupported, bool& yawSupported);
/// Returns true if the vehicle is a VTOL
virtual bool isVtol(const Vehicle* vehicle) const;
// FIXME: Hack workaround for non pluginize FollowMe support // FIXME: Hack workaround for non pluginize FollowMe support
static const char* px4FollowMeFlightMode; static const char* px4FollowMeFlightMode;
......
...@@ -227,11 +227,12 @@ bool PX4FirmwarePlugin::supportsManualControl(void) ...@@ -227,11 +227,12 @@ bool PX4FirmwarePlugin::supportsManualControl(void)
bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities)
{ {
if (vehicle->multiRotor()) { int available = MavCmdPreflightStorageCapability | SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability;
return (capabilities & (MavCmdPreflightStorageCapability | GuidedModeCapability | SetFlightModeCapability | PauseVehicleCapability /*| OrbitModeCapability still NYI*/)) == capabilities; if (vehicle->multiRotor() || vehicle->vtol()) {
} else { available |= TakeoffVehicleCapability;
return (capabilities & (MavCmdPreflightStorageCapability | GuidedModeCapability | SetFlightModeCapability | PauseVehicleCapability)) == capabilities;
} }
return (capabilities & available) == capabilities;
} }
void PX4FirmwarePlugin::initializeVehicle(Vehicle* vehicle) void PX4FirmwarePlugin::initializeVehicle(Vehicle* vehicle)
......
...@@ -92,7 +92,7 @@ Item { ...@@ -92,7 +92,7 @@ Item {
property bool showArm: _activeVehicle && !_vehicleArmed property bool showArm: _activeVehicle && !_vehicleArmed
property bool showDisarm: _activeVehicle && _vehicleArmed && !_vehicleFlying property bool showDisarm: _activeVehicle && _vehicleArmed && !_vehicleFlying
property bool showRTL: _activeVehicle && _vehicleArmed && _activeVehicle.guidedModeSupported && _vehicleFlying && !_vehicleInRTLMode property bool showRTL: _activeVehicle && _vehicleArmed && _activeVehicle.guidedModeSupported && _vehicleFlying && !_vehicleInRTLMode
property bool showTakeoff: _activeVehicle && _activeVehicle.guidedModeSupported && !_vehicleFlying && !_activeVehicle.fixedWing property bool showTakeoff: _activeVehicle && _activeVehicle.takeoffVehicleSupported && !_vehicleFlying
property bool showLand: _activeVehicle && _activeVehicle.guidedModeSupported && _vehicleArmed && !_activeVehicle.fixedWing && !_vehicleInLandMode property bool showLand: _activeVehicle && _activeVehicle.guidedModeSupported && _vehicleArmed && !_activeVehicle.fixedWing && !_vehicleInLandMode
property bool showStartMission: _activeVehicle && _missionAvailable && !_missionActive && !_vehicleFlying property bool showStartMission: _activeVehicle && _missionAvailable && !_missionActive && !_vehicleFlying
property bool showContinueMission: _activeVehicle && _missionAvailable && !_missionActive && _vehicleFlying && (_currentMissionIndex < missionController.visualItems.count - 1) property bool showContinueMission: _activeVehicle && _missionAvailable && !_missionActive && _vehicleFlying && (_currentMissionIndex < missionController.visualItems.count - 1)
......
...@@ -2094,18 +2094,7 @@ bool Vehicle::multiRotor(void) const ...@@ -2094,18 +2094,7 @@ bool Vehicle::multiRotor(void) const
bool Vehicle::vtol(void) const bool Vehicle::vtol(void) const
{ {
switch (vehicleType()) { return _firmwarePlugin->isVtol(this);
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:
return true;
default:
return false;
}
} }
bool Vehicle::supportsManualControl(void) const bool Vehicle::supportsManualControl(void) const
...@@ -2224,6 +2213,11 @@ bool Vehicle::orbitModeSupported() const ...@@ -2224,6 +2213,11 @@ bool Vehicle::orbitModeSupported() const
return _firmwarePlugin->isCapable(this, FirmwarePlugin::OrbitModeCapability); return _firmwarePlugin->isCapable(this, FirmwarePlugin::OrbitModeCapability);
} }
bool Vehicle::takeoffVehicleSupported() const
{
return _firmwarePlugin->isCapable(this, FirmwarePlugin::TakeoffVehicleCapability);
}
void Vehicle::guidedModeRTL(void) void Vehicle::guidedModeRTL(void)
{ {
if (!guidedModeSupported()) { if (!guidedModeSupported()) {
......
...@@ -319,23 +319,14 @@ public: ...@@ -319,23 +319,14 @@ public:
Q_PROPERTY(QmlObjectListModel* adsbVehicles READ adsbVehicles CONSTANT) Q_PROPERTY(QmlObjectListModel* adsbVehicles READ adsbVehicles CONSTANT)
Q_PROPERTY(bool initialPlanRequestComplete READ initialPlanRequestComplete NOTIFY initialPlanRequestCompleteChanged) Q_PROPERTY(bool initialPlanRequestComplete READ initialPlanRequestComplete NOTIFY initialPlanRequestCompleteChanged)
/// true: Vehicle is flying, false: Vehicle is on ground // Vehicle state used for guided control
Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying
Q_PROPERTY(bool landing READ landing NOTIFY landingChanged) ///< Vehicle is in landing pattern (DO_LAND_START)
/// true: Vehicle is flying, false: Vehicle is on ground Q_PROPERTY(bool guidedMode READ guidedMode WRITE setGuidedMode NOTIFY guidedModeChanged) ///< Vehicle is in Guided mode and can respond to guided commands
Q_PROPERTY(bool landing READ landing NOTIFY landingChanged) Q_PROPERTY(bool guidedModeSupported READ guidedModeSupported CONSTANT) ///< Guided mode commands are supported by this vehicle
Q_PROPERTY(bool pauseVehicleSupported READ pauseVehicleSupported CONSTANT) ///< Pause vehicle command is supported
/// true: Vehicle is in Guided mode and can respond to guided commands, false: vehicle cannot respond to direct control commands Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT) ///< Orbit mode is supported by this vehicle
Q_PROPERTY(bool guidedMode READ guidedMode WRITE setGuidedMode NOTIFY guidedModeChanged) Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT) ///< Guided takeoff supported
/// true: Guided mode commands are supported by this vehicle
Q_PROPERTY(bool guidedModeSupported READ guidedModeSupported CONSTANT)
/// true: pauseVehicle command is supported
Q_PROPERTY(bool pauseVehicleSupported READ pauseVehicleSupported CONSTANT)
/// true: Orbit mode is supported by this vehicle
Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT)
Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT) Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)
...@@ -441,9 +432,10 @@ public: ...@@ -441,9 +432,10 @@ public:
Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs); Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs);
#endif #endif
bool guidedModeSupported(void) const; bool guidedModeSupported (void) const;
bool pauseVehicleSupported(void) const; bool pauseVehicleSupported (void) const;
bool orbitModeSupported(void) const; bool orbitModeSupported (void) const;
bool takeoffVehicleSupported(void) const;
// Property accessors // Property accessors
......
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