|
|
@ -510,7 +510,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) |
|
|
|
bool statechanged = false; |
|
|
|
bool statechanged = false; |
|
|
|
bool modechanged = false; |
|
|
|
bool modechanged = false; |
|
|
|
|
|
|
|
|
|
|
|
QString audiomodeText = getAudioModeTextFor(static_cast<int>(state.base_mode)); |
|
|
|
QString audiomodeText = getAudioModeTextFor(state.base_mode, state.custom_mode); |
|
|
|
|
|
|
|
|
|
|
|
if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT) |
|
|
|
if ((state.system_status != this->status) && state.system_status != MAV_STATE_UNINIT) |
|
|
|
{ |
|
|
|
{ |
|
|
@ -3141,10 +3141,16 @@ const QString& UAS::getShortState() const |
|
|
|
* hardware in the loop is being used. |
|
|
|
* hardware in the loop is being used. |
|
|
|
* @return the audio mode text for the id given. |
|
|
|
* @return the audio mode text for the id given. |
|
|
|
*/ |
|
|
|
*/ |
|
|
|
QString UAS::getAudioModeTextFor(int id) |
|
|
|
QString UAS::getAudioModeTextFor(uint8_t base_mode, uint32_t custom_mode) const |
|
|
|
{ |
|
|
|
{ |
|
|
|
|
|
|
|
QString mode = AutoPilotPluginManager::instance()->getAudioModeText(base_mode, custom_mode, autopilot); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
if (mode.length() == 0) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
// Fall back to generic decoding
|
|
|
|
|
|
|
|
|
|
|
|
QString mode; |
|
|
|
QString mode; |
|
|
|
uint8_t modeid = id; |
|
|
|
uint8_t modeid = base_mode; |
|
|
|
|
|
|
|
|
|
|
|
// BASE MODE DECODING
|
|
|
|
// BASE MODE DECODING
|
|
|
|
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO) |
|
|
|
if (modeid & (uint8_t)MAV_MODE_FLAG_DECODE_POSITION_AUTO) |
|
|
@ -3185,16 +3191,13 @@ QString UAS::getAudioModeTextFor(int id) |
|
|
|
{ |
|
|
|
{ |
|
|
|
mode.append(" using hardware in the loop simulation"); |
|
|
|
mode.append(" using hardware in the loop simulation"); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
return mode; |
|
|
|
return mode; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
/**
|
|
|
|
* The mode returned can be auto, stabilized, test, manual, preflight or unknown. |
|
|
|
* The mode returned depends on the specific autopilot used. |
|
|
|
* @return the short text of the mode for the id given. |
|
|
|
|
|
|
|
*/ |
|
|
|
|
|
|
|
/**
|
|
|
|
|
|
|
|
* The mode returned can be auto, stabilized, test, manual, preflight or unknown. |
|
|
|
|
|
|
|
* @return the short text of the mode for the id given. |
|
|
|
* @return the short text of the mode for the id given. |
|
|
|
*/ |
|
|
|
*/ |
|
|
|
QString UAS::getShortModeTextFor(uint8_t base_mode, uint32_t custom_mode) const |
|
|
|
QString UAS::getShortModeTextFor(uint8_t base_mode, uint32_t custom_mode) const |
|
|
|