QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RadioStatusFactGroup.h
Go to the documentation of this file.
1
#pragma once
2
3
#include "
FactGroup.h
"
4
13
class
RadioStatusFactGroup
:
public
FactGroup
14
{
15
Q_OBJECT
16
Q_PROPERTY(
Fact
*
lrssi
READ
lrssi
CONSTANT)
17
Q_PROPERTY(
Fact
*
rrssi
READ
rrssi
CONSTANT)
18
Q_PROPERTY(
Fact
*
rxErrors
READ
rxErrors
CONSTANT)
19
Q_PROPERTY(
Fact
*
fixed
READ
fixed
CONSTANT)
20
Q_PROPERTY(
Fact
*
txBuffer
READ
txBuffer
CONSTANT)
21
Q_PROPERTY(
Fact
*
lNoise
READ
lNoise
CONSTANT)
22
Q_PROPERTY(
Fact
*
rNoise
READ
rNoise
CONSTANT)
23
24
public
:
25
explicit
RadioStatusFactGroup
(QObject *parent =
nullptr
);
26
27
Fact
*
lrssi
() {
return
&_lrssiFact; }
28
Fact
*
rrssi
() {
return
&_rrssiFact; }
29
Fact
*
rxErrors
() {
return
&_rxErrorsFact; }
30
Fact
*
fixed
() {
return
&_fixedFact; }
31
Fact
*
txBuffer
() {
return
&_txBufferFact; }
32
Fact
*
lNoise
() {
return
&_lNoiseFact; }
33
Fact
*
rNoise
() {
return
&_rNoiseFact; }
34
35
void
handleMessage
(
Vehicle
*vehicle,
const
mavlink_message_t
&message)
final
;
36
37
private
:
38
void
_handleRadioStatus(
const
mavlink_message_t
&message);
39
40
Fact
_lrssiFact =
Fact
(0, QStringLiteral(
"lrssi"
),
FactMetaData::valueTypeInt16
);
41
Fact
_rrssiFact =
Fact
(0, QStringLiteral(
"rrssi"
),
FactMetaData::valueTypeInt16
);
42
Fact
_rxErrorsFact =
Fact
(0, QStringLiteral(
"rxErrors"
),
FactMetaData::valueTypeUint32
);
43
Fact
_fixedFact =
Fact
(0, QStringLiteral(
"fixed"
),
FactMetaData::valueTypeUint32
);
44
Fact
_txBufferFact =
Fact
(0, QStringLiteral(
"txBuffer"
),
FactMetaData::valueTypeUint32
);
45
Fact
_lNoiseFact =
Fact
(0, QStringLiteral(
"lNoise"
),
FactMetaData::valueTypeInt16
);
46
Fact
_rNoiseFact =
Fact
(0, QStringLiteral(
"rNoise"
),
FactMetaData::valueTypeInt16
);
47
};
FactGroup.h
mavlink_message_t
struct __mavlink_message mavlink_message_t
Definition
QGCCorePlugin.h:24
FactGroup
Used to group Facts together into an object hierarachy.
Definition
FactGroup.h:16
FactMetaData::valueTypeInt16
@ valueTypeInt16
Definition
FactMetaData.h:28
FactMetaData::valueTypeUint32
@ valueTypeUint32
Definition
FactMetaData.h:29
Fact
A Fact is used to hold a single value within the system.
Definition
Fact.h:17
RadioStatusFactGroup
Radio link telemetry decoded from MAVLINK_MSG_ID_RADIO_STATUS.
Definition
RadioStatusFactGroup.h:14
RadioStatusFactGroup::rNoise
Fact * rNoise()
Definition
RadioStatusFactGroup.h:33
RadioStatusFactGroup::handleMessage
void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) final
Allows a FactGroup to parse incoming messages and fill in values.
Definition
RadioStatusFactGroup.cc:18
RadioStatusFactGroup::txBuffer
Fact * txBuffer()
Definition
RadioStatusFactGroup.h:31
RadioStatusFactGroup::rrssi
Fact * rrssi()
Definition
RadioStatusFactGroup.h:28
RadioStatusFactGroup::lNoise
Fact * lNoise()
Definition
RadioStatusFactGroup.h:32
RadioStatusFactGroup::lrssi
Fact * lrssi()
Definition
RadioStatusFactGroup.h:27
RadioStatusFactGroup::fixed
Fact * fixed()
Definition
RadioStatusFactGroup.h:30
RadioStatusFactGroup::rxErrors
Fact * rxErrors()
Definition
RadioStatusFactGroup.h:29
Vehicle
Definition
Vehicle.h:86
src
Vehicle
FactGroups
RadioStatusFactGroup.h
Generated by
1.9.8