diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 7eec705..9549141 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -389,3 +389,13 @@ void APMFirmwarePlugin::addMetaDataToFact(Fact* fact) { _parameterMetaData.addMetaDataToFact(fact); } + +QList APMFirmwarePlugin::supportedMissionCommands(void) +{ + QList list; + + // FIXME: Temp list, just dup of PX4 + list << MAV_CMD_NAV_WAYPOINT << MAV_CMD_NAV_LOITER_UNLIM << MAV_CMD_NAV_LOITER_TURNS << MAV_CMD_NAV_LOITER_TIME + << MAV_CMD_NAV_RETURN_TO_LAUNCH << MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF << MAV_CMD_CONDITION_DELAY << MAV_CMD_DO_JUMP; + return list; +} diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h index d1c429c..9836c75 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -91,6 +91,7 @@ public: virtual bool sendHomePositionToVehicle(void); virtual void addMetaDataToFact(Fact* fact); virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); } + virtual QList supportedMissionCommands(void); protected: /// All access to singleton is through stack specific implementation diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index d1d2719..4a05bdd 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -109,6 +109,9 @@ public: /// Adds the parameter meta data to the Fact virtual void addMetaDataToFact(Fact* fact) = 0; + + /// List of supported mission commands. Empty list for all commands supported. + virtual QList supportedMissionCommands(void) = 0; }; #endif diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc index 6e748b9..d4cd776 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc @@ -118,3 +118,9 @@ void GenericFirmwarePlugin::addMetaDataToFact(Fact* fact) FactMetaData* metaData = new FactMetaData(fact->type(), fact); fact->setMetaData(metaData); } + +QList GenericFirmwarePlugin::supportedMissionCommands(void) +{ + // Generic supports all commands + return QList(); +} diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h index 5eaa175..9a01d1a 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h @@ -47,6 +47,7 @@ public: virtual bool sendHomePositionToVehicle(void); virtual void addMetaDataToFact(Fact* fact); virtual QString getDefaultComponentIdParam(void) const { return QString(); } + virtual QList supportedMissionCommands(void); }; #endif diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index b45215b..8c5272c 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -207,3 +207,12 @@ void PX4FirmwarePlugin::addMetaDataToFact(Fact* fact) { _parameterMetaData.addMetaDataToFact(fact); } + +QList PX4FirmwarePlugin::supportedMissionCommands(void) +{ + QList list; + + list << MAV_CMD_NAV_WAYPOINT << MAV_CMD_NAV_LOITER_UNLIM << MAV_CMD_NAV_LOITER_TURNS << MAV_CMD_NAV_LOITER_TIME + << MAV_CMD_NAV_RETURN_TO_LAUNCH << MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF << MAV_CMD_CONDITION_DELAY << MAV_CMD_DO_JUMP; + return list; +} diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index 216d536..99134ec 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -47,6 +47,7 @@ public: virtual bool sendHomePositionToVehicle(void); virtual void addMetaDataToFact(Fact* fact); virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); } + virtual QList supportedMissionCommands(void); private: PX4ParameterMetaData _parameterMetaData;