Commit 20e14910 authored by Lorenz Meier's avatar Lorenz Meier

Decode radio status and emit signal. Not used anywhere yet

parent 89de2115
...@@ -308,6 +308,16 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) ...@@ -308,6 +308,16 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
} }
} }
if(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS)
{
// process telemetry status message
mavlink_radio_status_t rstatus;
mavlink_msg_radio_status_decode(&message, &rstatus);
emit radioStatusChanged(link, rstatus.rxerrors, rstatus.fixed, rstatus.rssi, rstatus.remrssi,
rstatus.txbuf, rstatus.noise, rstatus.remnoise);
}
#if defined(QGC_PROTOBUF_ENABLED) #if defined(QGC_PROTOBUF_ENABLED)
if (message.msgid == MAVLINK_MSG_ID_EXTENDED_MESSAGE) if (message.msgid == MAVLINK_MSG_ID_EXTENDED_MESSAGE)
......
...@@ -276,6 +276,19 @@ signals: ...@@ -276,6 +276,19 @@ signals:
void actionGuardChanged(bool enabled); void actionGuardChanged(bool enabled);
/** @brief Emitted if actiion request timeout changed */ /** @brief Emitted if actiion request timeout changed */
void actionRetransmissionTimeoutChanged(int ms); void actionRetransmissionTimeoutChanged(int ms);
/**
* @brief Emitted if a new radio status packet received
*
* @param rxerrors receive errors
* @param fixed count of error corrected packets
* @param rssi local signal strength
* @param remrssi remote signal strength
* @param txbuf how full the tx buffer is as a percentage
* @param noise background noise level
* @param remnoise remote background noise level
*/
void radioStatusChanged(LinkInterface* link, unsigned rxerrors, unsigned fixed, unsigned rssi, unsigned remrssi,
unsigned txbuf, unsigned noise, unsigned remnoise);
}; };
#endif // MAVLINKPROTOCOL_H_ #endif // MAVLINKPROTOCOL_H_
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