QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleDistanceSensorFactGroup.h
Go to the documentation of this file.
1#pragma once
2
3#include "FactGroup.h"
4
6{
7 Q_OBJECT
8 Q_PROPERTY(Fact *rotationNone READ rotationNone CONSTANT)
9 Q_PROPERTY(Fact *rotationYaw45 READ rotationYaw45 CONSTANT)
10 Q_PROPERTY(Fact *rotationYaw90 READ rotationYaw90 CONSTANT)
11 Q_PROPERTY(Fact *rotationYaw135 READ rotationYaw135 CONSTANT)
12 Q_PROPERTY(Fact *rotationYaw180 READ rotationYaw180 CONSTANT)
13 Q_PROPERTY(Fact *rotationYaw225 READ rotationYaw225 CONSTANT)
14 Q_PROPERTY(Fact *rotationYaw270 READ rotationYaw270 CONSTANT)
15 Q_PROPERTY(Fact *rotationYaw315 READ rotationYaw315 CONSTANT)
16 Q_PROPERTY(Fact *rotationPitch90 READ rotationPitch90 CONSTANT)
17 Q_PROPERTY(Fact *rotationPitch270 READ rotationPitch270 CONSTANT)
18 Q_PROPERTY(Fact *minDistance READ minDistance CONSTANT)
19 Q_PROPERTY(Fact *maxDistance READ maxDistance CONSTANT)
20
21public:
22 explicit VehicleDistanceSensorFactGroup(QObject *parent = nullptr);
23
24 Fact *rotationNone() { return &_rotationNoneFact; }
25 Fact *rotationYaw45() { return &_rotationYaw45Fact; }
26 Fact *rotationYaw90() { return &_rotationYaw90Fact; }
27 Fact *rotationYaw135() { return &_rotationYaw135Fact; }
28 Fact *rotationYaw180() { return &_rotationYaw180Fact; }
29 Fact *rotationYaw225() { return &_rotationYaw225Fact; }
30 Fact *rotationYaw270() { return &_rotationYaw270Fact; }
31 Fact *rotationYaw315() { return &_rotationYaw315Fact; }
32 Fact *rotationPitch90() { return &_rotationPitch90Fact; }
33 Fact *rotationPitch270() { return &_rotationPitch270Fact; }
34 Fact *minDistance() { return &_minDistanceFact; }
35 Fact *maxDistance() { return &_maxDistanceFact; }
36
37 // Overrides from FactGroup
38 void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) final;
39
40private:
41 Fact _rotationNoneFact = Fact(0, QStringLiteral("rotationNone"), FactMetaData::valueTypeDouble);
42 Fact _rotationYaw45Fact = Fact(0, QStringLiteral("rotationYaw45"), FactMetaData::valueTypeDouble);
43 Fact _rotationYaw90Fact = Fact(0, QStringLiteral("rotationYaw90"), FactMetaData::valueTypeDouble);
44 Fact _rotationYaw135Fact = Fact(0, QStringLiteral("rotationYaw135"), FactMetaData::valueTypeDouble);
45 Fact _rotationYaw180Fact = Fact(0, QStringLiteral("rotationYaw180"), FactMetaData::valueTypeDouble);
46 Fact _rotationYaw225Fact = Fact(0, QStringLiteral("rotationYaw225"), FactMetaData::valueTypeDouble);
47 Fact _rotationYaw270Fact = Fact(0, QStringLiteral("rotationYaw270"), FactMetaData::valueTypeDouble);
48 Fact _rotationYaw315Fact = Fact(0, QStringLiteral("rotationYaw315"), FactMetaData::valueTypeDouble);
49 Fact _rotationPitch90Fact = Fact(0, QStringLiteral("rotationPitch90"), FactMetaData::valueTypeDouble);
50 Fact _rotationPitch270Fact = Fact(0, QStringLiteral("rotationPitch270"), FactMetaData::valueTypeDouble);
51 Fact _minDistanceFact = Fact(0, QStringLiteral("minDistance"), FactMetaData::valueTypeDouble);
52 Fact _maxDistanceFact = Fact(0, QStringLiteral("maxDistance"), FactMetaData::valueTypeDouble);
53};
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:19
A Fact is used to hold a single value within the system.
Definition Fact.h:19