11#include <QtPositioning/QGeoPositionInfo>
19 , _gcsMotionReportTimer(new QTimer(this))
23 _gcsMotionReportTimer->setSingleShot(
false);
27 _gcsMotionReportTimer->setInterval(kMotionUpdateInterval);
37 return _followMeInstance();
42 static bool once =
false;
44 (void) connect(_gcsMotionReportTimer, &QTimer::timeout,
this, &FollowMe::_sendGCSMotionReport);
52void FollowMe::_settingsChanged(QVariant value)
54 _currentMode =
static_cast<FollowMode
>(value.toUInt());
56 switch (_currentMode) {
70 _enableIfVehicleInFollow();
75void FollowMe::_enableFollowSend()
77 if (!_gcsMotionReportTimer->isActive()) {
78 _gcsMotionReportTimer->start();
82void FollowMe::_disableFollowSend()
84 if (_gcsMotionReportTimer->isActive()) {
85 _gcsMotionReportTimer->stop();
89void FollowMe::_sendGCSMotionReport()
92 const QGeoCoordinate gcsCoordinate = geoPositionInfo.coordinate();
94 if (!geoPositionInfo.isValid()) {
99 bool needFollowMe =
false;
100 if (_currentMode == MODE_ALWAYS) {
102 }
else if (_currentMode == MODE_FOLLOWME) {
104 for (
int i = 0; i < vehicles->
count(); i++) {
106 if (_isFollowFlightMode(vehicle, vehicle->
flightMode())) {
115 GCSMotionReport motionReport{};
116 uint8_t estimationCapabilities = 0;
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);
125 if (geoPositionInfo.hasAttribute(QGeoPositionInfo::Direction)) {
126 estimationCapabilities |= (1 <<
HEADING);
127 motionReport.headingDegrees = geoPositionInfo.attribute(QGeoPositionInfo::Direction);
131 if (geoPositionInfo.hasAttribute(QGeoPositionInfo::HorizontalAccuracy)) {
132 motionReport.pos_std_dev[0] = motionReport.pos_std_dev[1] = geoPositionInfo.attribute(QGeoPositionInfo::HorizontalAccuracy);
136 if (geoPositionInfo.hasAttribute(QGeoPositionInfo::VerticalAccuracy)) {
137 motionReport.pos_std_dev[2] = geoPositionInfo.attribute(QGeoPositionInfo::VerticalAccuracy);
141 if (geoPositionInfo.hasAttribute(QGeoPositionInfo::VerticalSpeed)) {
142 motionReport.vzMetersPerSec = geoPositionInfo.attribute(QGeoPositionInfo::VerticalSpeed);
146 if (geoPositionInfo.hasAttribute(QGeoPositionInfo::Direction) && geoPositionInfo.hasAttribute(QGeoPositionInfo::GroundSpeed)) {
147 estimationCapabilities |= (1 <<
VEL);
149 const qreal direction = qDegreesToRadians(geoPositionInfo.attribute(QGeoPositionInfo::Direction));
150 const qreal velocity = geoPositionInfo.attribute(QGeoPositionInfo::GroundSpeed);
152 motionReport.vxMetersPerSec = cos(direction) * velocity;
153 motionReport.vyMetersPerSec = sin(direction) * velocity;
155 motionReport.vxMetersPerSec = 0;
156 motionReport.vyMetersPerSec = 0;
161 for (
int i = 0; i < vehicles->
count(); 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;
170void FollowMe::_vehicleAdded(
Vehicle *vehicle)
173 _enableIfVehicleInFollow();
176void FollowMe::_vehicleRemoved(
Vehicle *vehicle)
179 _enableIfVehicleInFollow();
182void FollowMe::_enableIfVehicleInFollow()
184 if (_currentMode == MODE_ALWAYS) {
191 for (
int i = 0; i < vehicles->
count(); i++) {
193 if (_isFollowFlightMode(vehicle, vehicle->
flightMode())) {
199 _disableFollowSend();
202bool FollowMe::_isFollowFlightMode(
const Vehicle *vehicle,
const QString &flightMode)
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()
static MultiVehicleManager * instance()
void vehicleAdded(Vehicle *vehicle)
QmlObjectListModel * vehicles() const
void vehicleRemoved(Vehicle *vehicle)
QGeoPositionInfo geoPositionInfo() const
static QGCPositionManager * instance()
int count() const override final
static SettingsManager * instance()
AppSettings * appSettings() const
QString flightMode() const
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
QString followFlightMode() const
void flightModeChanged(const QString &flightMode)