Browse Source

Add supportedMissionCommands

QGC4.4
Don Gagne 10 years ago
parent
commit
57cdf65ba9
  1. 10
      src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
  2. 1
      src/FirmwarePlugin/APM/APMFirmwarePlugin.h
  3. 3
      src/FirmwarePlugin/FirmwarePlugin.h
  4. 6
      src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc
  5. 1
      src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h
  6. 9
      src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
  7. 1
      src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h

10
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc

@ -389,3 +389,13 @@ void APMFirmwarePlugin::addMetaDataToFact(Fact* fact) @@ -389,3 +389,13 @@ void APMFirmwarePlugin::addMetaDataToFact(Fact* 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;
}

1
src/FirmwarePlugin/APM/APMFirmwarePlugin.h

@ -91,6 +91,7 @@ public: @@ -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<MAV_CMD> supportedMissionCommands(void);
protected:
/// All access to singleton is through stack specific implementation

3
src/FirmwarePlugin/FirmwarePlugin.h

@ -109,6 +109,9 @@ public: @@ -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<MAV_CMD> supportedMissionCommands(void) = 0;
};
#endif

6
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc

@ -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);
fact->setMetaData(metaData);
}
QList<MAV_CMD> GenericFirmwarePlugin::supportedMissionCommands(void)
{
// Generic supports all commands
return QList<MAV_CMD>();
}

1
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h

@ -47,6 +47,7 @@ public: @@ -47,6 +47,7 @@ public:
virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact);
virtual QString getDefaultComponentIdParam(void) const { return QString(); }
virtual QList<MAV_CMD> supportedMissionCommands(void);
};
#endif

9
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc

@ -207,3 +207,12 @@ void PX4FirmwarePlugin::addMetaDataToFact(Fact* fact) @@ -207,3 +207,12 @@ void PX4FirmwarePlugin::addMetaDataToFact(Fact* 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;
}

1
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h

@ -47,6 +47,7 @@ public: @@ -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<MAV_CMD> supportedMissionCommands(void);
private:
PX4ParameterMetaData _parameterMetaData;

Loading…
Cancel
Save