QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleSetpointFactGroup.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 *roll READ roll CONSTANT)
9 Q_PROPERTY(Fact *pitch READ pitch CONSTANT)
10 Q_PROPERTY(Fact *yaw READ yaw CONSTANT)
11 Q_PROPERTY(Fact *rollRate READ rollRate CONSTANT)
12 Q_PROPERTY(Fact *pitchRate READ pitchRate CONSTANT)
13 Q_PROPERTY(Fact *yawRate READ yawRate CONSTANT)
14
15public:
16 explicit VehicleSetpointFactGroup(QObject *parent = nullptr);
17
18 Fact *roll() { return &_rollFact; }
19 Fact *pitch() { return &_pitchFact; }
20 Fact *yaw() { return &_yawFact; }
21 Fact *rollRate() { return &_rollRateFact; }
22 Fact *pitchRate() { return &_pitchRateFact; }
23 Fact *yawRate() { return &_yawRateFact; }
24
25 // Overrides from FactGroup
26 void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) final;
27
28private:
29 Fact _rollFact = Fact(0, QStringLiteral("roll"), FactMetaData::valueTypeDouble);
30 Fact _pitchFact = Fact(0, QStringLiteral("pitch"), FactMetaData::valueTypeDouble);
31 Fact _yawFact = Fact(0, QStringLiteral("yaw"), FactMetaData::valueTypeDouble);
32 Fact _rollRateFact = Fact(0, QStringLiteral("rollRate"), FactMetaData::valueTypeDouble);
33 Fact _pitchRateFact = Fact(0, QStringLiteral("pitchRate"), FactMetaData::valueTypeDouble);
34 Fact _yawRateFact = Fact(0, QStringLiteral("yawRate"), FactMetaData::valueTypeDouble);
35};
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