QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
FollowMe.cc
Go to the documentation of this file.
2#include "FollowMe.h"
4#include "FirmwarePlugin.h"
5#include "Vehicle.h"
6#include "PositionManager.h"
7#include "SettingsManager.h"
8#include "AppSettings.h"
10
11#include <QtPositioning/QGeoPositionInfo>
12
13QGC_LOGGING_CATEGORY(FollowMeLog, "API.FollowMe")
14
15Q_APPLICATION_STATIC(FollowMe, _followMeInstance);
16
17FollowMe::FollowMe(QObject *parent)
18 : QObject(parent)
19 , _gcsMotionReportTimer(new QTimer(this))
20{
21 // qCDebug(FollowMeLog) << Q_FUNC_INFO << this;
22
23 _gcsMotionReportTimer->setSingleShot(false);
24 // We set the update interval to a fixed amount of time.
25 // Even if the device can't update this quickly we'll pick up a new value on the next time around.
26 // We can't trust the value for update interval which comes from the actual device.
27 _gcsMotionReportTimer->setInterval(kMotionUpdateInterval);
28}
29
31{
32 // qCDebug(FollowMeLog) << Q_FUNC_INFO << this;
33}
34
36{
37 return _followMeInstance();
38}
39
41{
42 static bool once = false;
43 if (!once) {
44 (void) connect(_gcsMotionReportTimer, &QTimer::timeout, this, &FollowMe::_sendGCSMotionReport);
45 (void) connect(SettingsManager::instance()->appSettings()->followTarget(), &Fact::rawValueChanged, this, &FollowMe::_settingsChanged);
46
47 _settingsChanged(SettingsManager::instance()->appSettings()->followTarget()->rawValue());
48 }
49 once = true;
50}
51
52void FollowMe::_settingsChanged(QVariant value)
53{
54 _currentMode = static_cast<FollowMode>(value.toUInt());
55
56 switch (_currentMode) {
57 case MODE_NEVER:
58 (void) disconnect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded);
59 (void) disconnect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved);
60 _disableFollowSend();
61 break;
62 case MODE_ALWAYS:
63 (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded);
64 (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved);
65 _enableFollowSend();
66 break;
67 case MODE_FOLLOWME:
68 (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleAdded, this, &FollowMe::_vehicleAdded);
69 (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::vehicleRemoved, this, &FollowMe::_vehicleRemoved);
70 _enableIfVehicleInFollow();
71 break;
72 }
73}
74
75void FollowMe::_enableFollowSend()
76{
77 if (!_gcsMotionReportTimer->isActive()) {
78 _gcsMotionReportTimer->start();
79 }
80}
81
82void FollowMe::_disableFollowSend()
83{
84 if (_gcsMotionReportTimer->isActive()) {
85 _gcsMotionReportTimer->stop();
86 }
87}
88
89void FollowMe::_sendGCSMotionReport()
90{
91 const QGeoPositionInfo geoPositionInfo = QGCPositionManager::instance()->geoPositionInfo();
92 const QGeoCoordinate gcsCoordinate = geoPositionInfo.coordinate();
93
94 if (!geoPositionInfo.isValid()) {
95 return;
96 }
97
98 // First check to see if any vehicles need follow me updates
99 bool needFollowMe = false;
100 if (_currentMode == MODE_ALWAYS) {
101 needFollowMe = true;
102 } else if (_currentMode == MODE_FOLLOWME) {
104 for (int i = 0; i < vehicles->count(); i++) {
105 const Vehicle* const vehicle = vehicles->value<const Vehicle*>(i);
106 if (_isFollowFlightMode(vehicle, vehicle->flightMode())) {
107 needFollowMe = true;
108 }
109 }
110 }
111 if (!needFollowMe) {
112 return;
113 }
114
115 GCSMotionReport motionReport{};
116 uint8_t estimationCapabilities = 0;
117
118 // Get the current location coordinates
119 // Important note: QGC only supports sending the constant GCS home position altitude for follow me.
120 motionReport.lat_int = static_cast<int>(gcsCoordinate.latitude() * 1e7);
121 motionReport.lon_int = static_cast<int>(gcsCoordinate.longitude() * 1e7);
122 motionReport.altMetersAMSL = gcsCoordinate.altitude();
123 estimationCapabilities |= (1 << POS);
124
125 if (geoPositionInfo.hasAttribute(QGeoPositionInfo::Direction)) {
126 estimationCapabilities |= (1 << HEADING);
127 motionReport.headingDegrees = geoPositionInfo.attribute(QGeoPositionInfo::Direction);
128 }
129
130 // get the current eph
131 if (geoPositionInfo.hasAttribute(QGeoPositionInfo::HorizontalAccuracy)) {
132 motionReport.pos_std_dev[0] = motionReport.pos_std_dev[1] = geoPositionInfo.attribute(QGeoPositionInfo::HorizontalAccuracy);
133 }
134
135 // get the current epv
136 if (geoPositionInfo.hasAttribute(QGeoPositionInfo::VerticalAccuracy)) {
137 motionReport.pos_std_dev[2] = geoPositionInfo.attribute(QGeoPositionInfo::VerticalAccuracy);
138 }
139
140 // calculate z velocity if it's available
141 if (geoPositionInfo.hasAttribute(QGeoPositionInfo::VerticalSpeed)) {
142 motionReport.vzMetersPerSec = geoPositionInfo.attribute(QGeoPositionInfo::VerticalSpeed);
143 }
144
145 // calculate x,y velocity if it's available
146 if (geoPositionInfo.hasAttribute(QGeoPositionInfo::Direction) && geoPositionInfo.hasAttribute(QGeoPositionInfo::GroundSpeed)) {
147 estimationCapabilities |= (1 << VEL);
148
149 const qreal direction = qDegreesToRadians(geoPositionInfo.attribute(QGeoPositionInfo::Direction));
150 const qreal velocity = geoPositionInfo.attribute(QGeoPositionInfo::GroundSpeed);
151
152 motionReport.vxMetersPerSec = cos(direction) * velocity;
153 motionReport.vyMetersPerSec = sin(direction) * velocity;
154 } else {
155 motionReport.vxMetersPerSec = 0;
156 motionReport.vyMetersPerSec = 0;
157 }
158
160
161 for (int i = 0; i < vehicles->count(); i++) {
162 Vehicle* const vehicle = vehicles->value<Vehicle*>(i);
163 if ((_currentMode == MODE_ALWAYS) || (_isFollowFlightMode(vehicle, vehicle->flightMode()))) {
164 qCDebug(FollowMeLog) << "sendGCSMotionReport latInt:lonInt:altMetersAMSL" << motionReport.lat_int << motionReport.lon_int << motionReport.altMetersAMSL;
165 vehicle->firmwarePlugin()->sendGCSMotionReport(vehicle, motionReport, estimationCapabilities);
166 }
167 }
168}
169
170void FollowMe::_vehicleAdded(Vehicle *vehicle)
171{
172 (void) connect(vehicle, &Vehicle::flightModeChanged, this, &FollowMe::_enableIfVehicleInFollow);
173 _enableIfVehicleInFollow();
174}
175
176void FollowMe::_vehicleRemoved(Vehicle *vehicle)
177{
178 (void) disconnect(vehicle, &Vehicle::flightModeChanged, this, &FollowMe::_enableIfVehicleInFollow);
179 _enableIfVehicleInFollow();
180}
181
182void FollowMe::_enableIfVehicleInFollow()
183{
184 if (_currentMode == MODE_ALWAYS) {
185 return;
186 }
187
188 // Any vehicle in follow mode will enable the system
190
191 for (int i = 0; i < vehicles->count(); i++) {
192 const Vehicle* const vehicle = vehicles->value<const Vehicle*>(i);
193 if (_isFollowFlightMode(vehicle, vehicle->flightMode())) {
194 _enableFollowSend();
195 return;
196 }
197 }
198
199 _disableFollowSend();
200}
201
202bool FollowMe::_isFollowFlightMode(const Vehicle *vehicle, const QString &flightMode)
203{
204 return (flightMode.compare(vehicle->followFlightMode()) == 0);
205}
Q_APPLICATION_STATIC(FollowMe, _followMeInstance)
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void rawValueChanged(const QVariant &value)
virtual void sendGCSMotionReport(Vehicle *vehicle, const FollowMe::GCSMotionReport &motionReport, uint8_t estimationCapabilities) const
Sends the appropriate mavlink message for follow me support.
static FollowMe * instance()
Definition FollowMe.cc:35
~FollowMe()
Definition FollowMe.cc:30
void init()
Definition FollowMe.cc:40
@ HEADING
Definition FollowMe.h:38
static MultiVehicleManager * instance()
void vehicleAdded(Vehicle *vehicle)
QmlObjectListModel * vehicles() const
void vehicleRemoved(Vehicle *vehicle)
QGeoPositionInfo geoPositionInfo() const
static QGCPositionManager * instance()
T value(int index) const
int count() const override final
static SettingsManager * instance()
AppSettings * appSettings() const
QString flightMode() const
Definition Vehicle.cc:1468
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
Definition Vehicle.h:444
QString followFlightMode() const
Definition Vehicle.cc:2563
void flightModeChanged(const QString &flightMode)