QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RadioStatusFactGroup.cc
Go to the documentation of this file.
2#include "Vehicle.h"
3
4#include <QtCore/QtMath>
5
7 : FactGroup(1000, QStringLiteral(":/json/Vehicle/RadioStatusFact.json"), parent)
8{
9 _addFact(&_lrssiFact);
10 _addFact(&_rrssiFact);
11 _addFact(&_rxErrorsFact);
12 _addFact(&_fixedFact);
13 _addFact(&_txBufferFact);
14 _addFact(&_lNoiseFact);
15 _addFact(&_rNoiseFact);
16}
17
19{
20 Q_UNUSED(vehicle);
21
22 if (message.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
23 _handleRadioStatus(message);
24 }
25}
26
27void RadioStatusFactGroup::_handleRadioStatus(const mavlink_message_t &message)
28{
29 mavlink_radio_status_t rstatus{};
30 mavlink_msg_radio_status_decode(&message, &rstatus);
31
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));
36
37 // 3DR Si1k radio reports raw register values; convert to dBm per the
38 // Si1K datasheet figure 23.25 and SI AN474:
39 // inputPower = rssi * (10/19) - 127
40 // Limit to the realistic range [-120, 0] dBm. Non-Si1k radios are assumed
41 // to already be signed-8-bit dBm.
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);
45 } else {
46 rssi = static_cast<int>(static_cast<int8_t>(rstatus.rssi));
47 remrssi = static_cast<int>(static_cast<int8_t>(rstatus.remrssi));
48 }
49
50 lrssi()->setRawValue(rssi);
51 rrssi()->setRawValue(remrssi);
52 rxErrors()->setRawValue(rstatus.rxerrors);
53 fixed()->setRawValue(rstatus.fixed);
54 txBuffer()->setRawValue(rstatus.txbuf);
55 lNoise()->setRawValue(lnoise);
56 rNoise()->setRawValue(rnoise);
57
59}
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:16
void _setTelemetryAvailable(bool telemetryAvailable)
Definition FactGroup.cc:175
void _addFact(Fact *fact, const QString &name)
Definition FactGroup.cc:116
void setRawValue(const QVariant &value)
Definition Fact.cc:128
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)