QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
SpeedSection.cc
Go to the documentation of this file.
1#include "SpeedSection.h"
2#include "SimpleMissionItem.h"
4#include "Vehicle.h"
6
7const char* SpeedSection::_flightSpeedName = "FlightSpeed";
8
9QMap<QString, FactMetaData*> SpeedSection::_metaDataMap;
10
11SpeedSection::SpeedSection(PlanMasterController* masterController, QObject* parent)
12 : Section (masterController, parent)
13 , _available (false)
14 , _dirty (false)
15 , _specifyFlightSpeed (false)
16 , _flightSpeedFact (0, _flightSpeedName, FactMetaData::valueTypeDouble)
17{
18 if (_metaDataMap.isEmpty()) {
19 _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/SpeedSection.FactMetaData.json"), nullptr /* metaDataParent */);
20 }
21
22 double flightSpeed = 0;
25 } else {
27 }
28
29 _metaDataMap[_flightSpeedName]->setRawDefaultValue(flightSpeed);
30 _flightSpeedFact.setMetaData(_metaDataMap[_flightSpeedName]);
31 _flightSpeedFact.setRawValue(flightSpeed);
32
34 connect(&_flightSpeedFact, &Fact::valueChanged, this, &SpeedSection::_flightSpeedChanged);
35
36 connect(this, &SpeedSection::specifyFlightSpeedChanged, this, &SpeedSection::_updateSpecifiedFlightSpeed);
37 connect(&_flightSpeedFact, &Fact::valueChanged, this, &SpeedSection::_updateSpecifiedFlightSpeed);
38}
39
41{
42 return _specifyFlightSpeed;
43}
44
45void SpeedSection::setAvailable(bool available)
46{
47 if (available != _available) {
49 _available = available;
51 }
52 }
53}
54
55void SpeedSection::setDirty(bool dirty)
56{
57 if (_dirty != dirty) {
58 _dirty = dirty;
59 emit dirtyChanged(_dirty);
60 }
61}
62
63void SpeedSection::setSpecifyFlightSpeed(bool specifyFlightSpeed)
64{
65 if (specifyFlightSpeed != _specifyFlightSpeed) {
66 _specifyFlightSpeed = specifyFlightSpeed;
67 emit specifyFlightSpeedChanged(specifyFlightSpeed);
68 setDirty(true);
70 }
71}
72
74{
75 return _specifyFlightSpeed ? 1: 0;
76}
77
78void SpeedSection::appendSectionItems(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum)
79{
80 // IMPORTANT NOTE: If anything changes here you must also change SpeedSection::scanForSettings
81
82 if (_specifyFlightSpeed) {
83 MissionItem* item = new MissionItem(seqNum++,
84 MAV_CMD_DO_CHANGE_SPEED,
85 MAV_FRAME_MISSION,
86 _masterController->controllerVehicle()->multiRotor() ? 1 /* groundspeed */ : 0 /* airspeed */, // Change airspeed or groundspeed
87 _flightSpeedFact.rawValue().toDouble(),
88 -1, // No throttle change
89 0, // Absolute speed change
90 0, 0, 0, // param 5-7 not used
91 true, // autoContinue
92 false, // isCurrentItem
93 missionItemParent);
94 items.append(item);
95 }
96}
97
98bool SpeedSection::scanForSection(QmlObjectListModel* visualItems, int scanIndex)
99{
100 if (!_available || scanIndex >= visualItems->count()) {
101 return false;
102 }
103
104 SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
105 if (!item) {
106 // We hit a complex item, there can't be a speed setting
107 return false;
108 }
109 MissionItem& missionItem = item->missionItem();
110
111 // See SpeedSection::appendMissionItems for specs on what consitutes a known speed setting
112
113 if (missionItem.command() == MAV_CMD_DO_CHANGE_SPEED && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
114 if (_masterController->controllerVehicle()->multiRotor() && missionItem.param1() != 1) {
115 return false;
116 } else if (_masterController->controllerVehicle()->fixedWing() && missionItem.param1() != 0) {
117 return false;
118 }
119 visualItems->removeAt(scanIndex)->deleteLater();
120 _flightSpeedFact.setRawValue(missionItem.param2());
122 return true;
123 }
124
125 return false;
126}
127
128
130{
131 return _specifyFlightSpeed ? _flightSpeedFact.rawValue().toDouble() : std::numeric_limits<double>::quiet_NaN();
132}
133
134void SpeedSection::_updateSpecifiedFlightSpeed(void)
135{
136 if (_specifyFlightSpeed) {
138 }
139}
140
141void SpeedSection::_flightSpeedChanged(void)
142{
143 // We only set the dirty bit if specify flight speed it set. This allows us to change defaults for flight speed
144 // without affecting dirty.
145 if (_specifyFlightSpeed) {
146 setDirty(true);
147 }
148}
static QMap< QString, FactMetaData * > createMapFromJsonFile(const QString &jsonFilename, QObject *metaDataParent)
void valueChanged(const QVariant &value)
This signal is only meant for use by the QT property system. It should not be connected to by client ...
MAV_CMD command(void) const
Definition MissionItem.h:49
double param5(void) const
Definition MissionItem.h:58
double param7(void) const
Definition MissionItem.h:60
double param3(void) const
Definition MissionItem.h:56
double param6(void) const
Definition MissionItem.h:59
double param1(void) const
Definition MissionItem.h:54
double param4(void) const
Definition MissionItem.h:57
double param2(void) const
Definition MissionItem.h:55
Master controller for mission, fence, rally.
Vehicle * controllerVehicle(void)
T value(int index) const
QObject * removeAt(int index)
int count() const override final
void dirtyChanged(bool dirty)
PlanMasterController * _masterController
Definition Section.h:59
void itemCountChanged(int itemCount)
bool available READ available WRITE setAvailable NOTIFY availableChanged(bool settingsSpecified READ settingsSpecified NOTIFY settingsSpecifiedChanged) 1(bool dirty READ dirty WRITE setDirty NOTIFY availableChanged) virtual bool available(void) const =0
void settingsSpecifiedChanged(bool settingsSpecified)
A SimpleMissionItem is used to represent a single MissionItem to the ui.
MissionItem & missionItem(void)
Fact * flightSpeed(void)
bool dirty(void) const override
void setAvailable(bool available) override
double specifiedFlightSpeed(void) const
int itemCount(void) const override
SpeedSection(PlanMasterController *masterController, QObject *parent=nullptr)
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
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
bool multiRotor() const
Definition Vehicle.cc:1864
double defaultHoverSpeed() const
Definition Vehicle.h:525
bool fixedWing() const
Definition Vehicle.cc:1844
double defaultCruiseSpeed() const
Definition Vehicle.h:524