Commit 57cdf65b authored by Don Gagne's avatar Don Gagne

Add supportedMissionCommands

parent c8942215
...@@ -389,3 +389,13 @@ void APMFirmwarePlugin::addMetaDataToFact(Fact* fact) ...@@ -389,3 +389,13 @@ void APMFirmwarePlugin::addMetaDataToFact(Fact* fact)
{ {
_parameterMetaData.addMetaDataToFact(fact); _parameterMetaData.addMetaDataToFact(fact);
} }
QList<MAV_CMD> APMFirmwarePlugin::supportedMissionCommands(void)
{
QList<MAV_CMD> 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;
}
...@@ -91,6 +91,7 @@ public: ...@@ -91,6 +91,7 @@ public:
virtual bool sendHomePositionToVehicle(void); virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact); virtual void addMetaDataToFact(Fact* fact);
virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); } virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); }
virtual QList<MAV_CMD> supportedMissionCommands(void);
protected: protected:
/// All access to singleton is through stack specific implementation /// All access to singleton is through stack specific implementation
......
...@@ -109,6 +109,9 @@ public: ...@@ -109,6 +109,9 @@ public:
/// Adds the parameter meta data to the Fact /// Adds the parameter meta data to the Fact
virtual void addMetaDataToFact(Fact* fact) = 0; virtual void addMetaDataToFact(Fact* fact) = 0;
/// List of supported mission commands. Empty list for all commands supported.
virtual QList<MAV_CMD> supportedMissionCommands(void) = 0;
}; };
#endif #endif
...@@ -118,3 +118,9 @@ void GenericFirmwarePlugin::addMetaDataToFact(Fact* fact) ...@@ -118,3 +118,9 @@ void GenericFirmwarePlugin::addMetaDataToFact(Fact* fact)
FactMetaData* metaData = new FactMetaData(fact->type(), fact); FactMetaData* metaData = new FactMetaData(fact->type(), fact);
fact->setMetaData(metaData); fact->setMetaData(metaData);
} }
QList<MAV_CMD> GenericFirmwarePlugin::supportedMissionCommands(void)
{
// Generic supports all commands
return QList<MAV_CMD>();
}
...@@ -47,6 +47,7 @@ public: ...@@ -47,6 +47,7 @@ public:
virtual bool sendHomePositionToVehicle(void); virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact); virtual void addMetaDataToFact(Fact* fact);
virtual QString getDefaultComponentIdParam(void) const { return QString(); } virtual QString getDefaultComponentIdParam(void) const { return QString(); }
virtual QList<MAV_CMD> supportedMissionCommands(void);
}; };
#endif #endif
...@@ -207,3 +207,12 @@ void PX4FirmwarePlugin::addMetaDataToFact(Fact* fact) ...@@ -207,3 +207,12 @@ void PX4FirmwarePlugin::addMetaDataToFact(Fact* fact)
{ {
_parameterMetaData.addMetaDataToFact(fact); _parameterMetaData.addMetaDataToFact(fact);
} }
QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
{
QList<MAV_CMD> 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;
}
...@@ -47,6 +47,7 @@ public: ...@@ -47,6 +47,7 @@ public:
virtual bool sendHomePositionToVehicle(void); virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact); virtual void addMetaDataToFact(Fact* fact);
virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); } virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); }
virtual QList<MAV_CMD> supportedMissionCommands(void);
private: private:
PX4ParameterMetaData _parameterMetaData; PX4ParameterMetaData _parameterMetaData;
......
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