QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
SpeedSection.h
Go to the documentation of this file.
1#pragma once
2
3#include "Section.h"
4#include "Fact.h"
5
8
9class SpeedSection : public Section
10{
11 Q_OBJECT
12
13public:
14 SpeedSection(PlanMasterController* masterController, QObject* parent = nullptr);
15
16 Q_PROPERTY(bool specifyFlightSpeed READ specifyFlightSpeed WRITE setSpecifyFlightSpeed NOTIFY specifyFlightSpeedChanged)
17 Q_PROPERTY(Fact* flightSpeed READ flightSpeed CONSTANT)
18
19 bool specifyFlightSpeed (void) const { return _specifyFlightSpeed; }
20 Fact* flightSpeed (void) { return &_flightSpeedFact; }
21 void setSpecifyFlightSpeed (bool specifyFlightSpeed);
22
25 double specifiedFlightSpeed(void) const;
26
27 // Overrides from Section
28 bool available (void) const override { return _available; }
29 bool dirty (void) const override { return _dirty; }
30 void setAvailable (bool available) override;
31 void setDirty (bool dirty) override;
32 bool scanForSection (QmlObjectListModel* visualItems, int scanIndex) override;
33 void appendSectionItems (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum) override;
34 int itemCount (void) const override;
35 bool settingsSpecified (void) const override;
36
37signals:
38 void specifyFlightSpeedChanged (bool specifyFlightSpeed);
40
41private slots:
42 void _updateSpecifiedFlightSpeed(void);
43 void _flightSpeedChanged (void);
44
45private:
46 bool _available;
47 bool _dirty;
48 bool _specifyFlightSpeed;
49 Fact _flightSpeedFact;
50
51 static QMap<QString, FactMetaData*> _metaDataMap;
52
53 static const char* _flightSpeedName;
54};
A Fact is used to hold a single value within the system.
Definition Fact.h:19
Master controller for mission, fence, rally.
Fact * flightSpeed(void)
bool dirty(void) const override
void setAvailable(bool available) override
double specifiedFlightSpeed(void) const
int itemCount(void) const override
void specifiedFlightSpeedChanged(double flightSpeed)
void setSpecifyFlightSpeed(bool specifyFlightSpeed)
void appendSectionItems(QList< MissionItem * > &items, QObject *missionItemParent, int &seqNum) override
void setDirty(bool dirty) override
bool settingsSpecified(void) const override
void specifyFlightSpeedChanged(bool specifyFlightSpeed)
bool specifyFlightSpeed READ specifyFlightSpeed WRITE setSpecifyFlightSpeed NOTIFY specifyFlightSpeedChanged(Fact *flightSpeed READ flightSpeed CONSTANT) bool specifyFlightSpeed(void) const
bool available(void) const override
bool scanForSection(QmlObjectListModel *visualItems, int scanIndex) override