4#include <QtCore/QtMath>
7 :
FactGroup(1000, QStringLiteral(
":/json/Vehicle/RadioStatusFact.json"), parent)
22 if (message.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
23 _handleRadioStatus(message);
29 mavlink_radio_status_t rstatus{};
30 mavlink_msg_radio_status_decode(&message, &rstatus);
32 int rssi = rstatus.rssi;
33 int remrssi = rstatus.remrssi;
34 const int lnoise =
static_cast<int>(
static_cast<int8_t
>(rstatus.noise));
35 const int rnoise =
static_cast<int>(
static_cast<int8_t
>(rstatus.remnoise));
42 if (message.sysid ==
'3' && message.compid ==
'D') {
43 rssi = qBound(-120, qRound(
static_cast<qreal
>(rssi) / 1.9 - 127.0), 0);
44 remrssi = qBound(-120, qRound(
static_cast<qreal
>(remrssi) / 1.9 - 127.0), 0);
46 rssi =
static_cast<int>(
static_cast<int8_t
>(rstatus.rssi));
47 remrssi =
static_cast<int>(
static_cast<int8_t
>(rstatus.remrssi));
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
void _setTelemetryAvailable(bool telemetryAvailable)
void _addFact(Fact *fact, const QString &name)
void setRawValue(const QVariant &value)
void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) final
Allows a FactGroup to parse incoming messages and fill in values.
RadioStatusFactGroup(QObject *parent=nullptr)