Browse Source

Autopilot plugins: Generate audio strings

QGC4.4
Lorenz Meier 10 years ago
parent
commit
6d80c11f25
  1. 11
      src/AutoPilotPlugins/AutoPilotPluginManager.cc
  2. 3
      src/AutoPilotPlugins/AutoPilotPluginManager.h
  3. 9
      src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc
  4. 1
      src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h
  5. 57
      src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc
  6. 1
      src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h

11
src/AutoPilotPlugins/AutoPilotPluginManager.cc

@ -124,6 +124,17 @@ QList<AutoPilotPluginManager::FullMode_t> AutoPilotPluginManager::getModes(int a @@ -124,6 +124,17 @@ QList<AutoPilotPluginManager::FullMode_t> AutoPilotPluginManager::getModes(int a
}
}
QString AutoPilotPluginManager::getAudioModeText(uint8_t baseMode, uint32_t customMode, int autopilotType) const
{
switch (autopilotType) {
case MAV_AUTOPILOT_PX4:
return PX4AutoPilotPlugin::getAudioModeText(baseMode, customMode);
case MAV_AUTOPILOT_GENERIC:
default:
return GenericAutoPilotPlugin::getAudioModeText(baseMode, customMode);
}
}
QString AutoPilotPluginManager::getShortModeText(uint8_t baseMode, uint32_t customMode, int autopilotType) const
{
switch (autopilotType) {

3
src/AutoPilotPlugins/AutoPilotPluginManager.h

@ -63,6 +63,9 @@ public: @@ -63,6 +63,9 @@ public:
/// @brief Returns a human readable short description for the specified mode.
QString getShortModeText(uint8_t baseMode, uint32_t customMode, int autopilotType) const;
/// @brief Returns a human hearable short description for the specified mode.
QString getAudioModeText(uint8_t baseMode, uint32_t customMode, int autopilotType) const;
private slots:
void _uasCreated(UASInterface* uas);
void _uasDeleted(UASInterface* uas);

9
src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc

@ -60,6 +60,15 @@ QList<AutoPilotPluginManager::FullMode_t> GenericAutoPilotPlugin::getModes(void) @@ -60,6 +60,15 @@ QList<AutoPilotPluginManager::FullMode_t> GenericAutoPilotPlugin::getModes(void)
return modeList;
}
QString GenericAutoPilotPlugin::getAudioModeText(uint8_t baseMode, uint32_t customMode)
{
Q_UNUSED(customMode);
QString mode = "";
return mode;
}
QString GenericAutoPilotPlugin::getShortModeText(uint8_t baseMode, uint32_t customMode)
{
Q_UNUSED(customMode);

1
src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h

@ -44,6 +44,7 @@ public: @@ -44,6 +44,7 @@ public:
virtual const QVariantList& vehicleComponents(void);
static QList<AutoPilotPluginManager::FullMode_t> getModes(void);
static QString getAudioModeText(uint8_t baseMode, uint32_t customMode);
static QString getShortModeText(uint8_t baseMode, uint32_t customMode);
static void clearStaticData(void);

57
src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc

@ -141,6 +141,63 @@ QList<AutoPilotPluginManager::FullMode_t> PX4AutoPilotPlugin::getModes(void) @@ -141,6 +141,63 @@ QList<AutoPilotPluginManager::FullMode_t> PX4AutoPilotPlugin::getModes(void)
return modeList;
}
QString PX4AutoPilotPlugin::getAudioModeText(uint8_t baseMode, uint32_t customMode)
{
QString mode;
Q_ASSERT(baseMode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED);
if (baseMode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
union px4_custom_mode px4_mode;
px4_mode.data = customMode;
if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) {
mode = "manual";
} else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_ACRO) {
mode = "caro";
} else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_STABILIZED) {
mode = "stabilized";
} else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL) {
mode = "altitude control";
} else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_POSCTL) {
mode = "position control";
} else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) {
mode = "auto and ";
if (px4_mode.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_READY) {
mode += "ready";
} else if (px4_mode.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_TAKEOFF) {
mode += "taking off";
} else if (px4_mode.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_LOITER) {
mode += "loitering";
} else if (px4_mode.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_MISSION) {
mode += "following waypoints";
} else if (px4_mode.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_RTL) {
mode += "returning to land";
} else if (px4_mode.sub_mode == PX4_CUSTOM_SUB_MODE_AUTO_LAND) {
mode += "landing";
}
} else if (px4_mode.main_mode == PX4_CUSTOM_MAIN_MODE_OFFBOARD) {
mode = "offboard controlled";
}
if (baseMode != 0)
{
mode += " mode";
}
// ARMED STATE DECODING
if (baseMode & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_SAFETY)
{
mode.append(" and armed");
}
} else {
mode = "";
}
return mode;
}
QString PX4AutoPilotPlugin::getShortModeText(uint8_t baseMode, uint32_t customMode)
{
QString mode;

1
src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h

@ -53,6 +53,7 @@ public: @@ -53,6 +53,7 @@ public:
virtual const QVariantList& vehicleComponents(void);
static QList<AutoPilotPluginManager::FullMode_t> getModes(void);
static QString getAudioModeText(uint8_t baseMode, uint32_t customMode);
static QString getShortModeText(uint8_t baseMode, uint32_t customMode);
static void clearStaticData(void);

Loading…
Cancel
Save