forked from mavlink/qgroundcontrol
-
Notifications
You must be signed in to change notification settings - Fork 0
/
FollowMe.cc
151 lines (120 loc) · 5.3 KB
/
FollowMe.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include <QElapsedTimer>
#include <cmath>
#include "MultiVehicleManager.h"
#include "FirmwarePlugin.h"
#include "MAVLinkProtocol.h"
#include "FollowMe.h"
#include "Vehicle.h"
#include "PositionManager.h"
FollowMe::FollowMe(QGCApplication* app, QGCToolbox* toolbox)
: QGCTool(app, toolbox), estimatation_capabilities(0)
{
memset(&_motionReport, 0, sizeof(motionReport_s));
runTime.start();
_gcsMotionReportTimer.setSingleShot(false);
connect(&_gcsMotionReportTimer, &QTimer::timeout, this, &FollowMe::_sendGCSMotionReport);
}
void FollowMe::followMeHandleManager(const QString&)
{
QmlObjectListModel & vehicles = *_toolbox->multiVehicleManager()->vehicles();
for (int i=0; i< vehicles.count(); i++) {
Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles[i]);
if (vehicle->px4Firmware() && vehicle->flightMode().compare(FirmwarePlugin::px4FollowMeFlightMode, Qt::CaseInsensitive) == 0) {
_enable();
return;
}
}
_disable();
}
void FollowMe::_enable()
{
connect(_toolbox->qgcPositionManager(),
SIGNAL(positionInfoUpdated(QGeoPositionInfo)),
this,
SLOT(_setGPSLocation(QGeoPositionInfo)));
_gcsMotionReportTimer.setInterval(_toolbox->qgcPositionManager()->updateInterval());
_gcsMotionReportTimer.start();
}
void FollowMe::_disable()
{
disconnect(_toolbox->qgcPositionManager(),
SIGNAL(positionInfoUpdated(QGeoPositionInfo)),
this,
SLOT(_setGPSLocation(QGeoPositionInfo)));
_gcsMotionReportTimer.stop();
}
void FollowMe::_setGPSLocation(QGeoPositionInfo geoPositionInfo)
{
if (geoPositionInfo.isValid())
{
// get the current location coordinates
QGeoCoordinate geoCoordinate = geoPositionInfo.coordinate();
_motionReport.lat_int = geoCoordinate.latitude()*1e7;
_motionReport.lon_int = geoCoordinate.longitude()*1e7;
_motionReport.alt = geoCoordinate.altitude();
estimatation_capabilities |= (1 << POS);
// get the current eph and epv
if(geoPositionInfo.hasAttribute(QGeoPositionInfo::HorizontalAccuracy) == true) {
_motionReport.pos_std_dev[0] = _motionReport.pos_std_dev[1] = geoPositionInfo.attribute(QGeoPositionInfo::HorizontalAccuracy);
}
if(geoPositionInfo.hasAttribute(QGeoPositionInfo::VerticalAccuracy) == true) {
_motionReport.pos_std_dev[2] = geoPositionInfo.attribute(QGeoPositionInfo::VerticalAccuracy);
}
// calculate z velocity if it's available
if(geoPositionInfo.hasAttribute(QGeoPositionInfo::VerticalSpeed)) {
_motionReport.vz = geoPositionInfo.attribute(QGeoPositionInfo::VerticalSpeed);
}
// calculate x,y velocity if it's available
if((geoPositionInfo.hasAttribute(QGeoPositionInfo::Direction) == true) &&
(geoPositionInfo.hasAttribute(QGeoPositionInfo::GroundSpeed) == true)) {
estimatation_capabilities |= (1 << VEL);
qreal direction = _degreesToRadian(geoPositionInfo.attribute(QGeoPositionInfo::Direction));
qreal velocity = geoPositionInfo.attribute(QGeoPositionInfo::GroundSpeed);
_motionReport.vx = cos(direction)*velocity;
_motionReport.vy = sin(direction)*velocity;
} else {
_motionReport.vx = 0.0f;
_motionReport.vy = 0.0f;
}
}
}
void FollowMe::_sendGCSMotionReport(void)
{
QmlObjectListModel & vehicles = *_toolbox->multiVehicleManager()->vehicles();
MAVLinkProtocol* mavlinkProtocol = _toolbox->mavlinkProtocol();
mavlink_follow_target_t follow_target;
memset(&follow_target, 0, sizeof(follow_target));
follow_target.timestamp = runTime.nsecsElapsed()*1e-6;
follow_target.est_capabilities = estimatation_capabilities;
follow_target.position_cov[0] = _motionReport.pos_std_dev[0];
follow_target.position_cov[2] = _motionReport.pos_std_dev[2];
follow_target.alt = _motionReport.alt;
follow_target.lat = _motionReport.lat_int;
follow_target.lon = _motionReport.lon_int;
follow_target.vel[0] = _motionReport.vx;
follow_target.vel[1] = _motionReport.vy;
for (int i=0; i< vehicles.count(); i++) {
Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles[i]);
if(vehicle->flightMode().compare(FirmwarePlugin::px4FollowMeFlightMode, Qt::CaseInsensitive) == 0) {
mavlink_message_t message;
mavlink_msg_follow_target_encode_chan(mavlinkProtocol->getSystemId(),
mavlinkProtocol->getComponentId(),
vehicle->priorityLink()->mavlinkChannel(),
&message,
&follow_target);
vehicle->sendMessageOnLink(vehicle->priorityLink(), message);
}
}
}
double FollowMe::_degreesToRadian(double deg)
{
return deg * M_PI / 180.0;
}