Vehicle.cc 176 KB
Newer Older
1
2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4
5
6
7
8
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
dogmaphobic's avatar
dogmaphobic committed
9

dheideman's avatar
dheideman committed
10
11
12
#include <QTime>
#include <QDateTime>
#include <QLocale>
DonLakeFlyer's avatar
DonLakeFlyer committed
13
#include <QQuaternion>
14

15
16
#include <Eigen/Eigen>

17
18
19
20
21
#include "Vehicle.h"
#include "MAVLinkProtocol.h"
#include "FirmwarePluginManager.h"
#include "LinkManager.h"
#include "FirmwarePlugin.h"
22
#include "UAS.h"
Don Gagne's avatar
Don Gagne committed
23
#include "JoystickManager.h"
Don Gagne's avatar
Don Gagne committed
24
#include "MissionManager.h"
Don Gagne's avatar
Don Gagne committed
25
#include "MissionController.h"
26
#include "PlanMasterController.h"
27
28
#include "GeoFenceManager.h"
#include "RallyPointManager.h"
Don Gagne's avatar
Don Gagne committed
29
#include "CoordinateVector.h"
30
#include "ParameterManager.h"
31
#include "QGCApplication.h"
dogmaphobic's avatar
dogmaphobic committed
32
#include "QGCImageProvider.h"
33
#include "MissionCommandTree.h"
34
#include "QGroundControlQmlGlobal.h"
35
#include "SettingsManager.h"
36
#include "QGCQGeoCoordinate.h"
37
#include "QGCCorePlugin.h"
Don Gagne's avatar
   
Don Gagne committed
38
#include "QGCOptions.h"
DonLakeFlyer's avatar
   
DonLakeFlyer committed
39
#include "ADSBVehicleManager.h"
Gus Grubba's avatar
Gus Grubba committed
40
#include "QGCCameraManager.h"
41
42
#include "VideoReceiver.h"
#include "VideoManager.h"
43
#include "VideoSettings.h"
Don Gagne's avatar
   
Don Gagne committed
44
#include "PositionManager.h"
Gus Grubba's avatar
Gus Grubba committed
45
#include "VehicleObjectAvoidance.h"
DonLakeFlyer's avatar
   
DonLakeFlyer committed
46
#include "TrajectoryPoints.h"
Matej Frančeškin's avatar
Matej Frančeškin committed
47
#include "QGCGeo.h"
Gus Grubba's avatar
Gus Grubba committed
48

49
50
51
52
#if defined(QGC_AIRMAP_ENABLED)
#include "AirspaceVehicleManager.h"
#endif

53
54
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")

55
56
57
58
#define UPDATE_TIMER 50
#define DEFAULT_LAT  38.965767f
#define DEFAULT_LON -120.083923f

DonLakeFlyer's avatar
DonLakeFlyer committed
59
const QString guided_mode_not_supported_by_vehicle = QObject::tr("Guided mode not supported by Vehicle.");
60

Don Gagne's avatar
Don Gagne committed
61
62
63
const char* Vehicle::_settingsGroup =               "Vehicle%1";        // %1 replaced with mavlink system id
const char* Vehicle::_joystickModeSettingsKey =     "JoystickMode";
const char* Vehicle::_joystickEnabledSettingsKey =  "JoystickEnabled";
64

Don Gagne's avatar
Don Gagne committed
65
66
67
const char* Vehicle::_rollFactName =                "roll";
const char* Vehicle::_pitchFactName =               "pitch";
const char* Vehicle::_headingFactName =             "heading";
DonLakeFlyer's avatar
DonLakeFlyer committed
68
69
70
const char* Vehicle::_rollRateFactName =             "rollRate";
const char* Vehicle::_pitchRateFactName =           "pitchRate";
const char* Vehicle::_yawRateFactName =             "yawRate";
Don Gagne's avatar
Don Gagne committed
71
72
73
74
75
const char* Vehicle::_airSpeedFactName =            "airSpeed";
const char* Vehicle::_groundSpeedFactName =         "groundSpeed";
const char* Vehicle::_climbRateFactName =           "climbRate";
const char* Vehicle::_altitudeRelativeFactName =    "altitudeRelative";
const char* Vehicle::_altitudeAMSLFactName =        "altitudeAMSL";
76
const char* Vehicle::_flightDistanceFactName =      "flightDistance";
77
const char* Vehicle::_flightTimeFactName =          "flightTime";
78
const char* Vehicle::_distanceToHomeFactName =      "distanceToHome";
79
const char* Vehicle::_headingToNextWPFactName =     "headingToNextWP";
Don Gagne's avatar
   
Don Gagne committed
80
const char* Vehicle::_headingToHomeFactName =       "headingToHome";
Don Gagne's avatar
   
Don Gagne committed
81
const char* Vehicle::_distanceToGCSFactName =       "distanceToGCS";
82
const char* Vehicle::_hobbsFactName =               "hobbs";
Don Gagne's avatar
   
Don Gagne committed
83
const char* Vehicle::_throttlePctFactName =         "throttlePct";
Don Gagne's avatar
Don Gagne committed
84

85
86
87
88
89
90
91
92
93
const char* Vehicle::_gpsFactGroupName =                "gps";
const char* Vehicle::_battery1FactGroupName =           "battery";
const char* Vehicle::_battery2FactGroupName =           "battery2";
const char* Vehicle::_windFactGroupName =               "wind";
const char* Vehicle::_vibrationFactGroupName =          "vibration";
const char* Vehicle::_temperatureFactGroupName =        "temperature";
const char* Vehicle::_clockFactGroupName =              "clock";
const char* Vehicle::_distanceSensorFactGroupName =     "distanceSensor";
const char* Vehicle::_estimatorStatusFactGroupName =    "estimatorStatus";
Don Gagne's avatar
Don Gagne committed
94

Don Gagne's avatar
   
Don Gagne committed
95
// Standard connected vehicle
96
97
Vehicle::Vehicle(LinkInterface*             link,
                 int                        vehicleId,
98
                 int                        defaultComponentId,
99
100
101
102
                 MAV_AUTOPILOT              firmwareType,
                 MAV_TYPE                   vehicleType,
                 FirmwarePluginManager*     firmwarePluginManager,
                 JoystickManager*           joystickManager)
Don Gagne's avatar
Don Gagne committed
103
104
    : FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json")
    , _id(vehicleId)
105
    , _defaultComponentId(defaultComponentId)
Don Gagne's avatar
Don Gagne committed
106
    , _active(false)
107
    , _offlineEditingVehicle(false)
108
    , _firmwareType(firmwareType)
109
    , _vehicleType(vehicleType)
110
111
112
113
    , _firmwarePlugin(nullptr)
    , _firmwarePluginInstanceData(nullptr)
    , _autopilotPlugin(nullptr)
    , _mavlink(nullptr)
Don Gagne's avatar
Don Gagne committed
114
    , _soloFirmware(false)
115
116
    , _toolbox(qgcApp()->toolbox())
    , _settingsManager(_toolbox->settingsManager())
117
    , _joystickMode(JoystickModeRC)
Don Gagne's avatar
Don Gagne committed
118
    , _joystickEnabled(false)
119
120
    , _uas(nullptr)
    , _mav(nullptr)
121
122
123
124
125
126
127
    , _currentMessageCount(0)
    , _messageCount(0)
    , _currentErrorCount(0)
    , _currentWarningCount(0)
    , _currentNormalCount(0)
    , _currentMessageType(MessageNone)
    , _updateCount(0)
128
    , _rcRSSI(255)
129
    , _rcRSSIstore(255.)
Don Gagne's avatar
Don Gagne committed
130
    , _autoDisconnect(false)
Don Gagne's avatar
Don Gagne committed
131
    , _flying(false)
132
    , _landing(false)
Don Gagne's avatar
Don Gagne committed
133
    , _vtolInFwdFlight(false)
134
135
136
137
    , _onboardControlSensorsPresent(0)
    , _onboardControlSensorsEnabled(0)
    , _onboardControlSensorsHealth(0)
    , _onboardControlSensorsUnhealthy(0)
138
139
    , _gpsRawIntMessageAvailable(false)
    , _globalPositionIntMessageAvailable(false)
DonLakeFlyer's avatar
DonLakeFlyer committed
140
141
    , _defaultCruiseSpeed(_settingsManager->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
    , _defaultHoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
Gus Grubba's avatar
Gus Grubba committed
142
143
144
145
146
147
148
    , _telemetryRRSSI(0)
    , _telemetryLRSSI(0)
    , _telemetryRXErrors(0)
    , _telemetryFixed(0)
    , _telemetryTXBuffer(0)
    , _telemetryLNoise(0)
    , _telemetryRNoise(0)
Don Gagne's avatar
Don Gagne committed
149
    , _highLatencyLink(false)
150
    , _receivingAttitudeQuaternion(false)
151
    , _cameras(nullptr)
152
153
    , _connectionLost(false)
    , _connectionLostEnabled(true)
DonLakeFlyer's avatar
DonLakeFlyer committed
154
    , _initialPlanRequestComplete(false)
155
    , _missionManager(nullptr)
156
    , _missionManagerInitialRequestSent(false)
157
    , _geoFenceManager(nullptr)
158
    , _geoFenceManagerInitialRequestSent(false)
159
    , _rallyPointManager(nullptr)
160
    , _rallyPointManagerInitialRequestSent(false)
161
#if defined(QGC_AIRMAP_ENABLED)
162
    , _airspaceVehicleManager(nullptr)
163
#endif
Don Gagne's avatar
Don Gagne committed
164
165
166
    , _armed(false)
    , _base_mode(0)
    , _custom_mode(0)
167
    , _nextSendMessageMultipleIndex(0)
DonLakeFlyer's avatar
   
DonLakeFlyer committed
168
    , _trajectoryPoints(new TrajectoryPoints(this, this))
169
170
    , _firmwarePluginManager(firmwarePluginManager)
    , _joystickManager(joystickManager)
dogmaphobic's avatar
dogmaphobic committed
171
    , _flowImageIndex(0)
Don Gagne's avatar
Don Gagne committed
172
    , _allLinksInactiveSent(false)
173
174
175
176
177
178
    , _messagesReceived(0)
    , _messagesSent(0)
    , _messagesLost(0)
    , _messageSeq(0)
    , _compID(0)
    , _heardFrom(false)
Don Gagne's avatar
Don Gagne committed
179
180
181
    , _firmwareMajorVersion(versionNotSetValue)
    , _firmwareMinorVersion(versionNotSetValue)
    , _firmwarePatchVersion(versionNotSetValue)
182
183
184
    , _firmwareCustomMajorVersion(versionNotSetValue)
    , _firmwareCustomMinorVersion(versionNotSetValue)
    , _firmwareCustomPatchVersion(versionNotSetValue)
185
    , _firmwareVersionType(FIRMWARE_VERSION_TYPE_OFFICIAL)
186
    , _gitHash(versionNotSetValue)
Gus Grubba's avatar
Gus Grubba committed
187
    , _uid(0)
188
    , _lastAnnouncedLowBatteryPercent(100)
189
    , _priorityLinkCommanded(false)
Don Gagne's avatar
   
Don Gagne committed
190
    , _orbitActive(false)
Don Gagne's avatar
   
Don Gagne committed
191
192
    , _pidTuningTelemetryMode(false)
    , _pidTuningWaitingForRates(false)
Don Gagne's avatar
Don Gagne committed
193
194
195
    , _rollFact             (0, _rollFactName,              FactMetaData::valueTypeDouble)
    , _pitchFact            (0, _pitchFactName,             FactMetaData::valueTypeDouble)
    , _headingFact          (0, _headingFactName,           FactMetaData::valueTypeDouble)
DonLakeFlyer's avatar
DonLakeFlyer committed
196
197
198
    , _rollRateFact         (0, _rollRateFactName,          FactMetaData::valueTypeDouble)
    , _pitchRateFact        (0, _pitchRateFactName,         FactMetaData::valueTypeDouble)
    , _yawRateFact          (0, _yawRateFactName,           FactMetaData::valueTypeDouble)
Don Gagne's avatar
Don Gagne committed
199
200
201
202
203
    , _groundSpeedFact      (0, _groundSpeedFactName,       FactMetaData::valueTypeDouble)
    , _airSpeedFact         (0, _airSpeedFactName,          FactMetaData::valueTypeDouble)
    , _climbRateFact        (0, _climbRateFactName,         FactMetaData::valueTypeDouble)
    , _altitudeRelativeFact (0, _altitudeRelativeFactName,  FactMetaData::valueTypeDouble)
    , _altitudeAMSLFact     (0, _altitudeAMSLFactName,      FactMetaData::valueTypeDouble)
204
    , _flightDistanceFact   (0, _flightDistanceFactName,    FactMetaData::valueTypeDouble)
205
    , _flightTimeFact       (0, _flightTimeFactName,        FactMetaData::valueTypeElapsedTimeInSeconds)
206
    , _distanceToHomeFact   (0, _distanceToHomeFactName,    FactMetaData::valueTypeDouble)
207
    , _headingToNextWPFact  (0, _headingToNextWPFactName,   FactMetaData::valueTypeDouble)
Don Gagne's avatar
   
Don Gagne committed
208
    , _headingToHomeFact    (0, _headingToHomeFactName,     FactMetaData::valueTypeDouble)
Don Gagne's avatar
   
Don Gagne committed
209
    , _distanceToGCSFact    (0, _distanceToGCSFactName,     FactMetaData::valueTypeDouble)
210
    , _hobbsFact            (0, _hobbsFactName,             FactMetaData::valueTypeString)
Don Gagne's avatar
   
Don Gagne committed
211
    , _throttlePctFact      (0, _throttlePctFactName,       FactMetaData::valueTypeUint16)
Don Gagne's avatar
Don Gagne committed
212
    , _gpsFactGroup(this)
DonLakeFlyer's avatar
comit    
DonLakeFlyer committed
213
214
    , _battery1FactGroup(this)
    , _battery2FactGroup(this)
Don Gagne's avatar
Don Gagne committed
215
    , _windFactGroup(this)
Don Gagne's avatar
Don Gagne committed
216
    , _vibrationFactGroup(this)
217
    , _temperatureFactGroup(this)
dheideman's avatar
dheideman committed
218
    , _clockFactGroup(this)
219
    , _distanceSensorFactGroup(this)
220
    , _estimatorStatusFactGroup(this)
221
{
222
223
    connect(_joystickManager, &JoystickManager::activeJoystickChanged, this, &Vehicle::_loadSettings);
    connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleAvailableChanged, this, &Vehicle::_loadSettings);
Jacob Walser's avatar
Jacob Walser committed
224

225
    _mavlink = _toolbox->mavlinkProtocol();
Don Gagne's avatar
   
Don Gagne committed
226
    qCDebug(VehicleLog) << "Link started with Mavlink " << (_mavlink->getCurrentVersion() >= 200 ? "V2" : "V1");
dogmaphobic's avatar
dogmaphobic committed
227

Gus Grubba's avatar
Gus Grubba committed
228
229
    connect(_mavlink, &MAVLinkProtocol::messageReceived,        this, &Vehicle::_mavlinkMessageReceived);
    connect(_mavlink, &MAVLinkProtocol::mavlinkMessageStatus,   this, &Vehicle::_mavlinkMessageStatus);
Don Gagne's avatar
Don Gagne committed
230

231
232
    _addLink(link);

233
    connect(this, &Vehicle::_sendMessageOnLinkOnThread, this, &Vehicle::_sendMessageOnLink, Qt::QueuedConnection);
Don Gagne's avatar
Don Gagne committed
234
    connect(this, &Vehicle::flightModeChanged,          this, &Vehicle::_handleFlightModeChanged);
235
    connect(this, &Vehicle::armedChanged,               this, &Vehicle::_announceArmedChanged);
236

237
238
    connect(_toolbox->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &Vehicle::_vehicleParamLoaded);

239
    _uas = new UAS(_mavlink, this, _firmwarePluginManager);
dogmaphobic's avatar
dogmaphobic committed
240

Don Gagne's avatar
Don Gagne committed
241
242
    connect(_uas, &UAS::imageReady,                     this, &Vehicle::_imageReady);
    connect(this, &Vehicle::remoteControlRSSIChanged,   this, &Vehicle::_remoteControlRSSIChanged);
dogmaphobic's avatar
dogmaphobic committed
243

244
    _commonInit();
Don Gagne's avatar
Don Gagne committed
245
    _autopilotPlugin = _firmwarePlugin->autopilotPlugin(this);
dogmaphobic's avatar
dogmaphobic committed
246

Don Gagne's avatar
Don Gagne committed
247
248
249
250
251
    // PreArm Error self-destruct timer
    connect(&_prearmErrorTimer, &QTimer::timeout, this, &Vehicle::_prearmErrorTimeout);
    _prearmErrorTimer.setInterval(_prearmErrorTimeoutMSecs);
    _prearmErrorTimer.setSingleShot(true);

252
253
    // Send MAV_CMD ack timer
    _mavCommandAckTimer.setSingleShot(true);
DonLakeFlyer's avatar
DonLakeFlyer committed
254
    _mavCommandAckTimer.setInterval(_highLatencyLink ? _mavCommandAckTimeoutMSecsHighLatency : _mavCommandAckTimeoutMSecs);
255
256
    connect(&_mavCommandAckTimer, &QTimer::timeout, this, &Vehicle::_sendMavCommandAgain);

257
    _mav = uas();
258

259
    // Listen for system messages
260
261
    connect(_toolbox->uasMessageHandler(), &UASMessageHandler::textMessageCountChanged,  this, &Vehicle::_handleTextMessage);
    connect(_toolbox->uasMessageHandler(), &UASMessageHandler::textMessageReceived,      this, &Vehicle::_handletextMessageReceived);
Tomaz Canabrava's avatar
Tomaz Canabrava committed
262

DonLakeFlyer's avatar
DonLakeFlyer committed
263
264
    if (_highLatencyLink || link->isPX4Flow()) {
        // These links don't request information
DonLakeFlyer's avatar
DonLakeFlyer committed
265
266
267
268
269
270
271
        _setMaxProtoVersion(100);
        _setCapabilities(0);
        _initialPlanRequestComplete = true;
        _missionManagerInitialRequestSent = true;
        _geoFenceManagerInitialRequestSent = true;
        _rallyPointManagerInitialRequestSent = true;
    } else {
Don Gagne's avatar
   
Don Gagne committed
272
        sendMavCommand(MAV_COMP_ID_ALL,
DonLakeFlyer's avatar
DonLakeFlyer committed
273
274
275
                       MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
                       false,                                   // No error shown if fails
                       1);                                      // Request firmware version
Don Gagne's avatar
   
Don Gagne committed
276
277
278
279
        sendMavCommand(MAV_COMP_ID_ALL,
                       MAV_CMD_REQUEST_PROTOCOL_VERSION,
                       false,                                   // No error shown if fails
                       1);                                      // Request protocol version
DonLakeFlyer's avatar
DonLakeFlyer committed
280
    }
281

282
    _firmwarePlugin->initializeVehicle(this);
283
284
285
    for(auto& factName: factNames()) {
        _firmwarePlugin->adjustMetaData(vehicleType, getFact(factName)->metaData());
    }
dogmaphobic's avatar
dogmaphobic committed
286

287
288
    _sendMultipleTimer.start(_sendMessageMultipleIntraMessageDelay);
    connect(&_sendMultipleTimer, &QTimer::timeout, this, &Vehicle::_sendMessageMultipleNext);
dogmaphobic's avatar
dogmaphobic committed
289

Don Gagne's avatar
   
Don Gagne committed
290
291
    connect(&_orbitTelemetryTimer, &QTimer::timeout, this, &Vehicle::_orbitTelemetryTimeout);

Gus Grubba's avatar
Gus Grubba committed
292
    // Create camera manager instance
293
    _cameras = _firmwarePlugin->createCameraManager(this);
Gus Grubba's avatar
Gus Grubba committed
294
    emit dynamicCamerasChanged();
295

Willian Galvani's avatar
Willian Galvani committed
296
297
298
    // Start csv logger
    connect(&_csvLogTimer, &QTimer::timeout, this, &Vehicle::_writeCsvLine);
    _csvLogTimer.start(1000);
299
    _lastBatteryAnnouncement.start();
300
301
}

302
303
304
305
306
// Disconnected Vehicle for offline editing
Vehicle::Vehicle(MAV_AUTOPILOT              firmwareType,
                 MAV_TYPE                   vehicleType,
                 FirmwarePluginManager*     firmwarePluginManager,
                 QObject*                   parent)
Don Gagne's avatar
Don Gagne committed
307
308
    : FactGroup(_vehicleUIUpdateRateMSecs, ":/json/Vehicle/VehicleFact.json", parent)
    , _id(0)
309
    , _defaultComponentId(MAV_COMP_ID_ALL)
Don Gagne's avatar
Don Gagne committed
310
    , _active(false)
311
    , _offlineEditingVehicle(true)
312
313
    , _firmwareType(firmwareType)
    , _vehicleType(vehicleType)
314
315
316
317
    , _firmwarePlugin(nullptr)
    , _firmwarePluginInstanceData(nullptr)
    , _autopilotPlugin(nullptr)
    , _mavlink(nullptr)
318
    , _soloFirmware(false)
319
320
    , _toolbox(qgcApp()->toolbox())
    , _settingsManager(_toolbox->settingsManager())
Don Gagne's avatar
Don Gagne committed
321
322
    , _joystickMode(JoystickModeRC)
    , _joystickEnabled(false)
323
324
    , _uas(nullptr)
    , _mav(nullptr)
Don Gagne's avatar
Don Gagne committed
325
326
327
328
329
330
331
    , _currentMessageCount(0)
    , _messageCount(0)
    , _currentErrorCount(0)
    , _currentWarningCount(0)
    , _currentNormalCount(0)
    , _currentMessageType(MessageNone)
    , _updateCount(0)
332
    , _rcRSSI(255)
333
    , _rcRSSIstore(255.)
Don Gagne's avatar
Don Gagne committed
334
    , _autoDisconnect(false)
335
    , _flying(false)
336
    , _landing(false)
Don Gagne's avatar
Don Gagne committed
337
    , _vtolInFwdFlight(false)
338
339
340
341
    , _onboardControlSensorsPresent(0)
    , _onboardControlSensorsEnabled(0)
    , _onboardControlSensorsHealth(0)
    , _onboardControlSensorsUnhealthy(0)
342
343
    , _gpsRawIntMessageAvailable(false)
    , _globalPositionIntMessageAvailable(false)
DonLakeFlyer's avatar
DonLakeFlyer committed
344
345
    , _defaultCruiseSpeed(_settingsManager->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
    , _defaultHoverSpeed(_settingsManager->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
Don Gagne's avatar
   
Don Gagne committed
346
347
    , _mavlinkProtocolRequestComplete(true)
    , _maxProtoVersion(200)
DonLakeFlyer's avatar
   
DonLakeFlyer committed
348
    , _capabilityBitsKnown(true)
Don Gagne's avatar
   
Don Gagne committed
349
    , _capabilityBits(MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY)
Don Gagne's avatar
Don Gagne committed
350
    , _highLatencyLink(false)
351
    , _receivingAttitudeQuaternion(false)
352
    , _cameras(nullptr)
Don Gagne's avatar
Don Gagne committed
353
354
    , _connectionLost(false)
    , _connectionLostEnabled(true)
DonLakeFlyer's avatar
DonLakeFlyer committed
355
    , _initialPlanRequestComplete(false)
356
    , _missionManager(nullptr)
357
    , _missionManagerInitialRequestSent(false)
358
    , _geoFenceManager(nullptr)
359
    , _geoFenceManagerInitialRequestSent(false)
360
    , _rallyPointManager(nullptr)
361
    , _rallyPointManagerInitialRequestSent(false)
362
#if defined(QGC_AIRMAP_ENABLED)
363
    , _airspaceVehicleManager(nullptr)
364
#endif
Don Gagne's avatar
Don Gagne committed
365
366
367
368
    , _armed(false)
    , _base_mode(0)
    , _custom_mode(0)
    , _nextSendMessageMultipleIndex(0)
DonLakeFlyer's avatar
   
DonLakeFlyer committed
369
    , _trajectoryPoints(new TrajectoryPoints(this, this))
370
    , _firmwarePluginManager(firmwarePluginManager)
371
    , _joystickManager(nullptr)
Don Gagne's avatar
Don Gagne committed
372
373
374
375
376
377
378
379
    , _flowImageIndex(0)
    , _allLinksInactiveSent(false)
    , _messagesReceived(0)
    , _messagesSent(0)
    , _messagesLost(0)
    , _messageSeq(0)
    , _compID(0)
    , _heardFrom(false)
Don Gagne's avatar
Don Gagne committed
380
381
382
    , _firmwareMajorVersion(versionNotSetValue)
    , _firmwareMinorVersion(versionNotSetValue)
    , _firmwarePatchVersion(versionNotSetValue)
383
384
385
386
    , _firmwareCustomMajorVersion(versionNotSetValue)
    , _firmwareCustomMinorVersion(versionNotSetValue)
    , _firmwareCustomPatchVersion(versionNotSetValue)
    , _firmwareVersionType(FIRMWARE_VERSION_TYPE_OFFICIAL)
387
    , _gitHash(versionNotSetValue)
Gus Grubba's avatar
Gus Grubba committed
388
    , _uid(0)
389
    , _lastAnnouncedLowBatteryPercent(100)
Don Gagne's avatar
   
Don Gagne committed
390
    , _orbitActive(false)
Don Gagne's avatar
   
Don Gagne committed
391
392
    , _pidTuningTelemetryMode(false)
    , _pidTuningWaitingForRates(false)
Don Gagne's avatar
Don Gagne committed
393
394
395
    , _rollFact             (0, _rollFactName,              FactMetaData::valueTypeDouble)
    , _pitchFact            (0, _pitchFactName,             FactMetaData::valueTypeDouble)
    , _headingFact          (0, _headingFactName,           FactMetaData::valueTypeDouble)
DonLakeFlyer's avatar
DonLakeFlyer committed
396
397
398
    , _rollRateFact         (0, _rollRateFactName,          FactMetaData::valueTypeDouble)
    , _pitchRateFact        (0, _pitchRateFactName,         FactMetaData::valueTypeDouble)
    , _yawRateFact          (0, _yawRateFactName,           FactMetaData::valueTypeDouble)
Don Gagne's avatar
Don Gagne committed
399
400
401
402
403
    , _groundSpeedFact      (0, _groundSpeedFactName,       FactMetaData::valueTypeDouble)
    , _airSpeedFact         (0, _airSpeedFactName,          FactMetaData::valueTypeDouble)
    , _climbRateFact        (0, _climbRateFactName,         FactMetaData::valueTypeDouble)
    , _altitudeRelativeFact (0, _altitudeRelativeFactName,  FactMetaData::valueTypeDouble)
    , _altitudeAMSLFact     (0, _altitudeAMSLFactName,      FactMetaData::valueTypeDouble)
404
405
    , _flightDistanceFact   (0, _flightDistanceFactName,    FactMetaData::valueTypeDouble)
    , _flightTimeFact       (0, _flightTimeFactName,        FactMetaData::valueTypeElapsedTimeInSeconds)
406
    , _distanceToHomeFact   (0, _distanceToHomeFactName,    FactMetaData::valueTypeDouble)
407
    , _headingToNextWPFact  (0, _headingToNextWPFactName,   FactMetaData::valueTypeDouble)
Don Gagne's avatar
   
Don Gagne committed
408
    , _headingToHomeFact    (0, _headingToHomeFactName,     FactMetaData::valueTypeDouble)
Don Gagne's avatar
   
Don Gagne committed
409
    , _distanceToGCSFact    (0, _distanceToGCSFactName,     FactMetaData::valueTypeDouble)
410
    , _hobbsFact            (0, _hobbsFactName,             FactMetaData::valueTypeString)
Don Gagne's avatar
   
Don Gagne committed
411
    , _throttlePctFact      (0, _throttlePctFactName,       FactMetaData::valueTypeUint16)
Don Gagne's avatar
Don Gagne committed
412
    , _gpsFactGroup(this)
DonLakeFlyer's avatar
comit    
DonLakeFlyer committed
413
414
    , _battery1FactGroup(this)
    , _battery2FactGroup(this)
Don Gagne's avatar
Don Gagne committed
415
416
    , _windFactGroup(this)
    , _vibrationFactGroup(this)
dheideman's avatar
dheideman committed
417
    , _clockFactGroup(this)
418
    , _distanceSensorFactGroup(this)
Don Gagne's avatar
Don Gagne committed
419
{
420
    _commonInit();
Don Gagne's avatar
   
Don Gagne committed
421
422
423
424
425
426
427

    // Offline editing vehicle tracks settings changes for offline editing settings
    connect(_settingsManager->appSettings()->offlineEditingFirmwareType(),  &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged);
    connect(_settingsManager->appSettings()->offlineEditingVehicleType(),   &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged);
    connect(_settingsManager->appSettings()->offlineEditingCruiseSpeed(),   &Fact::rawValueChanged, this, &Vehicle::_offlineCruiseSpeedSettingChanged);
    connect(_settingsManager->appSettings()->offlineEditingHoverSpeed(),    &Fact::rawValueChanged, this, &Vehicle::_offlineHoverSpeedSettingChanged);

428
    _firmwarePlugin->initializeVehicle(this);
429
430
}

431
void Vehicle::_commonInit()
432
433
{
    _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
434

435
436
    connect(_firmwarePlugin, &FirmwarePlugin::toolbarIndicatorsChanged, this, &Vehicle::toolBarIndicatorsChanged);

Don Gagne's avatar
   
Don Gagne committed
437
    connect(this, &Vehicle::coordinateChanged,      this, &Vehicle::_updateDistanceHeadingToHome);
Don Gagne's avatar
   
Don Gagne committed
438
    connect(this, &Vehicle::coordinateChanged,      this, &Vehicle::_updateDistanceToGCS);
Don Gagne's avatar
   
Don Gagne committed
439
    connect(this, &Vehicle::homePositionChanged,    this, &Vehicle::_updateDistanceHeadingToHome);
440
    connect(this, &Vehicle::hobbsMeterChanged,      this, &Vehicle::_updateHobbsMeter);
441

Don Gagne's avatar
   
Don Gagne committed
442
443
    connect(_toolbox->qgcPositionManager(), &QGCPositionManager::gcsPositionChanged, this, &Vehicle::_updateDistanceToGCS);

444
    _missionManager = new MissionManager(this);
445
    connect(_missionManager, &MissionManager::error,                    this, &Vehicle::_missionManagerError);
DonLakeFlyer's avatar
DonLakeFlyer committed
446
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_missionLoadComplete);
447
448
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_clearCameraTriggerPoints);
    connect(_missionManager, &MissionManager::sendComplete,             this, &Vehicle::_clearCameraTriggerPoints);
449
    connect(_missionManager, &MissionManager::currentIndexChanged,      this, &Vehicle::_updateHeadingToNextWP);
450

DonLakeFlyer's avatar
   
DonLakeFlyer committed
451
452
453
    connect(_missionManager, &MissionManager::sendComplete,             _trajectoryPoints, &TrajectoryPoints::clear);
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, _trajectoryPoints, &TrajectoryPoints::clear);

454
    _parameterManager = new ParameterManager(this);
Don Gagne's avatar
Don Gagne committed
455
    connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
456

Gus Grubba's avatar
Gus Grubba committed
457
458
    _objectAvoidance = new VehicleObjectAvoidance(this, this);

459
    // GeoFenceManager needs to access ParameterManager so make sure to create after
460
    _geoFenceManager = new GeoFenceManager(this);
461
    connect(_geoFenceManager, &GeoFenceManager::error,          this, &Vehicle::_geoFenceManagerError);
DonLakeFlyer's avatar
DonLakeFlyer committed
462
    connect(_geoFenceManager, &GeoFenceManager::loadComplete,   this, &Vehicle::_geoFenceLoadComplete);
463

464
    _rallyPointManager = new RallyPointManager(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
465
466
    connect(_rallyPointManager, &RallyPointManager::error,          this, &Vehicle::_rallyPointManagerError);
    connect(_rallyPointManager, &RallyPointManager::loadComplete,   this, &Vehicle::_rallyPointLoadComplete);
467

468
469
470
    // Flight modes can differ based on advanced mode
    connect(_toolbox->corePlugin(), &QGCCorePlugin::showAdvancedUIChanged, this, &Vehicle::flightModesChanged);

Don Gagne's avatar
Don Gagne committed
471
472
473
474
475
    // Build FactGroup object model

    _addFact(&_rollFact,                _rollFactName);
    _addFact(&_pitchFact,               _pitchFactName);
    _addFact(&_headingFact,             _headingFactName);
DonLakeFlyer's avatar
DonLakeFlyer committed
476
477
478
    _addFact(&_rollRateFact,            _rollRateFactName);
    _addFact(&_pitchRateFact,           _pitchRateFactName);
    _addFact(&_yawRateFact,             _yawRateFactName);
Don Gagne's avatar
Don Gagne committed
479
480
481
482
483
    _addFact(&_groundSpeedFact,         _groundSpeedFactName);
    _addFact(&_airSpeedFact,            _airSpeedFactName);
    _addFact(&_climbRateFact,           _climbRateFactName);
    _addFact(&_altitudeRelativeFact,    _altitudeRelativeFactName);
    _addFact(&_altitudeAMSLFact,        _altitudeAMSLFactName);
484
    _addFact(&_flightDistanceFact,      _flightDistanceFactName);
485
    _addFact(&_flightTimeFact,          _flightTimeFactName);
486
    _addFact(&_distanceToHomeFact,      _distanceToHomeFactName);
487
    _addFact(&_headingToNextWPFact,     _headingToNextWPFactName);
Don Gagne's avatar
   
Don Gagne committed
488
    _addFact(&_headingToHomeFact,       _headingToHomeFactName);
Don Gagne's avatar
   
Don Gagne committed
489
    _addFact(&_distanceToGCSFact,       _distanceToGCSFactName);
Don Gagne's avatar
   
Don Gagne committed
490
    _addFact(&_throttlePctFact,         _throttlePctFactName);
491
492

    _hobbsFact.setRawValue(QVariant(QString("0000:00:00")));
493
    _addFact(&_hobbsFact,               _hobbsFactName);
Don Gagne's avatar
Don Gagne committed
494

495
    _addFactGroup(&_gpsFactGroup,               _gpsFactGroupName);
DonLakeFlyer's avatar
comit    
DonLakeFlyer committed
496
497
    _addFactGroup(&_battery1FactGroup,          _battery1FactGroupName);
    _addFactGroup(&_battery2FactGroup,          _battery2FactGroupName);
498
499
500
501
502
    _addFactGroup(&_windFactGroup,              _windFactGroupName);
    _addFactGroup(&_vibrationFactGroup,         _vibrationFactGroupName);
    _addFactGroup(&_temperatureFactGroup,       _temperatureFactGroupName);
    _addFactGroup(&_clockFactGroup,             _clockFactGroupName);
    _addFactGroup(&_distanceSensorFactGroup,    _distanceSensorFactGroupName);
503
    _addFactGroup(&_estimatorStatusFactGroup,   _estimatorStatusFactGroupName);
504

Jacob Walser's avatar
Jacob Walser committed
505
    // Add firmware-specific fact groups, if provided
506
507
508
509
510
511
512
    QMap<QString, FactGroup*>* fwFactGroups = _firmwarePlugin->factGroups();
    if (fwFactGroups) {
        QMapIterator<QString, FactGroup*> i(*fwFactGroups);
        while(i.hasNext()) {
            i.next();
            _addFactGroup(i.value(), i.key());
        }
513
514
    }

515
    _flightDistanceFact.setRawValue(0);
516
    _flightTimeFact.setRawValue(0);
DonLakeFlyer's avatar
   
DonLakeFlyer committed
517
518
519
    _flightTimeUpdater.setInterval(1000);
    _flightTimeUpdater.setSingleShot(false);
    connect(&_flightTimeUpdater, &QTimer::timeout, this, &Vehicle::_updateFlightTime);
520

521
    // Set video stream to udp if running ArduSub and Video is disabled
522
    if (sub() && _settingsManager->videoSettings()->videoSource()->rawValue() == VideoSettings::videoDisabled) {
Gus Grubba's avatar
Gus Grubba committed
523
        _settingsManager->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceUDPH264);
Willian Galvani's avatar
Willian Galvani committed
524
        _settingsManager->videoSettings()->lowLatencyMode()->setRawValue(true);
525
526
    }

527
528
529
530
531
532
533
534
535
536
    //-- Airspace Management
#if defined(QGC_AIRMAP_ENABLED)
    AirspaceManager* airspaceManager = _toolbox->airspaceManager();
    if (airspaceManager) {
        _airspaceVehicleManager = airspaceManager->instantiateVehicle(*this);
        if (_airspaceVehicleManager) {
            connect(_airspaceVehicleManager, &AirspaceVehicleManager::trafficUpdate, this, &Vehicle::_trafficUpdate);
        }
    }
#endif
Don Gagne's avatar
   
Don Gagne committed
537
538

    _pidTuningMessages << MAVLINK_MSG_ID_ATTITUDE << MAVLINK_MSG_ID_ATTITUDE_TARGET;
Don Gagne's avatar
Don Gagne committed
539
540
}

541
542
Vehicle::~Vehicle()
{
Don Gagne's avatar
Don Gagne committed
543
544
    qCDebug(VehicleLog) << "~Vehicle" << this;

545
    delete _missionManager;
546
    _missionManager = nullptr;
Don Gagne's avatar
Don Gagne committed
547

548
    delete _autopilotPlugin;
549
    _autopilotPlugin = nullptr;
550

Don Gagne's avatar
Don Gagne committed
551
    delete _mav;
552
    _mav = nullptr;
dogmaphobic's avatar
dogmaphobic committed
553

554
#if defined(QGC_AIRMAP_ENABLED)
Gus Grubba's avatar
Gus Grubba committed
555
556
    if (_airspaceVehicleManager) {
        delete _airspaceVehicleManager;
557
    }
558
#endif
559
560
}

561
562
563
void Vehicle::prepareDelete()
{
    if(_cameras) {
Stefan Dunca's avatar
Stefan Dunca committed
564
565
566
        // because of _cameras QML bindings check for nullptr won't work in the binding pipeline
        // the dangling pointer access will cause a runtime fault
        auto tmpCameras = _cameras;
567
        _cameras = nullptr;
Stefan Dunca's avatar
Stefan Dunca committed
568
        delete tmpCameras;
569
570
571
572
573
        emit dynamicCamerasChanged();
        qApp->processEvents();
    }
}

574
575
576
void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant value)
{
    _firmwareType = static_cast<MAV_AUTOPILOT>(value.toInt());
577
    _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
578
579
580
581
582
583
584
585
586
587
588
    emit firmwareTypeChanged();
}

void Vehicle::_offlineVehicleTypeSettingChanged(QVariant value)
{
    _vehicleType = static_cast<MAV_TYPE>(value.toInt());
    emit vehicleTypeChanged();
}

void Vehicle::_offlineCruiseSpeedSettingChanged(QVariant value)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
589
590
    _defaultCruiseSpeed = value.toDouble();
    emit defaultCruiseSpeedChanged(_defaultCruiseSpeed);
591
592
593
594
}

void Vehicle::_offlineHoverSpeedSettingChanged(QVariant value)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
595
596
    _defaultHoverSpeed = value.toDouble();
    emit defaultHoverSpeedChanged(_defaultHoverSpeed);
597
598
}

599
QString Vehicle::firmwareTypeString() const
600
601
602
603
604
605
606
607
608
609
{
    if (px4Firmware()) {
        return QStringLiteral("PX4 Pro");
    } else if (apmFirmware()) {
        return QStringLiteral("ArduPilot");
    } else {
        return tr("MAVLink Generic");
    }
}

610
QString Vehicle::vehicleTypeString() const
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
{
    if (fixedWing()) {
        return tr("Fixed Wing");
    } else if (multiRotor()) {
        return tr("Multi-Rotor");
    } else if (vtol()) {
        return tr("VTOL");
    } else if (rover()) {
        return tr("Rover");
    } else if (sub()) {
        return tr("Sub");
    } else {
        return tr("Unknown");
    }
}

void Vehicle::resetCounters()
628
629
630
631
632
633
634
635
{
    _messagesReceived   = 0;
    _messagesSent       = 0;
    _messagesLost       = 0;
    _messageSeq         = 0;
    _heardFrom          = false;
}

636
637
void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message)
{
Don Gagne's avatar
   
Don Gagne committed
638
    // If the link is already running at Mavlink V2 set our max proto version to it.
DonLakeFlyer's avatar
DonLakeFlyer committed
639
640
    unsigned mavlinkVersion = _mavlink->getCurrentVersion();
    if (_maxProtoVersion != mavlinkVersion && mavlinkVersion >= 200) {
Don Gagne's avatar
   
Don Gagne committed
641
642
        _maxProtoVersion = mavlinkVersion;
        qCDebug(VehicleLog) << "Vehicle::_mavlinkMessageReceived Link already running Mavlink v2. Setting _maxProtoVersion" << _maxProtoVersion;
DonLakeFlyer's avatar
DonLakeFlyer committed
643
644
    }

Don Gagne's avatar
Don Gagne committed
645
    if (message.sysid != _id && message.sysid != 0) {
646
647
648
649
        // We allow RADIO_STATUS messages which come from a link the vehicle is using to pass through and be handled
        if (!(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS && _containsLink(link))) {
            return;
        }
650
    }
651

652
653
654
    if (!_containsLink(link)) {
        _addLink(link);
    }
dogmaphobic's avatar
dogmaphobic committed
655

656
657
658
659
660
661
662
663
664
665
666
    //-- Check link status
    _messagesReceived++;
    emit messagesReceivedChanged();
    if(!_heardFrom) {
        if(message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
            _heardFrom = true;
            _compID = message.compid;
            _messageSeq = message.seq + 1;
        }
    } else {
        if(_compID == message.compid) {
Gus Grubba's avatar
Gus Grubba committed
667
            uint16_t seq_received = static_cast<uint16_t>(message.seq);
668
669
670
671
672
673
674
675
676
677
678
679
680
681
            uint16_t packet_lost_count = 0;
            //-- Account for overflow during packet loss
            if(seq_received < _messageSeq) {
                packet_lost_count = (seq_received + 255) - _messageSeq;
            } else {
                packet_lost_count = seq_received - _messageSeq;
            }
            _messageSeq = message.seq + 1;
            _messagesLost += packet_lost_count;
            if(packet_lost_count)
                emit messagesLostChanged();
        }
    }

Don Gagne's avatar
Don Gagne committed
682
    // Give the plugin a change to adjust the message contents
683
684
685
    if (!_firmwarePlugin->adjustIncomingMavlinkMessage(this, &message)) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
686

687
688
689
690
691
    // Give the Core Plugin access to all mavlink traffic
    if (!_toolbox->corePlugin()->mavlinkMessage(this, link, message)) {
        return;
    }

DonLakeFlyer's avatar
   
DonLakeFlyer committed
692
693
694
695
696
697
698
699
700
701
    if (!_capabilityBitsKnown && message.msgid == MAVLINK_MSG_ID_HEARTBEAT && message.compid == MAV_COMP_ID_AUTOPILOT1) {
        // We want to try to get capabilities as fast as possible so we retry on heartbeats
        bool foundRequest = false;
        for (MavCommandQueueEntry_t& queuedCommand : _mavCommandQueue) {
            if (queuedCommand.command ==  MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) {
                foundRequest = true;
                break;
            }
        }
        if (!foundRequest) {
Don Gagne's avatar
   
Don Gagne committed
702
703
704
705
706
            _capabilitiesRetryCount++;
            if (_capabilitiesRetryCount == 1) {
                _capabilitiesRetryElapsed.start();
            } else if (_capabilitiesRetryElapsed.elapsed() > 10000){
                qCDebug(VehicleLog) << "Giving up on getting AUTOPILOT_VERSION after 10 seconds";
Don Gagne's avatar
   
Don Gagne committed
707
                qgcApp()->showMessage(QStringLiteral("Vehicle failed to send AUTOPILOT_VERSION after waiting/retrying for 10 seconds"));
DonLakeFlyer's avatar
   
DonLakeFlyer committed
708
709
710
                _handleUnsupportedRequestAutopilotCapabilities();
            } else {
                // Vehicle never sent us AUTOPILOT_VERSION response. Try again.
Don Gagne's avatar
   
Don Gagne committed
711
                qCDebug(VehicleLog) << QStringLiteral("Sending MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES again due to no response with AUTOPILOT_VERSION - _capabilitiesRetryCount(%1) elapsed(%2)").arg(_capabilitiesRetryCount).arg(_capabilitiesRetryElapsed.elapsed());
DonLakeFlyer's avatar
   
DonLakeFlyer committed
712
713
714
715
716
717
718
719
                sendMavCommand(MAV_COMP_ID_ALL,
                               MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
                               true,                                    // Show error on failure
                               1);                                      // Request firmware version
            }
        }
    }

Don Gagne's avatar
Don Gagne committed
720
    switch (message.msgid) {
Don Gagne's avatar
Don Gagne committed
721
722
723
724
725
726
    case MAVLINK_MSG_ID_HOME_POSITION:
        _handleHomePosition(message);
        break;
    case MAVLINK_MSG_ID_HEARTBEAT:
        _handleHeartbeat(message);
        break;
727
728
729
    case MAVLINK_MSG_ID_RADIO_STATUS:
        _handleRadioStatus(message);
        break;
Don Gagne's avatar
Don Gagne committed
730
731
732
733
734
735
    case MAVLINK_MSG_ID_RC_CHANNELS:
        _handleRCChannels(message);
        break;
    case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
        _handleRCChannelsRaw(message);
        break;
Don Gagne's avatar
Don Gagne committed
736
737
738
739
740
741
    case MAVLINK_MSG_ID_BATTERY_STATUS:
        _handleBatteryStatus(message);
        break;
    case MAVLINK_MSG_ID_SYS_STATUS:
        _handleSysStatus(message);
        break;
Don Gagne's avatar
Don Gagne committed
742
743
744
745
746
747
748
749
750
751
752
753
    case MAVLINK_MSG_ID_RAW_IMU:
        emit mavlinkRawImu(message);
        break;
    case MAVLINK_MSG_ID_SCALED_IMU:
        emit mavlinkScaledImu1(message);
        break;
    case MAVLINK_MSG_ID_SCALED_IMU2:
        emit mavlinkScaledImu2(message);
        break;
    case MAVLINK_MSG_ID_SCALED_IMU3:
        emit mavlinkScaledImu3(message);
        break;
Don Gagne's avatar
Don Gagne committed
754
755
756
    case MAVLINK_MSG_ID_VIBRATION:
        _handleVibration(message);
        break;
Don Gagne's avatar
Don Gagne committed
757
758
759
    case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
        _handleExtendedSysState(message);
        break;
760
761
762
    case MAVLINK_MSG_ID_COMMAND_ACK:
        _handleCommandAck(message);
        break;
763
764
765
    case MAVLINK_MSG_ID_COMMAND_LONG:
        _handleCommandLong(message);
        break;
766
    case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
Gus Grubba's avatar
Gus Grubba committed
767
        _handleAutopilotVersion(link, message);
768
        break;
769
770
771
    case MAVLINK_MSG_ID_PROTOCOL_VERSION:
        _handleProtocolVersion(link, message);
        break;
772
773
774
    case MAVLINK_MSG_ID_WIND_COV:
        _handleWindCov(message);
        break;
Bart Slinger's avatar
Bart Slinger committed
775
776
777
    case MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS:
        _handleHilActuatorControls(message);
        break;
778
779
780
781
782
783
    case MAVLINK_MSG_ID_LOGGING_DATA:
        _handleMavlinkLoggingData(message);
        break;
    case MAVLINK_MSG_ID_LOGGING_DATA_ACKED:
        _handleMavlinkLoggingDataAcked(message);
        break;
784
785
786
787
788
789
790
791
792
793
794
795
    case MAVLINK_MSG_ID_GPS_RAW_INT:
        _handleGpsRawInt(message);
        break;
    case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
        _handleGlobalPositionInt(message);
        break;
    case MAVLINK_MSG_ID_ALTITUDE:
        _handleAltitude(message);
        break;
    case MAVLINK_MSG_ID_VFR_HUD:
        _handleVfrHud(message);
        break;
796
797
798
799
800
801
802
803
    case MAVLINK_MSG_ID_SCALED_PRESSURE:
        _handleScaledPressure(message);
        break;
    case MAVLINK_MSG_ID_SCALED_PRESSURE2:
        _handleScaledPressure2(message);
        break;
    case MAVLINK_MSG_ID_SCALED_PRESSURE3:
        _handleScaledPressure3(message);
DonLakeFlyer's avatar
DonLakeFlyer committed
804
        break;
805
806
    case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED:
        _handleCameraImageCaptured(message);
807
        break;
808
809
810
    case MAVLINK_MSG_ID_ADSB_VEHICLE:
        _handleADSBVehicle(message);
        break;
DonLakeFlyer's avatar
DonLakeFlyer committed
811
812
813
    case MAVLINK_MSG_ID_HIGH_LATENCY2:
        _handleHighLatency2(message);
        break;
814
815
816
    case MAVLINK_MSG_ID_ATTITUDE:
        _handleAttitude(message);
        break;
817
818
    case MAVLINK_MSG_ID_ATTITUDE_QUATERNION:
        _handleAttitudeQuaternion(message);
DonLakeFlyer's avatar
DonLakeFlyer committed
819
820
821
822
        break;
    case MAVLINK_MSG_ID_ATTITUDE_TARGET:
        _handleAttitudeTarget(message);
        break;
823
824
825
    case MAVLINK_MSG_ID_DISTANCE_SENSOR:
        _handleDistanceSensor(message);
        break;
826
827
828
    case MAVLINK_MSG_ID_ESTIMATOR_STATUS:
        _handleEstimatorStatus(message);
        break;
Don Gagne's avatar
   
Don Gagne committed
829
    case MAVLINK_MSG_ID_STATUSTEXT:
Don Gagne's avatar
   
Don Gagne committed
830
831
832
833
        _handleStatusText(message, false /* longVersion */);
        break;
    case MAVLINK_MSG_ID_STATUSTEXT_LONG:
        _handleStatusText(message, true /* longVersion */);
Don Gagne's avatar
   
Don Gagne committed
834
        break;
Don Gagne's avatar
   
Don Gagne committed
835
836
837
    case MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS:
        _handleOrbitExecutionStatus(message);
        break;
Don Gagne's avatar
   
Don Gagne committed
838
839
840
    case MAVLINK_MSG_ID_MESSAGE_INTERVAL:
        _handleMessageInterval(message);
        break;
DonLakeFlyer's avatar
DonLakeFlyer committed
841
842
843
    case MAVLINK_MSG_ID_PING:
        _handlePing(link, message);
        break;
Gus Grubba's avatar
Gus Grubba committed
844
845
846
    case MAVLINK_MSG_ID_MOUNT_ORIENTATION:
        _handleGimbalOrientation(message);
        break;
Gus Grubba's avatar
Gus Grubba committed
847
848
849
    case MAVLINK_MSG_ID_OBSTACLE_DISTANCE:
        _handleObstacleDistance(message);
        break;
Don Gagne's avatar
Don Gagne committed
850

Nate Weibley's avatar
Nate Weibley committed
851
852
853
854
855
856
857
    case MAVLINK_MSG_ID_SERIAL_CONTROL:
    {
        mavlink_serial_control_t ser;
        mavlink_msg_serial_control_decode(&message, &ser);
        emit mavlinkSerialControl(ser.device, ser.flags, ser.timeout, ser.baudrate, QByteArray(reinterpret_cast<const char*>(ser.data), ser.count));
    }
        break;
Don Gagne's avatar
Don Gagne committed
858

DonLakeFlyer's avatar
DonLakeFlyer committed
859
        // Following are ArduPilot dialect messages
860
861
862
863
#if !defined(NO_ARDUPILOT_DIALECT)
    case MAVLINK_MSG_ID_CAMERA_FEEDBACK:
        _handleCameraFeedback(message);
        break;
Don Gagne's avatar
Don Gagne committed
864
865
866
    case MAVLINK_MSG_ID_WIND:
        _handleWind(message);
        break;
867
#endif
Don Gagne's avatar
Don Gagne committed
868
    }
dogmaphobic's avatar
dogmaphobic committed
869

870
871
    // This must be emitted after the vehicle processes the message. This way the vehicle state is up to date when anyone else
    // does processing.
Don Gagne's avatar
Don Gagne committed
872
    emit mavlinkMessageReceived(message);
dogmaphobic's avatar
dogmaphobic committed
873

874
875
876
    _uas->receiveMessage(message);
}

877
#if !defined(NO_ARDUPILOT_DIALECT)
878
879
880
881
882
883
884
885
886
887
void Vehicle::_handleCameraFeedback(const mavlink_message_t& message)
{
    mavlink_camera_feedback_t feedback;

    mavlink_msg_camera_feedback_decode(&message, &feedback);

    QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lng / qPow(10.0, 7.0), feedback.alt_msl);
    qCDebug(VehicleLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.img_idx;
    _cameraTriggerPoints.append(new QGCQGeoCoordinate(imageCoordinate, this));
}
888
#endif
889

Don Gagne's avatar
   
Don Gagne committed
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
void Vehicle::_handleOrbitExecutionStatus(const mavlink_message_t& message)
{
    mavlink_orbit_execution_status_t orbitStatus;

    mavlink_msg_orbit_execution_status_decode(&message, &orbitStatus);

    double newRadius =  qAbs(static_cast<double>(orbitStatus.radius));
    if (!qFuzzyCompare(_orbitMapCircle.radius()->rawValue().toDouble(), newRadius)) {
        _orbitMapCircle.radius()->setRawValue(newRadius);
    }

    bool newOrbitClockwise = orbitStatus.radius > 0 ? true : false;
    if (_orbitMapCircle.clockwiseRotation() != newOrbitClockwise) {
        _orbitMapCircle.setClockwiseRotation(newOrbitClockwise);
    }

    QGeoCoordinate newCenter(static_cast<double>(orbitStatus.x) / qPow(10.0, 7.0), static_cast<double>(orbitStatus.y) / qPow(10.0, 7.0));
    if (_orbitMapCircle.center() != newCenter) {
        _orbitMapCircle.setCenter(newCenter);
    }

    if (!_orbitActive) {
        _orbitActive = true;
        _orbitMapCircle.setShowRotation(true);
        emit orbitActiveChanged(true);
    }

    _orbitTelemetryTimer.start(_orbitTelemetryTimeoutMsecs);
}

920
void Vehicle::_orbitTelemetryTimeout()
Don Gagne's avatar
   
Don Gagne committed
921
922
923
924
925
{
    _orbitActive = false;
    emit orbitActiveChanged(false);
}

926
927
928
929
930
931
932
933
934
935
936
937
938
void Vehicle::_handleCameraImageCaptured(const mavlink_message_t& message)
{
    mavlink_camera_image_captured_t feedback;

    mavlink_msg_camera_image_captured_decode(&message, &feedback);

    QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lon / qPow(10.0, 7.0), feedback.alt);
    qCDebug(VehicleLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.image_index << feedback.capture_result;
    if (feedback.capture_result == 1) {
        _cameraTriggerPoints.append(new QGCQGeoCoordinate(imageCoordinate, this));
    }
}

Don Gagne's avatar
   
Don Gagne committed
939
void Vehicle::_handleStatusText(mavlink_message_t& message, bool longVersion)
Don Gagne's avatar
   
Don Gagne committed
940
{
Don Gagne's avatar
   
Don Gagne committed
941
942
943
944
945
946
    QByteArray  b;
    QString     messageText;
    int         severity;

    if (longVersion) {
        b.resize(MAVLINK_MSG_STATUSTEXT_LONG_FIELD_TEXT_LEN+1);
DonLakeFlyer's avatar
   
DonLakeFlyer committed
947
948
949
950
        mavlink_statustext_long_t statustextLong;
        mavlink_msg_statustext_long_decode(&message, &statustextLong);
        strncpy(b.data(), statustextLong.text, MAVLINK_MSG_STATUSTEXT_LONG_FIELD_TEXT_LEN);
        severity = statustextLong.severity;
Don Gagne's avatar
   
Don Gagne committed
951
952
    } else {
        b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
DonLakeFlyer's avatar
   
DonLakeFlyer committed
953
954
955
956
        mavlink_statustext_t statustext;
        mavlink_msg_statustext_decode(&message, &statustext);
        strncpy(b.data(), statustext.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
        severity = statustext.severity;
Don Gagne's avatar
   
Don Gagne committed
957
    }
Don Gagne's avatar
   
Don Gagne committed
958
    b[b.length()-1] = '\0';
Don Gagne's avatar
   
Don Gagne committed
959
    messageText = QString(b);
Don Gagne's avatar
   
Don Gagne committed
960
961

    bool skipSpoken = false;
Don Gagne's avatar
   
Don Gagne committed
962
    bool ardupilotPrearm = messageText.startsWith(QStringLiteral("PreArm"));
Don Gagne's avatar
   
Don Gagne committed
963
    bool px4Prearm = messageText.startsWith(QStringLiteral("preflight"), Qt::CaseInsensitive) && severity >= MAV_SEVERITY_CRITICAL;
Don Gagne's avatar
   
Don Gagne committed
964
    if (ardupilotPrearm || px4Prearm) {
Don Gagne's avatar
   
Don Gagne committed
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
        // Limit repeated PreArm message to once every 10 seconds
        if (_noisySpokenPrearmMap.contains(messageText) && _noisySpokenPrearmMap[messageText].msecsTo(QTime::currentTime()) < (10 * 1000)) {
            skipSpoken = true;
        } else {
            _noisySpokenPrearmMap[messageText] = QTime::currentTime();
            setPrearmError(messageText);
        }
    }


    // If the message is NOTIFY or higher severity, or starts with a '#',
    // then read it aloud.
    if (messageText.startsWith("#") || severity <= MAV_SEVERITY_NOTICE) {
        messageText.remove("#");
        if (!skipSpoken) {
            qgcApp()->toolbox()->audioOutput()->say(messageText);
        }
    }
    emit textMessageReceived(id(), message.compid, severity, messageText);
}

986
987
988
989
990
991
992
993
void Vehicle::_handleVfrHud(mavlink_message_t& message)
{
    mavlink_vfr_hud_t vfrHud;
    mavlink_msg_vfr_hud_decode(&message, &vfrHud);

    _airSpeedFact.setRawValue(qIsNaN(vfrHud.airspeed) ? 0 : vfrHud.airspeed);
    _groundSpeedFact.setRawValue(qIsNaN(vfrHud.groundspeed) ? 0 : vfrHud.groundspeed);
    _climbRateFact.setRawValue(qIsNaN(vfrHud.climb) ? 0 : vfrHud.climb);
Don Gagne's avatar
   
Don Gagne committed
994
    _throttlePctFact.setRawValue(static_cast<int16_t>(vfrHud.throttle));
995
996
}

997
998
999
1000
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
1020
1021
1022
1023
1024
1025
1026
1027
1028
1029
1030
1031
1032
1033
1034
1035
1036
1037
1038
1039
1040
1041
1042
1043
1044
1045
1046
1047
1048
1049
void Vehicle::_handleEstimatorStatus(mavlink_message_t& message)
{
    mavlink_estimator_status_t estimatorStatus;
    mavlink_msg_estimator_status_decode(&message, &estimatorStatus);

    _estimatorStatusFactGroup.goodAttitudeEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_ATTITUDE));
    _estimatorStatusFactGroup.goodHorizVelEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_VELOCITY_HORIZ));
    _estimatorStatusFactGroup.goodVertVelEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_VELOCITY_VERT));
    _estimatorStatusFactGroup.goodHorizPosRelEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_POS_HORIZ_REL));
    _estimatorStatusFactGroup.goodHorizPosAbsEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_POS_HORIZ_ABS));
    _estimatorStatusFactGroup.goodVertPosAbsEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_POS_VERT_ABS));
    _estimatorStatusFactGroup.goodVertPosAGLEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_POS_VERT_AGL));
    _estimatorStatusFactGroup.goodConstPosModeEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_CONST_POS_MODE));
    _estimatorStatusFactGroup.goodPredHorizPosRelEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_PRED_POS_HORIZ_REL));
    _estimatorStatusFactGroup.goodPredHorizPosAbsEstimate()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_PRED_POS_HORIZ_ABS));
    _estimatorStatusFactGroup.gpsGlitch()->setRawValue(estimatorStatus.flags & ESTIMATOR_GPS_GLITCH ? true : false);
    _estimatorStatusFactGroup.accelError()->setRawValue(!!(estimatorStatus.flags & ESTIMATOR_ACCEL_ERROR));
    _estimatorStatusFactGroup.velRatio()->setRawValue(estimatorStatus.vel_ratio);
    _estimatorStatusFactGroup.horizPosRatio()->setRawValue(estimatorStatus.pos_horiz_ratio);
    _estimatorStatusFactGroup.vertPosRatio()->setRawValue(estimatorStatus.pos_vert_ratio);
    _estimatorStatusFactGroup.magRatio()->setRawValue(estimatorStatus.mag_ratio);
    _estimatorStatusFactGroup.haglRatio()->setRawValue(estimatorStatus.hagl_ratio);
    _estimatorStatusFactGroup.tasRatio()->setRawValue(estimatorStatus.tas_ratio);
    _estimatorStatusFactGroup.horizPosAccuracy()->setRawValue(estimatorStatus.pos_horiz_accuracy);
    _estimatorStatusFactGroup.vertPosAccuracy()->setRawValue(estimatorStatus.pos_vert_accuracy);

#if 0
    typedef enum ESTIMATOR_STATUS_FLAGS
    {
       ESTIMATOR_ATTITUDE=1, /* True if the attitude estimate is good | */
       ESTIMATOR_VELOCITY_HORIZ=2, /* True if the horizontal velocity estimate is good | */
       ESTIMATOR_VELOCITY_VERT=4, /* True if the  vertical velocity estimate is good | */
       ESTIMATOR_POS_HORIZ_REL=8, /* True if the horizontal position (relative) estimate is good | */
       ESTIMATOR_POS_HORIZ_ABS=16, /* True if the horizontal position (absolute) estimate is good | */
       ESTIMATOR_POS_VERT_ABS=32, /* True if the vertical position (absolute) estimate is good | */
       ESTIMATOR_POS_VERT_AGL=64, /* True if the vertical position (above ground) estimate is good | */
       ESTIMATOR_CONST_POS_MODE=128, /* True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) | */
       ESTIMATOR_PRED_POS_HORIZ_REL=256, /* True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate | */
       ESTIMATOR_PRED_POS_HORIZ_ABS=512, /* True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate | */
       ESTIMATOR_GPS_GLITCH=1024, /* True if the EKF has detected a GPS glitch | */
       ESTIMATOR_ACCEL_ERROR=2048, /* True if the EKF has detected bad accelerometer data | */

        typedef struct __mavlink_estimator_status_t {
         uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
         float vel_ratio; /*< Velocity innovation test ratio*/
         float pos_horiz_ratio; /*< Horizontal position innovation test ratio*/
         float pos_vert_ratio; /*< Vertical position innovation test ratio*/
         float mag_ratio; /*< Magnetometer innovation test ratio*/
         float hagl_ratio; /*< Height above terrain innovation test ratio*/
         float tas_ratio; /*< True airspeed innovation test ratio*/
         float pos_horiz_accuracy; /*< Horizontal position 1-STD accuracy relative to the EKF local origin (m)*/
         float pos_vert_accuracy; /*< Vertical position 1-STD accuracy relative to the EKF local origin (m)*/
         uint16_t flags; /*< Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.*/
Gus Grubba's avatar
Gus Grubba committed
1050
1051
        } mavlink_estimator_status_t;
    };
1052
1053
1054
#endif
}

1055
1056
1057
1058
void Vehicle::_handleDistanceSensor(mavlink_message_t& message)
{
    mavlink_distance_sensor_t distanceSensor;

DonLakeFlyer's avatar
   
DonLakeFlyer committed
1059
    mavlink_msg_distance_sensor_decode(&message, &distanceSensor);
1060
1061
1062
1063
1064
1065
1066
1067

    struct orientation2Fact_s {
        MAV_SENSOR_ORIENTATION  orientation;
        Fact*                   fact;
    };

    orientation2Fact_s rgOrientation2Fact[] =
    {
1068
1069
1070
1071
1072
1073
1074
1075
1076
1077
        { MAV_SENSOR_ROTATION_NONE,         _distanceSensorFactGroup.rotationNone() },
        { MAV_SENSOR_ROTATION_YAW_45,       _distanceSensorFactGroup.rotationYaw45() },
        { MAV_SENSOR_ROTATION_YAW_90,       _distanceSensorFactGroup.rotationYaw90() },
        { MAV_SENSOR_ROTATION_YAW_135,      _distanceSensorFactGroup.rotationYaw135() },
        { MAV_SENSOR_ROTATION_YAW_180,      _distanceSensorFactGroup.rotationYaw180() },
        { MAV_SENSOR_ROTATION_YAW_225,      _distanceSensorFactGroup.rotationYaw225() },
        { MAV_SENSOR_ROTATION_YAW_270,      _distanceSensorFactGroup.rotationYaw270() },
        { MAV_SENSOR_ROTATION_YAW_315,      _distanceSensorFactGroup.rotationYaw315() },
        { MAV_SENSOR_ROTATION_PITCH_90,     _distanceSensorFactGroup.rotationPitch90() },
        { MAV_SENSOR_ROTATION_PITCH_270,    _distanceSensorFactGroup.rotationPitch270() },
1078
1079
1080
1081
1082
    };

    for (size_t i=0; i<sizeof(rgOrientation2Fact)/sizeof(rgOrientation2Fact[0]); i++) {
        const orientation2Fact_s& orientation2Fact = rgOrientation2Fact[i];
        if (orientation2Fact.orientation == distanceSensor.orientation) {
1083
            orientation2Fact.fact->setRawValue(distanceSensor.current_distance / 100.0); // cm to meters
1084
1085
1086
1087
        }
    }
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1088
1089
1090
1091
1092
1093
1094
1095
1096
void Vehicle::_handleAttitudeTarget(mavlink_message_t& message)
{
    mavlink_attitude_target_t attitudeTarget;

    mavlink_msg_attitude_target_decode(&message, &attitudeTarget);

    float roll, pitch, yaw;
    mavlink_quaternion_to_euler(attitudeTarget.q, &roll, &pitch, &yaw);

DonLakeFlyer's avatar
DonLakeFlyer committed
1097
1098
1099
    _setpointFactGroup.roll()->setRawValue(qRadiansToDegrees(roll));
    _setpointFactGroup.pitch()->setRawValue(qRadiansToDegrees(pitch));
    _setpointFactGroup.yaw()->setRawValue(qRadiansToDegrees(yaw));
DonLakeFlyer's avatar
DonLakeFlyer committed
1100
1101
1102
1103
1104
1105

    _setpointFactGroup.rollRate()->setRawValue(qRadiansToDegrees(attitudeTarget.body_roll_rate));
    _setpointFactGroup.pitchRate()->setRawValue(qRadiansToDegrees(attitudeTarget.body_pitch_rate));
    _setpointFactGroup.yawRate()->setRawValue(qRadiansToDegrees(attitudeTarget.body_yaw_rate));
}

1106
void Vehicle::_handleAttitudeWorker(double rollRadians, double pitchRadians, double yawRadians)
DonLakeFlyer's avatar
DonLakeFlyer committed
1107
{
1108
    double roll, pitch, yaw;
1109

1110
1111
1112
    roll = QGC::limitAngleToPMPIf(rollRadians);
    pitch = QGC::limitAngleToPMPIf(pitchRadians);
    yaw = QGC::limitAngleToPMPIf(yawRadians);
1113
1114
1115
1116
1117
1118
1119
1120
1121
1122
1123
1124
1125
1126

    roll = qRadiansToDegrees(roll);
    pitch = qRadiansToDegrees(pitch);
    yaw = qRadiansToDegrees(yaw);

    if (yaw < 0.0) {
        yaw += 360.0;
    }
    // truncate to integer so widget never displays 360
    yaw = trunc(yaw);

    _rollFact.setRawValue(roll);
    _pitchFact.setRawValue(pitch);
    _headingFact.setRawValue(yaw);
1127
1128
1129
1130
1131
1132
1133
1134
1135
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145
1146
1147
}

void Vehicle::_handleAttitude(mavlink_message_t& message)
{
    if (_receivingAttitudeQuaternion) {
        return;
    }

    mavlink_attitude_t attitude;
    mavlink_msg_attitude_decode(&message, &attitude);

    _handleAttitudeWorker(attitude.roll, attitude.pitch, attitude.yaw);
}

void Vehicle::_handleAttitudeQuaternion(mavlink_message_t& message)
{
    _receivingAttitudeQuaternion = true;

    mavlink_attitude_quaternion_t attitudeQuaternion;
    mavlink_msg_attitude_quaternion_decode(&message, &attitudeQuaternion);

1148
1149
1150
1151
1152
1153
1154
    Eigen::Quaternionf quat(attitudeQuaternion.q1, attitudeQuaternion.q2, attitudeQuaternion.q3, attitudeQuaternion.q4);
    Eigen::Vector3f rates(attitudeQuaternion.rollspeed, attitudeQuaternion.pitchspeed, attitudeQuaternion.yawspeed);
    Eigen::Quaternionf repr_offset(attitudeQuaternion.repr_offset_q[0], attitudeQuaternion.repr_offset_q[1], attitudeQuaternion.repr_offset_q[2], attitudeQuaternion.repr_offset_q[3]);

    // if repr_offset is valid, rotate attitude and rates
    if (repr_offset.norm() >= 0.5f) {
        quat = quat * repr_offset;
1155
        rates = repr_offset * rates;
1156
1157
    }

1158
    float roll, pitch, yaw;
1159
    float q[] = { quat.w(), quat.x(), quat.y(), quat.z() };
1160
1161
1162
    mavlink_quaternion_to_euler(q, &roll, &pitch, &yaw);

    _handleAttitudeWorker(roll, pitch, yaw);
1163

1164
1165
1166
    rollRate()->setRawValue(qRadiansToDegrees(rates[0]));
    pitchRate()->setRawValue(qRadiansToDegrees(rates[1]));
    yawRate()->setRawValue(qRadiansToDegrees(rates[2]));
DonLakeFlyer's avatar
DonLakeFlyer committed
1167
1168
}

1169
1170
1171
1172
1173
void Vehicle::_handleGpsRawInt(mavlink_message_t& message)
{
    mavlink_gps_raw_int_t gpsRawInt;
    mavlink_msg_gps_raw_int_decode(&message, &gpsRawInt);

1174
1175
    _gpsRawIntMessageAvailable = true;

1176
    if (gpsRawInt.fix_type >= GPS_FIX_TYPE_3D_FIX) {
1177
        if (!_globalPositionIntMessageAvailable) {
1178
1179
1180
1181
1182
            QGeoCoordinate newPosition(gpsRawInt.lat  / (double)1E7, gpsRawInt.lon / (double)1E7, gpsRawInt.alt  / 1000.0);
            if (newPosition != _coordinate) {
                _coordinate = newPosition;
                emit coordinateChanged(_coordinate);
            }
1183
            _altitudeAMSLFact.setRawValue(gpsRawInt.alt / 1000.0);
1184
1185
1186
        }
    }

1187
1188
    _gpsFactGroup.lat()->setRawValue(gpsRawInt.lat * 1e-7);
    _gpsFactGroup.lon()->setRawValue(gpsRawInt.lon * 1e-7);
Matej Frančeškin's avatar
Matej Frančeškin committed
1189
    _gpsFactGroup.mgrs()->setRawValue(convertGeoToMGRS(QGeoCoordinate(gpsRawInt.lat * 1e-7, gpsRawInt.lon * 1e-7)));
1190
    _gpsFactGroup.count()->setRawValue(gpsRawInt.satellites_visible == 255 ? 0 : gpsRawInt.satellites_visible);
1191
1192
1193
    _gpsFactGroup.hdop()->setRawValue(gpsRawInt.eph == UINT16_MAX ? std::numeric_limits<double>::quiet_NaN() : gpsRawInt.eph / 100.0);
    _gpsFactGroup.vdop()->setRawValue(gpsRawInt.epv == UINT16_MAX ? std::numeric_limits<double>::quiet_NaN() : gpsRawInt.epv / 100.0);
    _gpsFactGroup.courseOverGround()->setRawValue(gpsRawInt.cog == UINT16_MAX ? std::numeric_limits<double>::quiet_NaN() : gpsRawInt.cog / 100.0);
1194
1195
1196
1197
1198
1199
1200
1201
    _gpsFactGroup.lock()->setRawValue(gpsRawInt.fix_type);
}

void Vehicle::_handleGlobalPositionInt(mavlink_message_t& message)
{
    mavlink_global_position_int_t globalPositionInt;
    mavlink_msg_global_position_int_decode(&message, &globalPositionInt);

1202
1203
1204
1205
1206
    _altitudeRelativeFact.setRawValue(globalPositionInt.relative_alt / 1000.0);
    _altitudeAMSLFact.setRawValue(globalPositionInt.alt / 1000.0);

    // ArduPilot sends bogus GLOBAL_POSITION_INT messages with lat/lat 0/0 even when it has no gps signal
    // Apparently, this is in order to transport relative altitude information.
1207
    if (globalPositionInt.lat == 0 && globalPositionInt.lon == 0) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1208
1209
1210
        return;
    }

1211
    _globalPositionIntMessageAvailable = true;
1212
1213
1214
1215
1216
    QGeoCoordinate newPosition(globalPositionInt.lat  / (double)1E7, globalPositionInt.lon / (double)1E7, globalPositionInt.alt  / 1000.0);
    if (newPosition != _coordinate) {
        _coordinate = newPosition;
        emit coordinateChanged(_coordinate);
    }
1217
1218
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1219
1220
1221
1222
1223
void Vehicle::_handleHighLatency2(mavlink_message_t& message)
{
    mavlink_high_latency2_t highLatency2;
    mavlink_msg_high_latency2_decode(&message, &highLatency2);

1224
1225
1226
1227
1228
1229
1230
1231
1232
1233
1234
1235
1236
1237
1238
1239
1240
1241
    QString previousFlightMode;
    if (_base_mode != 0 || _custom_mode != 0){
        // Vehicle is initialized with _base_mode=0 and _custom_mode=0. Don't pass this to flightMode() since it will complain about
        // bad modes while unit testing.
        previousFlightMode = flightMode();
    }
    _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
    _custom_mode = _firmwarePlugin->highLatencyCustomModeTo32Bits(highLatency2.custom_mode);
    if (previousFlightMode != flightMode()) {
        emit flightModeChanged(flightMode());
    }

    // Assume armed since we don't know
    if (_armed != true) {
        _armed = true;
        emit armedChanged(_armed);
    }

DonLakeFlyer's avatar
DonLakeFlyer committed
1242
1243
1244
1245
1246
1247
1248
1249
1250
    _coordinate.setLatitude(highLatency2.latitude  / (double)1E7);
    _coordinate.setLongitude(highLatency2.longitude / (double)1E7);
    _coordinate.setAltitude(highLatency2.altitude);
    emit coordinateChanged(_coordinate);

    _airSpeedFact.setRawValue((double)highLatency2.airspeed / 5.0);
    _groundSpeedFact.setRawValue((double)highLatency2.groundspeed / 5.0);
    _climbRateFact.setRawValue((double)highLatency2.climb_rate / 10.0);
    _headingFact.setRawValue((double)highLatency2.heading * 2.0);
DonLakeFlyer's avatar
DonLakeFlyer committed
1251
1252
    _altitudeRelativeFact.setRawValue(std::numeric_limits<double>::quiet_NaN());
    _altitudeAMSLFact.setRawValue(highLatency2.altitude);
DonLakeFlyer's avatar
DonLakeFlyer committed
1253
1254
1255
1256

    _windFactGroup.direction()->setRawValue((double)highLatency2.wind_heading * 2.0);
    _windFactGroup.speed()->setRawValue((double)highLatency2.windspeed / 5.0);

DonLakeFlyer's avatar
comit    
DonLakeFlyer committed
1257
    _battery1FactGroup.percentRemaining()->setRawValue(highLatency2.battery);
DonLakeFlyer's avatar
DonLakeFlyer committed
1258
1259
1260
1261
1262

    _temperatureFactGroup.temperature1()->setRawValue(highLatency2.temperature_air);

    _gpsFactGroup.lat()->setRawValue(highLatency2.latitude * 1e-7);
    _gpsFactGroup.lon()->setRawValue(highLatency2.longitude * 1e-7);
Matej Frančeškin's avatar
Matej Frančeškin committed
1263
    _gpsFactGroup.mgrs()->setRawValue(convertGeoToMGRS(QGeoCoordinate(highLatency2.latitude * 1e-7, highLatency2.longitude * 1e-7)));
DonLakeFlyer's avatar
DonLakeFlyer committed
1264
1265
1266
    _gpsFactGroup.count()->setRawValue(0);
    _gpsFactGroup.hdop()->setRawValue(highLatency2.eph == UINT8_MAX ? std::numeric_limits<double>::quiet_NaN() : highLatency2.eph / 10.0);
    _gpsFactGroup.vdop()->setRawValue(highLatency2.epv == UINT8_MAX ? std::numeric_limits<double>::quiet_NaN() : highLatency2.epv / 10.0);
1267
1268

    struct failure2Sensor_s {
1269
        HL_FAILURE_FLAG         failureBit;
1270
1271
1272
1273
        MAV_SYS_STATUS_SENSOR   sensorBit;
    };

    static const failure2Sensor_s rgFailure2Sensor[] = {
1274
1275
1276
1277
1278
1279
        { HL_FAILURE_FLAG_GPS,                      MAV_SYS_STATUS_SENSOR_GPS },
        { HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE,    MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE },
        { HL_FAILURE_FLAG_ABSOLUTE_PRESSURE,        MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE },
        { HL_FAILURE_FLAG_3D_ACCEL,                 MAV_SYS_STATUS_SENSOR_3D_ACCEL },
        { HL_FAILURE_FLAG_3D_GYRO,                  MAV_SYS_STATUS_SENSOR_3D_GYRO },
        { HL_FAILURE_FLAG_3D_MAG,                   MAV_SYS_STATUS_SENSOR_3D_MAG },
1280
1281
1282
1283
1284
1285
1286
1287
1288
1289
1290
1291
1292
1293
1294
1295
1296
    };

    // Map from MAV_FAILURE bits to standard SYS_STATUS message handling
    uint32_t newOnboardControlSensorsEnabled = 0;
    for (size_t i=0; i<sizeof(rgFailure2Sensor)/sizeof(failure2Sensor_s); i++) {
        const failure2Sensor_s* pFailure2Sensor = &rgFailure2Sensor[i];
        if (highLatency2.failure_flags & pFailure2Sensor->failureBit) {
            // Assume if reporting as unhealthy that is it present and enabled
            newOnboardControlSensorsEnabled |= pFailure2Sensor->sensorBit;
        }
    }
    if (newOnboardControlSensorsEnabled != _onboardControlSensorsEnabled) {
        _onboardControlSensorsEnabled = newOnboardControlSensorsEnabled;
        _onboardControlSensorsPresent = newOnboardControlSensorsEnabled;
        _onboardControlSensorsUnhealthy = 0;
        emit unhealthySensorsChanged();
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1297
1298
}

1299
1300
1301
1302
1303
void Vehicle::_handleAltitude(mavlink_message_t& message)
{
    mavlink_altitude_t altitude;
    mavlink_msg_altitude_decode(&message, &altitude);

1304
1305
1306
1307
1308
1309
1310
    // If data from GPS is available it takes precedence over ALTITUDE message
    if (!_globalPositionIntMessageAvailable) {
        _altitudeRelativeFact.setRawValue(altitude.altitude_relative);
        if (!_gpsRawIntMessageAvailable) {
            _altitudeAMSLFact.setRawValue(altitude.altitude_amsl);
        }
    }
1311
1312
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1313
1314
void Vehicle::_setCapabilities(uint64_t capabilityBits)
{
1315
    _capabilityBits = capabilityBits;
DonLakeFlyer's avatar
   
DonLakeFlyer committed
1316
    _capabilityBitsKnown = true;
1317
    emit capabilitiesKnownChanged(true);
1318
    emit capabilityBitsChanged(_capabilityBits);
DonLakeFlyer's avatar
DonLakeFlyer committed
1319

1320
1321
1322
1323
1324
    QString supports("supports");
    QString doesNotSupport("does not support");

    qCDebug(VehicleLog) << QString("Vehicle %1 Mavlink 2.0").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MAVLINK2 ? supports : doesNotSupport);
    qCDebug(VehicleLog) << QString("Vehicle %1 MISSION_ITEM_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_INT ? supports : doesNotSupport);
1325
    qCDebug(VehicleLog) << QString("Vehicle %1 MISSION_COMMAND_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_COMMAND_INT ? supports : doesNotSupport);
1326
1327
    qCDebug(VehicleLog) << QString("Vehicle %1 GeoFence").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE ? supports : doesNotSupport);
    qCDebug(VehicleLog) << QString("Vehicle %1 RallyPoints").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_RALLY ? supports : doesNotSupport);
DonLakeFlyer's avatar
   
DonLakeFlyer committed
1328
1329

    _setMaxProtoVersionFromBothSources();
DonLakeFlyer's avatar
DonLakeFlyer committed
1330
1331
}

Gus Grubba's avatar
Gus Grubba committed
1332
void Vehicle::_handleAutopilotVersion(LinkInterface *link, mavlink_message_t& message)
1333
{
Don Gagne's avatar
Don Gagne committed
1334
1335
    Q_UNUSED(link);

1336
1337
1338
    mavlink_autopilot_version_t autopilotVersion;
    mavlink_msg_autopilot_version_decode(&message, &autopilotVersion);

Gus Grubba's avatar
Gus Grubba committed
1339
1340
1341
    _uid = (quint64)autopilotVersion.uid;
    emit vehicleUIDChanged();

1342
1343
1344
1345
1346
1347
1348
1349
    if (autopilotVersion.flight_sw_version != 0) {
        int majorVersion, minorVersion, patchVersion;
        FIRMWARE_VERSION_TYPE versionType;

        majorVersion = (autopilotVersion.flight_sw_version >> (8*3)) & 0xFF;
        minorVersion = (autopilotVersion.flight_sw_version >> (8*2)) & 0xFF;
        patchVersion = (autopilotVersion.flight_sw_version >> (8*1)) & 0xFF;
        versionType = (FIRMWARE_VERSION_TYPE)((autopilotVersion.flight_sw_version >> (8*0)) & 0xFF);
Don Gagne's avatar
Don Gagne committed
1350
        setFirmwareVersion(majorVersion, minorVersion, patchVersion, versionType);
1351
    }
1352

Don Gagne's avatar
Don Gagne committed
1353
1354
1355
1356
1357
1358
1359
1360
    if (px4Firmware()) {
        // Lower 3 bytes is custom version
        int majorVersion, minorVersion, patchVersion;
        majorVersion = autopilotVersion.flight_custom_version[2];
        minorVersion = autopilotVersion.flight_custom_version[1];
        patchVersion = autopilotVersion.flight_custom_version[0];
        setFirmwareCustomVersion(majorVersion, minorVersion, patchVersion);

1361
        // PX4 Firmware stores the first 16 characters of the git hash as binary, with the individual bytes in reverse order
Don Gagne's avatar
Don Gagne committed
1362
1363
1364
        _gitHash = "";
        for (int i = 7; i >= 0; i--) {
            _gitHash.append(QString("%1").arg(autopilotVersion.flight_custom_version[i], 2, 16, QChar('0')));
1365
        }
Don Gagne's avatar
Don Gagne committed
1366
1367
    } else {
        // APM Firmware stores the first 8 characters of the git hash as an ASCII character string
DonLakeFlyer's avatar
   
DonLakeFlyer committed
1368
1369
1370
1371
        char nullStr[9];
        strncpy(nullStr, (char*)autopilotVersion.flight_custom_version, 8);
        nullStr[8] = 0;
        _gitHash = nullStr;
1372
    }
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
1373
1374
    if (_toolbox->corePlugin()->options()->checkFirmwareVersion() && !_checkLatestStableFWDone) {
        _checkLatestStableFWDone = true;
Don Gagne's avatar
   
Don Gagne committed
1375
1376
        _firmwarePlugin->checkIfIsLatestStable(this);
    }
Don Gagne's avatar
Don Gagne committed
1377
    emit gitHashChanged(_gitHash);
1378

DonLakeFlyer's avatar
DonLakeFlyer committed
1379
1380
    _setCapabilities(autopilotVersion.capabilities);
    _startPlanRequest();
1381
1382
}

1383
1384
1385
1386
1387
1388
1389
void Vehicle::_handleProtocolVersion(LinkInterface *link, mavlink_message_t& message)
{
    Q_UNUSED(link);

    mavlink_protocol_version_t protoVersion;
    mavlink_msg_protocol_version_decode(&message, &protoVersion);

Don Gagne's avatar
   
Don Gagne committed
1390
1391
    qCDebug(VehicleLog) << "_handleProtocolVersion" << protoVersion.max_version;

DonLakeFlyer's avatar
   
DonLakeFlyer committed
1392
    _mavlinkProtocolRequestMaxProtoVersion = protoVersion.max_version;
Don Gagne's avatar
   
Don Gagne committed
1393
    _mavlinkProtocolRequestComplete = true;
DonLakeFlyer's avatar
   
DonLakeFlyer committed
1394
    _setMaxProtoVersionFromBothSources();
Don Gagne's avatar
   
Don Gagne committed
1395
    _startPlanRequest();
1396
1397
1398
}

void Vehicle::_setMaxProtoVersion(unsigned version) {
1399
1400
1401

    // Set only once or if we need to reduce the max version
    if (_maxProtoVersion == 0 || version < _maxProtoVersion) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1402
        qCDebug(VehicleLog) << "_setMaxProtoVersion before:after" << _maxProtoVersion << version;
1403
1404
1405
        _maxProtoVersion = version;
        emit requestProtocolVersion(_maxProtoVersion);
    }
1406
1407
}

DonLakeFlyer's avatar
   
DonLakeFlyer committed
1408
1409
1410
1411
1412
1413
1414
1415
1416
1417
1418
1419
1420
void Vehicle::_setMaxProtoVersionFromBothSources()
{
    if (_mavlinkProtocolRequestComplete && _capabilityBitsKnown) {
        if (_mavlinkProtocolRequestMaxProtoVersion != 0) {
            qCDebug(VehicleLog) << "_setMaxProtoVersionFromBothSources using protocol version message";
            _setMaxProtoVersion(_mavlinkProtocolRequestMaxProtoVersion);
        } else {
            qCDebug(VehicleLog) << "_setMaxProtoVersionFromBothSources using capability bits";
            _setMaxProtoVersion(capabilityBits() & MAV_PROTOCOL_CAPABILITY_MAVLINK2 ? 200 : 100);
        }
    }
}

Gus Grubba's avatar
Gus Grubba committed
1421
1422
1423
1424
1425
QString Vehicle::vehicleUIDStr()
{
    QString uid;
    uint8_t* pUid = (uint8_t*)(void*)&_uid;
    uid.sprintf("%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X",
DonLakeFlyer's avatar
DonLakeFlyer committed
1426
1427
1428
1429
1430
1431
1432
1433
                pUid[0] & 0xff,
            pUid[1] & 0xff,
            pUid[2] & 0xff,
            pUid[3] & 0xff,
            pUid[4] & 0xff,
            pUid[5] & 0xff,
            pUid[6] & 0xff,
            pUid[7] & 0xff);
Gus Grubba's avatar
Gus Grubba committed
1434
1435
1436
    return uid;
}

Bart Slinger's avatar
Bart Slinger committed
1437
1438
1439
1440
1441
1442
void Vehicle::_handleHilActuatorControls(mavlink_message_t &message)
{
    mavlink_hil_actuator_controls_t hil;
    mavlink_msg_hil_actuator_controls_decode(&message, &hil);
    emit hilActuatorControlsChanged(hil.time_usec, hil.flags,
                                    hil.controls[0],
DonLakeFlyer's avatar
DonLakeFlyer committed
1443
1444
1445
1446
1447
1448
1449
1450
1451
1452
1453
1454
1455
1456
1457
1458
            hil.controls[1],
            hil.controls[2],
            hil.controls[3],
            hil.controls[4],
            hil.controls[5],
            hil.controls[6],
            hil.controls[7],
            hil.controls[8],
            hil.controls[9],
            hil.controls[10],
            hil.controls[11],
            hil.controls[12],
            hil.controls[13],
            hil.controls[14],
            hil.controls[15],
            hil.mode);
Bart Slinger's avatar
Bart Slinger committed
1459
1460
}

1461
1462
void Vehicle::_handleCommandLong(mavlink_message_t& message)
{
1463
1464
#ifdef NO_SERIAL_LINK
    // If not using serial link, bail out.
DonLakeFlyer's avatar
DonLakeFlyer committed
1465
1466
    Q_UNUSED(message)
#else
1467
1468
1469
1470
    mavlink_command_long_t cmd;
    mavlink_msg_command_long_decode(&message, &cmd);

    switch (cmd.command) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1471
1472
1473
1474
1475
1476
1477
1478
1479
1480
    // Other component on the same system
    // requests that QGC frees up the serial port of the autopilot
    case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
        if (cmd.param6 > 0) {
            // disconnect the USB link if its a direct connection to a Pixhawk
            for (int i = 0; i < _links.length(); i++) {
                SerialLink *sl = qobject_cast<SerialLink*>(_links.at(i));
                if (sl && sl->getSerialConfig()->usbDirect()) {
                    qDebug() << "Disconnecting:" << _links.at(i)->getName();
                    qgcApp()->toolbox()->linkManager()->disconnectLink(_links.at(i));
acfloria's avatar
acfloria committed
1481
                    emit linksChanged();
1482
1483
                }
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1484
        }
1485
1486
        break;
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1487
#endif
1488
1489
}

Don Gagne's avatar
Don Gagne committed
1490
1491
1492
1493
1494
1495
1496
void Vehicle::_handleExtendedSysState(mavlink_message_t& message)
{
    mavlink_extended_sys_state_t extendedState;
    mavlink_msg_extended_sys_state_decode(&message, &extendedState);

    switch (extendedState.landed_state) {
    case MAV_LANDED_STATE_ON_GROUND:
1497
1498
        _setFlying(false);
        _setLanding(false);
Don Gagne's avatar
Don Gagne committed
1499
        break;
1500
    case MAV_LANDED_STATE_TAKEOFF:
Don Gagne's avatar
Don Gagne committed
1501
    case MAV_LANDED_STATE_IN_AIR:
1502
1503
1504
1505
1506
1507
1508
1509
1510
        _setFlying(true);
        _setLanding(false);
        break;
    case MAV_LANDED_STATE_LANDING:
        _setFlying(true);
        _setLanding(true);
        break;
    default:
        break;
Don Gagne's avatar
Don Gagne committed
1511
    }
Don Gagne's avatar
Don Gagne committed
1512
1513

    if (vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1514
1515
1516
1517
1518
        bool vtolInFwdFlight = extendedState.vtol_state == MAV_VTOL_STATE_FW;
        if (vtolInFwdFlight != _vtolInFwdFlight) {
            _vtolInFwdFlight = vtolInFwdFlight;
            emit vtolInFwdFlightChanged(vtolInFwdFlight);
        }
Don Gagne's avatar
Don Gagne committed
1519
    }
Don Gagne's avatar
Don Gagne committed
1520
1521
}

Don Gagne's avatar
Don Gagne committed
1522
1523
1524
1525
1526
1527
1528
1529
1530
1531
1532
1533
1534
void Vehicle::_handleVibration(mavlink_message_t& message)
{
    mavlink_vibration_t vibration;
    mavlink_msg_vibration_decode(&message, &vibration);

    _vibrationFactGroup.xAxis()->setRawValue(vibration.vibration_x);
    _vibrationFactGroup.yAxis()->setRawValue(vibration.vibration_y);
    _vibrationFactGroup.zAxis()->setRawValue(vibration.vibration_z);
    _vibrationFactGroup.clipCount1()->setRawValue(vibration.clipping_0);
    _vibrationFactGroup.clipCount2()->setRawValue(vibration.clipping_1);
    _vibrationFactGroup.clipCount3()->setRawValue(vibration.clipping_2);
}

1535
1536
1537
1538
1539
1540
1541
1542
void Vehicle::_handleWindCov(mavlink_message_t& message)
{
    mavlink_wind_cov_t wind;
    mavlink_msg_wind_cov_decode(&message, &wind);

    float direction = qRadiansToDegrees(qAtan2(wind.wind_y, wind.wind_x));
    float speed = qSqrt(qPow(wind.wind_x, 2) + qPow(wind.wind_y, 2));

Don Gagne's avatar
   
Don Gagne committed
1543
1544
1545
1546
    if (direction < 0) {
        direction += 360;
    }

1547
1548
1549
1550
1551
    _windFactGroup.direction()->setRawValue(direction);
    _windFactGroup.speed()->setRawValue(speed);
    _windFactGroup.verticalSpeed()->setRawValue(0);
}

1552
#if !defined(NO_ARDUPILOT_DIALECT)
Don Gagne's avatar
Don Gagne committed
1553
1554
1555
1556
1557
void Vehicle::_handleWind(mavlink_message_t& message)
{
    mavlink_wind_t wind;
    mavlink_msg_wind_decode(&message, &wind);

1558
1559
1560
1561
1562
1563
    // We don't want negative wind angles
    float direction = wind.direction;
    if (direction < 0) {
        direction += 360;
    }
    _windFactGroup.direction()->setRawValue(direction);
Don Gagne's avatar
Don Gagne committed
1564
1565
1566
    _windFactGroup.speed()->setRawValue(wind.speed);
    _windFactGroup.verticalSpeed()->setRawValue(wind.speed_z);
}
1567
#endif
Don Gagne's avatar
Don Gagne committed
1568

1569
bool Vehicle::_apmArmingNotRequired()
DonLakeFlyer's avatar
DonLakeFlyer committed
1570
1571
1572
1573
1574
1575
{
    QString armingRequireParam("ARMING_REQUIRE");
    return _parameterManager->parameterExists(FactSystem::defaultComponentId, armingRequireParam) &&
            _parameterManager->getParameter(FactSystem::defaultComponentId, armingRequireParam)->rawValue().toInt() == 0;
}

DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
1576
1577
1578
1579
1580
1581
1582
1583
1584
1585
1586
1587
1588
1589
1590
1591
1592
1593
1594
1595
1596
1597
1598
1599
1600
1601
1602
1603
1604
void Vehicle::_batteryStatusWorker(int batteryId, double voltage, double current, double batteryRemainingPct)
{
    VehicleBatteryFactGroup* pBatteryFactGroup = nullptr;
    if (batteryId == 0) {
        pBatteryFactGroup = &_battery1FactGroup;
    } else if (batteryId == 1) {
        pBatteryFactGroup = &_battery2FactGroup;
    } else {
        return;
    }

    pBatteryFactGroup->voltage()->setRawValue(voltage);
    pBatteryFactGroup->current()->setRawValue(current);
    pBatteryFactGroup->instantPower()->setRawValue(voltage * current);
    pBatteryFactGroup->percentRemaining()->setRawValue(batteryRemainingPct);

    //-- Low battery warning
    if (batteryId == 0 && !qIsNaN(batteryRemainingPct)) {
        int warnThreshold = _settingsManager->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toInt();
        if (batteryRemainingPct < warnThreshold &&
                batteryRemainingPct < _lastAnnouncedLowBatteryPercent &&
                _lastBatteryAnnouncement.elapsed() > (batteryRemainingPct < warnThreshold * 0.5 ? 15000 : 30000)) {
            _say(tr("%1 low battery: %2 percent remaining").arg(_vehicleIdSpeech()).arg(static_cast<int>(batteryRemainingPct)));
            _lastBatteryAnnouncement.start();
            _lastAnnouncedLowBatteryPercent = static_cast<int>(batteryRemainingPct);
        }
    }
}

Don Gagne's avatar
Don Gagne committed
1605
1606
1607
1608
1609
void Vehicle::_handleSysStatus(mavlink_message_t& message)
{
    mavlink_sys_status_t sysStatus;
    mavlink_msg_sys_status_decode(&message, &sysStatus);

DonLakeFlyer's avatar
DonLakeFlyer committed
1610
1611
1612
1613
1614
1615
1616
1617
1618
1619
1620
1621
    if (_onboardControlSensorsPresent != sysStatus.onboard_control_sensors_present) {
        _onboardControlSensorsPresent = sysStatus.onboard_control_sensors_present;
        emit sensorsPresentBitsChanged(_onboardControlSensorsPresent);
    }
    if (_onboardControlSensorsEnabled != sysStatus.onboard_control_sensors_enabled) {
        _onboardControlSensorsEnabled = sysStatus.onboard_control_sensors_enabled;
        emit sensorsEnabledBitsChanged(_onboardControlSensorsEnabled);
    }
    if (_onboardControlSensorsHealth != sysStatus.onboard_control_sensors_health) {
        _onboardControlSensorsHealth = sysStatus.onboard_control_sensors_health;
        emit sensorsHealthBitsChanged(_onboardControlSensorsHealth);
    }
1622

DonLakeFlyer's avatar
DonLakeFlyer committed
1623
1624
1625
1626
1627
1628
    // ArduPilot firmare has a strange case when ARMING_REQUIRE=0. This means the vehicle is always armed but the motors are not
    // really powered up until the safety button is pressed. Because of this we can't depend on the heartbeat to tell us the true
    // armed (and dangerous) state. We must instead rely on SYS_STATUS telling us that the motors are enabled.
    if (apmFirmware() && _apmArmingNotRequired()) {
        _updateArmed(_onboardControlSensorsEnabled & MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS);
    }
1629
1630
1631
1632
1633

    uint32_t newSensorsUnhealthy = _onboardControlSensorsEnabled & ~_onboardControlSensorsHealth;
    if (newSensorsUnhealthy != _onboardControlSensorsUnhealthy) {
        _onboardControlSensorsUnhealthy = newSensorsUnhealthy;
        emit unhealthySensorsChanged();
DonLakeFlyer's avatar
DonLakeFlyer committed
1634
        emit sensorsUnhealthyBitsChanged(_onboardControlSensorsUnhealthy);
1635
    }
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
1636
1637
1638
1639
1640
1641

    // BATTERY_STATUS is currently unreliable on PX4 stack so we rely on SYS_STATUS for partial battery 0 information to work around it
    _batteryStatusWorker(0 /* batteryId */,
                         sysStatus.voltage_battery == UINT16_MAX ? qQNaN() : static_cast<double>(sysStatus.voltage_battery) / 1000.0,
                         sysStatus.current_battery == -1 ? qQNaN() : static_cast<double>(sysStatus.current_battery) / 100.0,
                         sysStatus.battery_remaining == -1 ? qQNaN() : sysStatus.battery_remaining);
Don Gagne's avatar
Don Gagne committed
1642
1643
1644
1645
1646
1647
1648
}

void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
{
    mavlink_battery_status_t bat_status;
    mavlink_msg_battery_status_decode(&message, &bat_status);

DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
1649
1650
1651
1652
1653
    VehicleBatteryFactGroup* pBatteryFactGroup = nullptr;
    if (bat_status.id == 0) {
        pBatteryFactGroup = &_battery1FactGroup;
    } else if (bat_status.id == 1) {
        pBatteryFactGroup = &_battery2FactGroup;
Don Gagne's avatar
Don Gagne committed
1654
    } else {
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
1655
        return;
Don Gagne's avatar
Don Gagne committed
1656
1657
    }

DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
1658
    double voltage = qQNaN();
Don Gagne's avatar
Don Gagne committed
1659
    for (int i=0; i<10; i++) {
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
1660
        double cellVoltage = bat_status.voltages[i] == UINT16_MAX ? qQNaN() : static_cast<double>(bat_status.voltages[i]) / 1000.0;
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
1661
1662
1663
1664
1665
1666
1667
        if (qIsNaN(cellVoltage)) {
            break;
        }
        if (i == 0) {
            voltage = cellVoltage;
        } else {
            voltage += cellVoltage;
Don Gagne's avatar
Don Gagne committed
1668
1669
        }
    }
1670

DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
1671
1672
1673
    pBatteryFactGroup->temperature()->setRawValue(bat_status.temperature == INT16_MAX ? qQNaN() : static_cast<double>(bat_status.temperature) / 100.0);
    pBatteryFactGroup->mahConsumed()->setRawValue(bat_status.current_consumed == -1  ? qQNaN() : bat_status.current_consumed);
    pBatteryFactGroup->chargeState()->setRawValue(bat_status.charge_state);
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
1674
    pBatteryFactGroup->timeRemaining()->setRawValue(bat_status.time_remaining == 0 ? qQNaN() : bat_status.time_remaining);
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
1675

DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
1676
1677
1678
1679
1680
1681
    // BATTERY_STATUS is currently unreliable on PX4 stack so we rely on SYS_STATUS for partial battery 0 information to work around it
    if (bat_status.id != 0) {
        _batteryStatusWorker(bat_status.id,
                             voltage,
                             bat_status.current_battery == -1 ? qQNaN() : (double)bat_status.current_battery / 100.0,
                             bat_status.battery_remaining == -1 ? qQNaN() : bat_status.battery_remaining);
1682
    }
Don Gagne's avatar
Don Gagne committed
1683
1684
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1685
1686
1687
1688
1689
1690
1691
1692
void Vehicle::_setHomePosition(QGeoCoordinate& homeCoord)
{
    if (homeCoord != _homePosition) {
        _homePosition = homeCoord;
        emit homePositionChanged(_homePosition);
    }
}

Don Gagne's avatar
Don Gagne committed
1693
1694
1695
void Vehicle::_handleHomePosition(mavlink_message_t& message)
{
    mavlink_home_position_t homePos;
dogmaphobic's avatar
dogmaphobic committed
1696

Don Gagne's avatar
Don Gagne committed
1697
    mavlink_msg_home_position_decode(&message, &homePos);
Don Gagne's avatar
Don Gagne committed
1698
1699
1700
1701

    QGeoCoordinate newHomePosition (homePos.latitude / 10000000.0,
                                    homePos.longitude / 10000000.0,
                                    homePos.altitude / 1000.0);
DonLakeFlyer's avatar
DonLakeFlyer committed
1702
    _setHomePosition(newHomePosition);
Don Gagne's avatar
Don Gagne committed
1703
1704
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1705
void Vehicle::_updateArmed(bool armed)
Don Gagne's avatar
Don Gagne committed
1706
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1707
1708
    if (_armed != armed) {
        _armed = armed;
Don Gagne's avatar
Don Gagne committed
1709
        emit armedChanged(_armed);
Don Gagne's avatar
Don Gagne committed
1710
1711
        // We are transitioning to the armed state, begin tracking trajectory points for the map
        if (_armed) {
DonLakeFlyer's avatar
   
DonLakeFlyer committed
1712
1713
            _trajectoryPoints->start();
            _flightTimerStart();
1714
            _clearCameraTriggerPoints();
1715
1716
            // Reset battery warning
            _lastAnnouncedLowBatteryPercent = 100;
Don Gagne's avatar
Don Gagne committed
1717
        } else {
DonLakeFlyer's avatar
   
DonLakeFlyer committed
1718
            _trajectoryPoints->stop();
DonLakeFlyer's avatar
   
DonLakeFlyer committed
1719
            _flightTimerStop();
1720
            // Also handle Video Streaming
1721
1722
1723
1724
1725
            if(qgcApp()->toolbox()->videoManager()->videoReceiver()) {
                if(_settingsManager->videoSettings()->disableWhenDisarmed()->rawValue().toBool()) {
                    _settingsManager->videoSettings()->streamEnabled()->setRawValue(false);
                    qgcApp()->toolbox()->videoManager()->videoReceiver()->stop();
                }
1726
            }
Don Gagne's avatar
Don Gagne committed
1727
        }
Don Gagne's avatar
Don Gagne committed
1728
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1729
1730
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1731
1732
1733
1734
1735
1736
void Vehicle::_handlePing(LinkInterface* link, mavlink_message_t& message)
{
    mavlink_ping_t      ping;
    mavlink_message_t   msg;

    mavlink_msg_ping_decode(&message, &ping);
1737
1738
    mavlink_msg_ping_pack_chan(static_cast<uint8_t>(_mavlink->getSystemId()),
                               static_cast<uint8_t>(_mavlink->getComponentId()),
DonLakeFlyer's avatar
DonLakeFlyer committed
1739
1740
1741
1742
1743
1744
1745
1746
1747
                               priorityLink()->mavlinkChannel(),
                               &msg,
                               ping.time_usec,
                               ping.seq,
                               message.sysid,
                               message.compid);
    sendMessageOnLink(link, msg);
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1748
1749
1750
1751
1752
1753
1754
1755
1756
1757
1758
1759
1760
1761
1762
1763
1764
1765
1766
1767
1768
1769
1770
1771
void Vehicle::_handleHeartbeat(mavlink_message_t& message)
{
    if (message.compid != _defaultComponentId) {
        return;
    }

    mavlink_heartbeat_t heartbeat;

    mavlink_msg_heartbeat_decode(&message, &heartbeat);

    bool newArmed = heartbeat.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;

    // ArduPilot firmare has a strange case when ARMING_REQUIRE=0. This means the vehicle is always armed but the motors are not
    // really powered up until the safety button is pressed. Because of this we can't depend on the heartbeat to tell us the true
    // armed (and dangerous) state. We must instead rely on SYS_STATUS telling us that the motors are enabled.
    if (apmFirmware()) {
        if (!_apmArmingNotRequired() || !(_onboardControlSensorsPresent & MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS)) {
            // If ARMING_REQUIRE!=0 or we haven't seen motor output status yet we use the hearbeat info for armed
            _updateArmed(newArmed);
        }
    } else {
        // Non-ArduPilot always updates from armed state in heartbeat
        _updateArmed(newArmed);
    }
Don Gagne's avatar
Don Gagne committed
1772
1773

    if (heartbeat.base_mode != _base_mode || heartbeat.custom_mode != _custom_mode) {
1774
1775
1776
1777
1778
1779
        QString previousFlightMode;
        if (_base_mode != 0 || _custom_mode != 0){
            // Vehicle is initialized with _base_mode=0 and _custom_mode=0. Don't pass this to flightMode() since it will complain about
            // bad modes while unit testing.
            previousFlightMode = flightMode();
        }
1780
        _base_mode   = heartbeat.base_mode;
Don Gagne's avatar
Don Gagne committed
1781
        _custom_mode = heartbeat.custom_mode;
1782
1783
1784
        if (previousFlightMode != flightMode()) {
            emit flightModeChanged(flightMode());
        }
Don Gagne's avatar
Don Gagne committed
1785
1786
1787
    }
}

1788
1789
void Vehicle::_handleRadioStatus(mavlink_message_t& message)
{
1790

1791
1792
1793
    //-- Process telemetry status message
    mavlink_radio_status_t rstatus;
    mavlink_msg_radio_status_decode(&message, &rstatus);
1794

1795
1796
    int rssi    = rstatus.rssi;
    int remrssi = rstatus.remrssi;
1797
1798
    int lnoise = (int)(int8_t)rstatus.noise;
    int rnoise = (int)(int8_t)rstatus.remnoise;
1799
1800
1801
1802
1803
1804
1805
1806
1807
1808
1809
1810
1811
1812
    //-- 3DR Si1k radio needs rssi fields to be converted to dBm
    if (message.sysid == '3' && message.compid == 'D') {
        /* Per the Si1K datasheet figure 23.25 and SI AN474 code
         * samples the relationship between the RSSI register
         * and received power is as follows:
         *
         *                       10
         * inputPower = rssi * ------ 127
         *                       19
         *
         * Additionally limit to the only realistic range [-120,0] dBm
         */
        rssi    = qMin(qMax(qRound(static_cast<qreal>(rssi)    / 1.9 - 127.0), - 120), 0);
        remrssi = qMin(qMax(qRound(static_cast<qreal>(remrssi) / 1.9 - 127.0), - 120), 0);
1813
1814
1815
    } else {
        rssi    = (int)(int8_t)rstatus.rssi;
        remrssi = (int)(int8_t)rstatus.remrssi;
1816
1817
1818
1819
1820
1821
1822
1823
1824
1825
1826
1827
1828
1829
1830
1831
1832
1833
1834
1835
1836
1837
    }
    //-- Check for changes
    if(_telemetryLRSSI != rssi) {
        _telemetryLRSSI = rssi;
        emit telemetryLRSSIChanged(_telemetryLRSSI);
    }
    if(_telemetryRRSSI != remrssi) {
        _telemetryRRSSI = remrssi;
        emit telemetryRRSSIChanged(_telemetryRRSSI);
    }
    if(_telemetryRXErrors != rstatus.rxerrors) {
        _telemetryRXErrors = rstatus.rxerrors;
        emit telemetryRXErrorsChanged(_telemetryRXErrors);
    }
    if(_telemetryFixed != rstatus.fixed) {
        _telemetryFixed = rstatus.fixed;
        emit telemetryFixedChanged(_telemetryFixed);
    }
    if(_telemetryTXBuffer != rstatus.txbuf) {
        _telemetryTXBuffer = rstatus.txbuf;
        emit telemetryTXBufferChanged(_telemetryTXBuffer);
    }
1838
1839
    if(_telemetryLNoise != lnoise) {
        _telemetryLNoise = lnoise;
1840
1841
        emit telemetryLNoiseChanged(_telemetryLNoise);
    }
1842
1843
    if(_telemetryRNoise != rnoise) {
        _telemetryRNoise = rnoise;
1844
1845
1846
1847
        emit telemetryRNoiseChanged(_telemetryRNoise);
    }
}

Don Gagne's avatar
Don Gagne committed
1848
1849
1850
1851
1852
1853
1854
1855
1856
1857
1858
1859
1860
1861
1862
1863
1864
1865
1866
1867
1868
1869
1870
1871
1872
1873
1874
1875
1876
1877
1878
1879
1880
1881
1882
1883
1884
1885
1886
1887
1888
1889
1890
1891
1892
1893
1894
1895
1896
1897
1898
1899
1900
1901
1902
1903
1904
1905
1906
1907
1908
1909
1910
1911
1912
void Vehicle::_handleRCChannels(mavlink_message_t& message)
{
    mavlink_rc_channels_t channels;

    mavlink_msg_rc_channels_decode(&message, &channels);

    uint16_t* _rgChannelvalues[cMaxRcChannels] = {
        &channels.chan1_raw,
        &channels.chan2_raw,
        &channels.chan3_raw,
        &channels.chan4_raw,
        &channels.chan5_raw,
        &channels.chan6_raw,
        &channels.chan7_raw,
        &channels.chan8_raw,
        &channels.chan9_raw,
        &channels.chan10_raw,
        &channels.chan11_raw,
        &channels.chan12_raw,
        &channels.chan13_raw,
        &channels.chan14_raw,
        &channels.chan15_raw,
        &channels.chan16_raw,
        &channels.chan17_raw,
        &channels.chan18_raw,
    };
    int pwmValues[cMaxRcChannels];

    for (int i=0; i<cMaxRcChannels; i++) {
        uint16_t channelValue = *_rgChannelvalues[i];

        if (i < channels.chancount) {
            pwmValues[i] = channelValue == UINT16_MAX ? -1 : channelValue;
        } else {
            pwmValues[i] = -1;
        }
    }

    emit remoteControlRSSIChanged(channels.rssi);
    emit rcChannelsChanged(channels.chancount, pwmValues);
}

void Vehicle::_handleRCChannelsRaw(mavlink_message_t& message)
{
    // We handle both RC_CHANNLES and RC_CHANNELS_RAW since different firmware will only
    // send one or the other.

    mavlink_rc_channels_raw_t channels;

    mavlink_msg_rc_channels_raw_decode(&message, &channels);

    uint16_t* _rgChannelvalues[cMaxRcChannels] = {
        &channels.chan1_raw,
        &channels.chan2_raw,
        &channels.chan3_raw,
        &channels.chan4_raw,
        &channels.chan5_raw,
        &channels.chan6_raw,
        &channels.chan7_raw,
        &channels.chan8_raw,
    };

    int pwmValues[cMaxRcChannels];
    int channelCount = 0;

Don Gagne's avatar
Don Gagne committed
1913
1914
1915
1916
    for (int i=0; i<cMaxRcChannels; i++) {
        pwmValues[i] = -1;
    }

Don Gagne's avatar
Don Gagne committed
1917
1918
1919
1920
1921
1922
    for (int i=0; i<8; i++) {
        uint16_t channelValue = *_rgChannelvalues[i];

        if (channelValue == UINT16_MAX) {
            pwmValues[i] = -1;
        } else {
Don Gagne's avatar
Don Gagne committed
1923
            channelCount = i + 1;
Don Gagne's avatar
Don Gagne committed
1924
1925
1926
1927
1928
1929
1930
1931
1932
1933
1934
            pwmValues[i] = channelValue;
        }
    }
    for (int i=9; i<18; i++) {
        pwmValues[i] = -1;
    }

    emit remoteControlRSSIChanged(channels.rssi);
    emit rcChannelsChanged(channelCount, pwmValues);
}

1935
1936
1937
1938
1939
1940
1941
1942
1943
1944
1945
1946
1947
1948
1949
1950
1951
1952
void Vehicle::_handleScaledPressure(mavlink_message_t& message) {
    mavlink_scaled_pressure_t pressure;
    mavlink_msg_scaled_pressure_decode(&message, &pressure);
    _temperatureFactGroup.temperature1()->setRawValue(pressure.temperature / 100.0);
}

void Vehicle::_handleScaledPressure2(mavlink_message_t& message) {
    mavlink_scaled_pressure2_t pressure;
    mavlink_msg_scaled_pressure2_decode(&message, &pressure);
    _temperatureFactGroup.temperature2()->setRawValue(pressure.temperature / 100.0);
}

void Vehicle::_handleScaledPressure3(mavlink_message_t& message) {
    mavlink_scaled_pressure3_t pressure;
    mavlink_msg_scaled_pressure3_decode(&message, &pressure);
    _temperatureFactGroup.temperature3()->setRawValue(pressure.temperature / 100.0);
}

1953
1954
bool Vehicle::_containsLink(LinkInterface* link)
{
Don Gagne's avatar
Don Gagne committed
1955
    return _links.contains(link);
1956
1957
1958
1959
1960
}

void Vehicle::_addLink(LinkInterface* link)
{
    if (!_containsLink(link)) {
DonLakeFlyer's avatar
   
DonLakeFlyer committed
1961
        qCDebug(VehicleLog) << "_addLink:" << QString("%1").arg((qulonglong)link, 0, 16);
1962
        _links += link;
1963
        if (_links.count() <= 1) {
acfloria's avatar
acfloria committed
1964
            _updatePriorityLink(true /* updateActive */, false /* sendCommand */);
1965
        } else {
acfloria's avatar
acfloria committed
1966
            _updatePriorityLink(true /* updateActive */, true /* sendCommand */);
1967
1968
        }

1969
1970
        connect(_toolbox->linkManager(), &LinkManager::linkInactive, this, &Vehicle::_linkInactiveOrDeleted);
        connect(_toolbox->linkManager(), &LinkManager::linkDeleted, this, &Vehicle::_linkInactiveOrDeleted);
Don Gagne's avatar
Don Gagne committed
1971
        connect(link, &LinkInterface::highLatencyChanged, this, &Vehicle::_updateHighLatencyLink);
1972
        connect(link, &LinkInterface::activeChanged, this, &Vehicle::_linkActiveChanged);
1973
1974
1975
    }
}

Don Gagne's avatar
Don Gagne committed
1976
void Vehicle::_linkInactiveOrDeleted(LinkInterface* link)
1977
{
Don Gagne's avatar
Don Gagne committed
1978
    qCDebug(VehicleLog) << "_linkInactiveOrDeleted linkCount" << _links.count();
dogmaphobic's avatar
dogmaphobic committed
1979

Don Gagne's avatar
Don Gagne committed
1980
    _links.removeOne(link);
1981

acfloria's avatar
acfloria committed
1982
    _updatePriorityLink(true /* updateActive */, true /* sendCommand */);
dogmaphobic's avatar
dogmaphobic committed
1983

Don Gagne's avatar
Don Gagne committed
1984
    if (_links.count() == 0 && !_allLinksInactiveSent) {
Don Gagne's avatar
Don Gagne committed
1985
        qCDebug(VehicleLog) << "All links inactive";
Don Gagne's avatar
Don Gagne committed
1986
1987
1988
        // Make sure to not send this more than one time
        _allLinksInactiveSent = true;
        emit allLinksInactive(this);
1989
1990
1991
    }
}

1992
1993
1994
1995
1996
1997
1998
1999
2000
2001
2002
2003
2004
bool Vehicle::sendMessageOnLink(LinkInterface* link, mavlink_message_t message)
{
    if (!link || !_links.contains(link) || !link->isConnected()) {
        return false;
    }

    emit _sendMessageOnLinkOnThread(link, message);

    return true;
}

void Vehicle::_sendMessageOnLink(LinkInterface* link, mavlink_message_t message)
{
2005
2006
2007
2008
2009
    // Make sure this is still a good link
    if (!link || !_links.contains(link) || !link->isConnected()) {
        return;
    }

Don Gagne's avatar
Don Gagne committed
2010
2011
2012
2013
2014
2015
#if 0
    // Leaving in for ease in Mav 2.0 testing
    mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(link->mavlinkChannel());
    qDebug() << "_sendMessageOnLink" << mavlinkStatus << link->mavlinkChannel() << mavlinkStatus->flags << message.magic;
#endif

2016
    // Give the plugin a chance to adjust
2017
    _firmwarePlugin->adjustOutgoingMavlinkMessage(this, link, &message);
Don Gagne's avatar
Don Gagne committed
2018
2019
2020
2021
2022
2023

    // Write message into buffer, prepending start sign
    uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
    int len = mavlink_msg_to_send_buffer(buffer, &message);

    link->writeBytesSafe((const char*)buffer, len);
2024
2025
    _messagesSent++;
    emit messagesSentChanged();
2026
2027
}

2028
void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand)
2029
{
acfloria's avatar
acfloria committed
2030
    emit linksPropertiesChanged();
2031
2032
2033

    // if the priority link is commanded and still active don't change anything
    if (_priorityLinkCommanded) {
acfloria's avatar
acfloria committed
2034
        if (_priorityLink.data()->link_active(_id)) {
2035
2036
2037
2038
2039
2040
            return;
        } else {
            _priorityLinkCommanded = false;
        }
    }

2041
    LinkInterface* newPriorityLink = nullptr;
2042

2043
    // This routine specifically does not clear _priorityLink when there are no links remaining.
2044
    // By doing this we hold a reference on the last link as the Vehicle shuts down. Thus preventing shutdown
2045
    // ordering nullptr pointer crashes where priorityLink() is still called during shutdown sequence.
2046
2047
2048
2049
2050
2051
2052
    if (_links.count() == 0) {
        return;
    }

    // Check for the existing priority link to still be valid
    for (int i=0; i<_links.count(); i++) {
        if (_priorityLink.data() == _links[i]) {
acfloria's avatar
acfloria committed
2053
            if (!_priorityLink.data()->highLatency() && _priorityLink->link_active(_id)) {
2054
2055
2056
2057
                // Link is still valid. Continue to use it unless it is high latency. In that case we still look for a better
                // link to use as priority link.
                return;
            }
2058
2059
2060
2061
        }
    }

    // The previous priority link is no longer valid. We must no find the best link available in this priority order:
2062
2063
2064
    //      First active direct USB connection
    //      Any active non high latency link
    //      An active high latency link
2065
2066
2067
    //      Any link

#ifndef NO_SERIAL_LINK
2068
    // Search for an active direct usb connection
2069
2070
    for (int i=0; i<_links.count(); i++) {
        LinkInterface* link = _links[i];
2071
2072
2073
2074
2075
2076
        SerialLink* pSerialLink = qobject_cast<SerialLink*>(link);
        if (pSerialLink) {
            LinkConfiguration* config = pSerialLink->getLinkConfiguration();
            if (config) {
                SerialConfiguration* pSerialConfig = qobject_cast<SerialConfiguration*>(config);
                if (pSerialConfig && pSerialConfig->usbDirect()) {
acfloria's avatar
acfloria committed
2077
                    if (_priorityLink.data() != link && link->link_active(_id)) {
2078
2079
                        newPriorityLink = link;
                        break;
2080
2081
2082
                    }
                }
            }
2083
2084
        }
    }
2085
#endif
2086

2087
    if (!newPriorityLink) {
2088
        // Search for an active non-high latency link
2089
2090
        for (int i=0; i<_links.count(); i++) {
            LinkInterface* link = _links[i];
acfloria's avatar
acfloria committed
2091
            if (!link->highLatency() && link->link_active(_id)) {
2092
2093
2094
2095
2096
2097
2098
2099
                newPriorityLink = link;
                break;
            }
        }
    }

    if (!newPriorityLink) {
        // Search for an active high latency link
2100
2101
        for (int i=0; i<_links.count(); i++) {
            LinkInterface* link = _links[i];
acfloria's avatar
acfloria committed
2102
            if (link->highLatency() && link->link_active(_id)) {
2103
2104
2105
2106
                newPriorityLink = link;
                break;
            }
        }
2107
2108
    }

2109
2110
2111
    if (!newPriorityLink) {
        // Use any link
        newPriorityLink = _links[0];
2112
    }
2113

2114
    if (_priorityLink.data() != newPriorityLink) {
2115
2116
2117
        if (_priorityLink) {
            qgcApp()->showMessage((tr("switch to %2 as priority link")).arg(newPriorityLink->getName()));
        }
2118
        _priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink);
2119

2120
        _updateHighLatencyLink(sendCommand);
2121

2122
2123
        emit priorityLinkNameChanged(_priorityLink->getName());
        if (updateActive) {
acfloria's avatar
acfloria committed
2124
            _linkActiveChanged(_priorityLink.data(), _priorityLink->link_active(_id), _id);
2125
2126
        }
    }
2127
2128
}

2129
int Vehicle::motorCount()
Don Gagne's avatar
Don Gagne committed
2130
2131
2132
2133
2134
2135
2136
2137
2138
2139
2140
2141
2142
2143
2144
{
    switch (_vehicleType) {
    case MAV_TYPE_HELICOPTER:
        return 1;
    case MAV_TYPE_VTOL_DUOROTOR:
        return 2;
    case MAV_TYPE_TRICOPTER:
        return 3;
    case MAV_TYPE_QUADROTOR:
    case MAV_TYPE_VTOL_QUADROTOR:
        return 4;
    case MAV_TYPE_HEXAROTOR:
        return 6;
    case MAV_TYPE_OCTOROTOR:
        return 8;
2145
2146
2147
2148
2149
2150
2151
2152
2153
2154
2155
2156
2157
2158
2159
2160
2161
2162
2163
2164
2165
2166
2167
2168
2169
2170
2171
2172
2173
2174
2175
2176
2177
2178
2179
2180
2181
2182
2183
2184
2185
    case MAV_TYPE_SUBMARINE:
    {
        // Supported frame types
        enum {
            SUB_FRAME_BLUEROV1,
            SUB_FRAME_VECTORED,
            SUB_FRAME_VECTORED_6DOF,
            SUB_FRAME_VECTORED_6DOF_90DEG,
            SUB_FRAME_SIMPLEROV_3,
            SUB_FRAME_SIMPLEROV_4,
            SUB_FRAME_SIMPLEROV_5,
            SUB_FRAME_CUSTOM
        };

        uint8_t frameType = parameterManager()->getParameter(_compID, "FRAME_CONFIG")->rawValue().toInt();

        switch (frameType) {  // ardupilot/libraries/AP_Motors/AP_Motors6DOF.h sub_frame_t

        case SUB_FRAME_BLUEROV1:
        case SUB_FRAME_VECTORED:
            return 6;

        case SUB_FRAME_SIMPLEROV_3:
            return 3;

        case SUB_FRAME_SIMPLEROV_4:
            return 4;

        case SUB_FRAME_SIMPLEROV_5:
            return 5;

        case SUB_FRAME_VECTORED_6DOF:
        case SUB_FRAME_VECTORED_6DOF_90DEG:
        case SUB_FRAME_CUSTOM:
            return 8;

        default:
            return -1;
        }
    }

Don Gagne's avatar
Don Gagne committed
2186
2187
2188
2189
2190
    default:
        return -1;
    }
}

2191
bool Vehicle::coaxialMotors()
Don Gagne's avatar
Don Gagne committed
2192
2193
2194
2195
{
    return _firmwarePlugin->multiRotorCoaxialMotors(this);
}

2196
bool Vehicle::xConfigMotors()
Don Gagne's avatar
Don Gagne committed
2197
2198
2199
2200
{
    return _firmwarePlugin->multiRotorXConfig(this);
}

dogmaphobic's avatar
dogmaphobic committed
2201
2202
2203
QString Vehicle::formatedMessages()
{
    QString messages;
2204
    for(UASMessage* message: _toolbox->uasMessageHandler()->messages()) {
dogmaphobic's avatar
dogmaphobic committed
2205
2206
2207
2208
2209
        messages += message->getFormatedText();
    }
    return messages;
}

dogmaphobic's avatar
dogmaphobic committed
2210
2211
void Vehicle::clearMessages()
{
2212
    _toolbox->uasMessageHandler()->clearMessages();
dogmaphobic's avatar
dogmaphobic committed
2213
2214
}

dogmaphobic's avatar
dogmaphobic committed
2215
2216
2217
2218
2219
2220
2221
2222
2223
void Vehicle::_handletextMessageReceived(UASMessage* message)
{
    if(message)
    {
        _formatedMessage = message->getFormatedText();
        emit formatedMessageChanged();
    }
}

2224
2225
2226
2227
2228
2229
2230
2231
2232
2233
2234
2235
2236
2237
2238
void Vehicle::_handleTextMessage(int newCount)
{
    // Reset?
    if(!newCount) {
        _currentMessageCount = 0;
        _currentNormalCount  = 0;
        _currentWarningCount = 0;
        _currentErrorCount   = 0;
        _messageCount        = 0;
        _currentMessageType  = MessageNone;
        emit newMessageCountChanged();
        emit messageTypeChanged();
        emit messageCountChanged();
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
2239

2240
    UASMessageHandler* pMh = _toolbox->uasMessageHandler();
2241
2242
2243
2244
2245
2246
2247
2248
2249
2250
2251
2252
2253
2254
2255
2256
2257
2258
2259
2260
2261
2262
2263
2264
2265
2266
2267
2268
2269
2270
2271
2272
2273
2274
2275
2276
2277
2278
2279
2280
2281
2282
2283
2284
2285
2286
2287
2288
2289
2290
2291
2292
2293
2294
2295
2296
2297
2298
2299
2300
2301
2302
2303
2304
2305
    MessageType_t type = newCount ? _currentMessageType : MessageNone;
    int errorCount     = _currentErrorCount;
    int warnCount      = _currentWarningCount;
    int normalCount    = _currentNormalCount;
    //-- Add current message counts
    errorCount  += pMh->getErrorCount();
    warnCount   += pMh->getWarningCount();
    normalCount += pMh->getNormalCount();
    //-- See if we have a higher level
    if(errorCount != _currentErrorCount) {
        _currentErrorCount = errorCount;
        type = MessageError;
    }
    if(warnCount != _currentWarningCount) {
        _currentWarningCount = warnCount;
        if(_currentMessageType != MessageError) {
            type = MessageWarning;
        }
    }
    if(normalCount != _currentNormalCount) {
        _currentNormalCount = normalCount;
        if(_currentMessageType != MessageError && _currentMessageType != MessageWarning) {
            type = MessageNormal;
        }
    }
    int count = _currentErrorCount + _currentWarningCount + _currentNormalCount;
    if(count != _currentMessageCount) {
        _currentMessageCount = count;
        // Display current total new messages count
        emit newMessageCountChanged();
    }
    if(type != _currentMessageType) {
        _currentMessageType = type;
        // Update message level
        emit messageTypeChanged();
    }
    // Update message count (all messages)
    if(newCount != _messageCount) {
        _messageCount = newCount;
        emit messageCountChanged();
    }
    QString errMsg = pMh->getLatestError();
    if(errMsg != _latestError) {
        _latestError = errMsg;
        emit latestErrorChanged();
    }
}

void Vehicle::resetMessages()
{
    // Reset Counts
    int count = _currentMessageCount;
    MessageType_t type = _currentMessageType;
    _currentErrorCount   = 0;
    _currentWarningCount = 0;
    _currentNormalCount  = 0;
    _currentMessageCount = 0;
    _currentMessageType = MessageNone;
    if(count != _currentMessageCount) {
        emit newMessageCountChanged();
    }
    if(type != _currentMessageType) {
        emit messageTypeChanged();
    }
}
2306

2307
void Vehicle::_loadSettings()
2308
{
2309
2310
2311
    if (!_active) {
        return;
    }
2312
2313
2314
    QSettings settings;
    settings.beginGroup(QString(_settingsGroup).arg(_id));
    bool convertOk;
Gus Grubba's avatar
Gus Grubba committed
2315
    _joystickMode = static_cast<JoystickMode_t>(settings.value(_joystickModeSettingsKey, JoystickModeRC).toInt(&convertOk));
2316
2317
2318
    if (!convertOk) {
        _joystickMode = JoystickModeRC;
    }
2319
    // Joystick enabled is a global setting so first make sure there are any joysticks connected
2320
    if (_toolbox->joystickManager()->joysticks().count()) {
2321
        setJoystickEnabled(settings.value(_joystickEnabledSettingsKey, false).toBool());
2322
        _startJoystick(true);
2323
    }
2324
2325
}

2326
void Vehicle::_saveSettings()
2327
2328
{
    QSettings settings;
dogmaphobic's avatar
dogmaphobic committed
2329

2330
    settings.beginGroup(QString(_settingsGroup).arg(_id));
dogmaphobic's avatar
dogmaphobic committed
2331

2332
    settings.setValue(_joystickModeSettingsKey, _joystickMode);
2333
2334
2335

    // The joystick enabled setting should only be changed if a joystick is present
    // since the checkbox can only be clicked if one is present
2336
    if (_toolbox->joystickManager()->joysticks().count()) {
2337
2338
        settings.setValue(_joystickEnabledSettingsKey, _joystickEnabled);
    }
2339
2340
}

2341
int Vehicle::joystickMode()
2342
2343
2344
2345
2346
2347
2348
2349
2350
2351
{
    return _joystickMode;
}

void Vehicle::setJoystickMode(int mode)
{
    if (mode < 0 || mode >= JoystickModeMax) {
        qCWarning(VehicleLog) << "Invalid joystick mode" << mode;
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
2352

2353
2354
2355
2356
2357
    _joystickMode = (JoystickMode_t)mode;
    _saveSettings();
    emit joystickModeChanged(mode);
}

2358
QStringList Vehicle::joystickModes()
2359
2360
{
    QStringList list;
dogmaphobic's avatar
dogmaphobic committed
2361

Don Gagne's avatar
Don Gagne committed
2362
    list << "Normal" << "Attitude" << "Position" << "Force" << "Velocity";
dogmaphobic's avatar
dogmaphobic committed
2363

2364
2365
    return list;
}
Don Gagne's avatar
Don Gagne committed
2366

2367
bool Vehicle::joystickEnabled()
Don Gagne's avatar
Don Gagne committed
2368
2369
2370
2371
2372
2373
{
    return _joystickEnabled;
}

void Vehicle::setJoystickEnabled(bool enabled)
{
2374
    _joystickEnabled = enabled;
2375
    _startJoystick(_joystickEnabled);
Don Gagne's avatar
Don Gagne committed
2376
    _saveSettings();
2377
    emit joystickEnabledChanged(_joystickEnabled);
Don Gagne's avatar
Don Gagne committed
2378
2379
2380
2381
}

void Vehicle::_startJoystick(bool start)
{
2382
    Joystick* joystick = _joystickManager->activeJoystick();
Don Gagne's avatar
Don Gagne committed
2383
2384
    if (joystick) {
        if (start) {
2385
            joystick->startPolling(this);
Don Gagne's avatar
Don Gagne committed
2386
2387
2388
2389
2390
2391
        } else {
            joystick->stopPolling();
        }
    }
}

2392
bool Vehicle::active()
Don Gagne's avatar
Don Gagne committed
2393
2394
2395
2396
2397
2398
{
    return _active;
}

void Vehicle::setActive(bool active)
{
2399
2400
    if (_active != active) {
        _active = active;
2401
        _startJoystick(false);
2402
2403
        emit activeChanged(_active);
    }
Don Gagne's avatar
Don Gagne committed
2404
}
2405

2406
QGeoCoordinate Vehicle::homePosition()
Don Gagne's avatar
Don Gagne committed
2407
2408
2409
{
    return _homePosition;
}
Don Gagne's avatar
Don Gagne committed
2410
2411
2412
2413

void Vehicle::setArmed(bool armed)
{
    // We specifically use COMMAND_LONG:MAV_CMD_COMPONENT_ARM_DISARM since it is supported by more flight stacks.
2414
    sendMavCommand(_defaultComponentId,
2415
2416
2417
                   MAV_CMD_COMPONENT_ARM_DISARM,
                   true,    // show error if fails
                   armed ? 1.0f : 0.0f);
Don Gagne's avatar
Don Gagne committed
2418
2419
}

2420
bool Vehicle::flightModeSetAvailable()
Don Gagne's avatar
Don Gagne committed
2421
{
2422
    return _firmwarePlugin->isCapable(this, FirmwarePlugin::SetFlightModeCapability);
Don Gagne's avatar
Don Gagne committed
2423
2424
}

2425
QStringList Vehicle::flightModes()
Don Gagne's avatar
Don Gagne committed
2426
{
Daniel Agar's avatar
Daniel Agar committed
2427
    return _firmwarePlugin->flightModes(this);
Don Gagne's avatar
Don Gagne committed
2428
2429
}

2430
QStringList Vehicle::extraJoystickFlightModes()
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
2431
2432
2433
2434
{
    return _firmwarePlugin->extraJoystickFlightModes(this);
}

2435
QString Vehicle::flightMode() const
Don Gagne's avatar
Don Gagne committed
2436
2437
2438
2439
2440
2441
2442
2443
2444
2445
2446
2447
2448
2449
2450
2451
{
    return _firmwarePlugin->flightMode(_base_mode, _custom_mode);
}

void Vehicle::setFlightMode(const QString& flightMode)
{
    uint8_t     base_mode;
    uint32_t    custom_mode;

    if (_firmwarePlugin->setFlightMode(flightMode, &base_mode, &custom_mode)) {
        // setFlightMode will only set MAV_MODE_FLAG_CUSTOM_MODE_ENABLED in base_mode, we need to move back in the existing
        // states.
        uint8_t newBaseMode = _base_mode & ~MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE;
        newBaseMode |= base_mode;

        mavlink_message_t msg;
2452
2453
2454
2455
2456
2457
2458
2459
        mavlink_msg_set_mode_pack_chan(_mavlink->getSystemId(),
                                       _mavlink->getComponentId(),
                                       priorityLink()->mavlinkChannel(),
                                       &msg,
                                       id(),
                                       newBaseMode,
                                       custom_mode);
        sendMessageOnLink(priorityLink(), msg);
Don Gagne's avatar
Don Gagne committed
2460
    } else {
Don Gagne's avatar
Don Gagne committed
2461
        qWarning() << "FirmwarePlugin::setFlightMode failed, flightMode:" << flightMode;
Don Gagne's avatar
Don Gagne committed
2462
2463
2464
    }
}

2465
QString Vehicle::priorityLinkName() const
2466
{
2467
    if (_priorityLink) {
2468
        return _priorityLink->getName();
2469
2470
2471
    }

    return "none";
2472
2473
}

2474
QVariantList Vehicle::links() const {
acfloria's avatar
acfloria committed
2475
2476
    QVariantList ret;

2477
    for( const auto &item: _links )
acfloria's avatar
acfloria committed
2478
2479
2480
2481
2482
        ret << QVariant::fromValue(item);

    return ret;
}

2483
2484
void Vehicle::setPriorityLinkByName(const QString& priorityLinkName)
{
2485
2486
2487
2488
    if (!_priorityLink) {
        return;
    }

2489
2490
2491
2492
2493
    if (priorityLinkName == _priorityLink->getName()) {
        // The link did not change
        return;
    }

2494
    LinkInterface* newPriorityLink = nullptr;
2495
2496
2497
2498
2499
2500
2501
2502
2503


    for (int i=0; i<_links.count(); i++) {
        if (_links[i]->getName() == priorityLinkName) {
            newPriorityLink = _links[i];
        }
    }

    if (newPriorityLink) {
2504
        _priorityLinkCommanded = true;
2505
        _priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink);
2506
        _updateHighLatencyLink(true);
2507
        emit priorityLinkNameChanged(_priorityLink->getName());
acfloria's avatar
acfloria committed
2508
        _linkActiveChanged(_priorityLink.data(), _priorityLink->link_active(_id), _id);
2509
2510
2511
    }
}

2512
bool Vehicle::hilMode()
Don Gagne's avatar
Don Gagne committed
2513
2514
2515
2516
2517
2518
2519
2520
2521
2522
2523
2524
2525
{
    return _base_mode & MAV_MODE_FLAG_HIL_ENABLED;
}

void Vehicle::setHilMode(bool hilMode)
{
    mavlink_message_t msg;

    uint8_t newBaseMode = _base_mode & ~MAV_MODE_FLAG_DECODE_POSITION_HIL;
    if (hilMode) {
        newBaseMode |= MAV_MODE_FLAG_HIL_ENABLED;
    }

2526
2527
2528
2529
2530
2531
2532
2533
    mavlink_msg_set_mode_pack_chan(_mavlink->getSystemId(),
                                   _mavlink->getComponentId(),
                                   priorityLink()->mavlinkChannel(),
                                   &msg,
                                   id(),
                                   newBaseMode,
                                   _custom_mode);
    sendMessageOnLink(priorityLink(), msg);
Don Gagne's avatar
Don Gagne committed
2534
}
2535

Don Gagne's avatar
Don Gagne committed
2536
void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple)
2537
2538
2539
{
    mavlink_message_t               msg;
    mavlink_request_data_stream_t   dataStream;
dogmaphobic's avatar
dogmaphobic committed
2540

Don Gagne's avatar
Don Gagne committed
2541
2542
    memset(&dataStream, 0, sizeof(dataStream));

2543
2544
2545
2546
    dataStream.req_stream_id = stream;
    dataStream.req_message_rate = rate;
    dataStream.start_stop = 1;  // start
    dataStream.target_system = id();
2547
    dataStream.target_component = _defaultComponentId;
dogmaphobic's avatar
dogmaphobic committed
2548

2549
2550
2551
2552
2553
    mavlink_msg_request_data_stream_encode_chan(_mavlink->getSystemId(),
                                                _mavlink->getComponentId(),
                                                priorityLink()->mavlinkChannel(),
                                                &msg,
                                                &dataStream);
2554

Don Gagne's avatar
Don Gagne committed
2555
2556
2557
2558
    if (sendMultiple) {
        // We use sendMessageMultiple since we really want these to make it to the vehicle
        sendMessageMultiple(msg);
    } else {
2559
        sendMessageOnLink(priorityLink(), msg);
Don Gagne's avatar
Don Gagne committed
2560
    }
2561
2562
}

2563
void Vehicle::_sendMessageMultipleNext()
2564
2565
2566
{
    if (_nextSendMessageMultipleIndex < _sendMessageMultipleList.count()) {
        qCDebug(VehicleLog) << "_sendMessageMultipleNext:" << _sendMessageMultipleList[_nextSendMessageMultipleIndex].message.msgid;
dogmaphobic's avatar
dogmaphobic committed
2567

2568
        sendMessageOnLink(priorityLink(), _sendMessageMultipleList[_nextSendMessageMultipleIndex].message);
dogmaphobic's avatar
dogmaphobic committed
2569

2570
2571
2572
2573
2574
2575
        if (--_sendMessageMultipleList[_nextSendMessageMultipleIndex].retryCount <= 0) {
            _sendMessageMultipleList.removeAt(_nextSendMessageMultipleIndex);
        } else {
            _nextSendMessageMultipleIndex++;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
2576

2577
2578
2579
2580
2581
2582
2583
2584
    if (_nextSendMessageMultipleIndex >= _sendMessageMultipleList.count()) {
        _nextSendMessageMultipleIndex = 0;
    }
}

void Vehicle::sendMessageMultiple(mavlink_message_t message)
{
    SendMessageMultipleInfo_t   info;
dogmaphobic's avatar
dogmaphobic committed
2585

2586
2587
    info.message =      message;
    info.retryCount =   _sendMessageMultipleRetries;
dogmaphobic's avatar
dogmaphobic committed
2588

2589
2590
    _sendMessageMultipleList.append(info);
}
2591
2592
2593
2594

void Vehicle::_missionManagerError(int errorCode, const QString& errorMsg)
{
    Q_UNUSED(errorCode);
DonLakeFlyer's avatar
DonLakeFlyer committed
2595
    qgcApp()->showMessage(tr("Mission transfer failed. Retry transfer. Error: %1").arg(errorMsg));
2596
}
Don Gagne's avatar
Don Gagne committed
2597

Don Gagne's avatar
Don Gagne committed
2598
2599
2600
void Vehicle::_geoFenceManagerError(int errorCode, const QString& errorMsg)
{
    Q_UNUSED(errorCode);
DonLakeFlyer's avatar
DonLakeFlyer committed
2601
    qgcApp()->showMessage(tr("GeoFence transfer failed. Retry transfer. Error: %1").arg(errorMsg));
2602
2603
2604
2605
2606
}

void Vehicle::_rallyPointManagerError(int errorCode, const QString& errorMsg)
{
    Q_UNUSED(errorCode);
DonLakeFlyer's avatar
DonLakeFlyer committed
2607
    qgcApp()->showMessage(tr("Rally Point transfer failed. Retry transfer. Error: %1").arg(errorMsg));
Don Gagne's avatar
Don Gagne committed
2608
2609
}

2610
void Vehicle::_clearCameraTriggerPoints()
2611
2612
{
    _cameraTriggerPoints.clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
2613
2614
}

2615
void Vehicle::_flightTimerStart()
Don Gagne's avatar
Don Gagne committed
2616
{
2617
    _flightTimer.start();
DonLakeFlyer's avatar
   
DonLakeFlyer committed
2618
    _flightTimeUpdater.start();
2619
    _flightDistanceFact.setRawValue(0);
2620
    _flightTimeFact.setRawValue(0);
Don Gagne's avatar
Don Gagne committed
2621
2622
}

2623
void Vehicle::_flightTimerStop()
DonLakeFlyer's avatar
   
DonLakeFlyer committed
2624
2625
2626
2627
{
    _flightTimeUpdater.stop();
}

2628
void Vehicle::_updateFlightTime()
DonLakeFlyer's avatar
   
DonLakeFlyer committed
2629
2630
2631
2632
{
    _flightTimeFact.setRawValue((double)_flightTimer.elapsed() / 1000.0);
}

2633
void Vehicle::_startPlanRequest()
2634
{
DonLakeFlyer's avatar
DonLakeFlyer committed
2635
    if (_missionManagerInitialRequestSent) {
Don Gagne's avatar
   
Don Gagne committed
2636
        // We have already started (or possibly completed) the sequence of requesting the plan for the first time
DonLakeFlyer's avatar
DonLakeFlyer committed
2637
2638
2639
        return;
    }

Don Gagne's avatar
   
Don Gagne committed
2640
2641
2642
2643
    // We don't start the Plan request until the following things are satisfied:
    //  - Parameter download is complete
    //  - We know the vehicle capabilities
    //  - We know the max mavlink protocol version
DonLakeFlyer's avatar
   
DonLakeFlyer committed
2644
    if (_parameterManager->parametersReady() && _capabilityBitsKnown && _mavlinkProtocolRequestComplete) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2645
        qCDebug(VehicleLog) << "_startPlanRequest";
2646
        _missionManagerInitialRequestSent = true;
2647
2648
2649
2650
        if (_settingsManager->appSettings()->autoLoadMissions()->rawValue().toBool()) {
            QString missionAutoLoadDirPath = _settingsManager->appSettings()->missionSavePath();
            if (!missionAutoLoadDirPath.isEmpty()) {
                QDir missionAutoLoadDir(missionAutoLoadDirPath);
2651
2652
                QString autoloadFilename = missionAutoLoadDir.absoluteFilePath(tr("AutoLoad%1.%2").arg(_id).arg(AppSettings::planFileExtension));
                if (QFile(autoloadFilename).exists()) {
2653
                    _initialPlanRequestComplete = true; // We aren't going to load from the vehicle, so we are done
2654
                    PlanMasterController::sendPlanToVehicle(this, autoloadFilename);
2655
2656
                    return;
                }
Don Gagne's avatar
Don Gagne committed
2657
2658
            }
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
2659
        _missionManager->loadFromVehicle();
2660
2661
    } else {
        if (!_parameterManager->parametersReady()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2662
            qCDebug(VehicleLog) << "Delaying _startPlanRequest due to parameters not ready";
DonLakeFlyer's avatar
   
DonLakeFlyer committed
2663
        } else if (!_capabilityBitsKnown) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2664
            qCDebug(VehicleLog) << "Delaying _startPlanRequest due to vehicle capabilities not known";
Don Gagne's avatar
   
Don Gagne committed
2665
2666
        } else if (!_mavlinkProtocolRequestComplete) {
            qCDebug(VehicleLog) << "Delaying _startPlanRequest due to mavlink protocol request not complete";
2667
2668
2669
2670
        }
    }
}

2671
void Vehicle::_missionLoadComplete()
DonLakeFlyer's avatar
DonLakeFlyer committed
2672
2673
2674
2675
{
    // After the initial mission request completes we ask for the geofence
    if (!_geoFenceManagerInitialRequestSent) {
        _geoFenceManagerInitialRequestSent = true;
2676
2677
2678
2679
2680
2681
2682
        if (_geoFenceManager->supported()) {
            qCDebug(VehicleLog) << "_missionLoadComplete requesting GeoFence";
            _geoFenceManager->loadFromVehicle();
        } else {
            qCDebug(VehicleLog) << "_missionLoadComplete GeoFence not supported skipping";
            _geoFenceLoadComplete();
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
2683
2684
2685
    }
}

2686
void Vehicle::_geoFenceLoadComplete()
DonLakeFlyer's avatar
DonLakeFlyer committed
2687
2688
2689
2690
{
    // After geofence request completes we ask for the rally points
    if (!_rallyPointManagerInitialRequestSent) {
        _rallyPointManagerInitialRequestSent = true;
2691
2692
2693
2694
2695
2696
2697
        if (_rallyPointManager->supported()) {
            qCDebug(VehicleLog) << "_missionLoadComplete requesting Rally Points";
            _rallyPointManager->loadFromVehicle();
        } else {
            qCDebug(VehicleLog) << "_missionLoadComplete Rally Points not supported skipping";
            _rallyPointLoadComplete();
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
2698
2699
2700
    }
}

2701
void Vehicle::_rallyPointLoadComplete()
DonLakeFlyer's avatar
DonLakeFlyer committed
2702
{
DonLakeFlyer's avatar
DonLakeFlyer committed
2703
    qCDebug(VehicleLog) << "_missionLoadComplete _initialPlanRequestComplete = true";
2704
2705
    if (!_initialPlanRequestComplete) {
        _initialPlanRequestComplete = true;
Don Gagne's avatar
Don Gagne committed
2706
        emit initialPlanRequestCompleteChanged(true);
2707
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2708
2709
}

2710
2711
void Vehicle::_parametersReady(bool parametersReady)
{
Don Gagne's avatar
   
Don Gagne committed
2712
    qDebug() << "_parametersReady" << parametersReady;
2713
2714
2715
2716
    // Try to set current unix time to the vehicle
    _sendQGCTimeToVehicle();
    // Send time twice, more likely to get to the vehicle on a noisy link
    _sendQGCTimeToVehicle();
2717
    if (parametersReady) {
2718
        _setupAutoDisarmSignalling();
DonLakeFlyer's avatar
DonLakeFlyer committed
2719
        _startPlanRequest();
Lorenz Meier's avatar
Lorenz Meier committed
2720
    }
2721
}
2722

2723
void Vehicle::_sendQGCTimeToVehicle()
2724
2725
2726
2727
2728
2729
2730
2731
2732
{
    mavlink_message_t       msg;
    mavlink_system_time_t   cmd;

    // Timestamp of the master clock in microseconds since UNIX epoch.
    cmd.time_unix_usec = QDateTime::currentDateTime().currentMSecsSinceEpoch()*1000;
    // Timestamp of the component clock since boot time in milliseconds (Not necessary).
    cmd.time_boot_ms = 0;
    mavlink_msg_system_time_encode_chan(_mavlink->getSystemId(),
2733
2734
2735
2736
                                        _mavlink->getComponentId(),
                                        priorityLink()->mavlinkChannel(),
                                        &msg,
                                        &cmd);
2737
2738
2739
2740

    sendMessageOnLink(priorityLink(), msg);
}

2741
void Vehicle::disconnectInactiveVehicle()
2742
{
Don Gagne's avatar
Don Gagne committed
2743
    // Vehicle is no longer communicating with us, disconnect all links
2744

2745
    LinkManager* linkMgr = _toolbox->linkManager();
2746
    for (int i=0; i<_links.count(); i++) {
2747
2748
        // FIXME: This linkInUse check is a hack fix for multiple vehicles on the same link.
        // The real fix requires significant restructuring which will come later.
2749
        if (!_toolbox->multiVehicleManager()->linkInUse(_links[i], this)) {
2750
2751
            linkMgr->disconnectLink(_links[i]);
        }
2752
    }
acfloria's avatar
acfloria committed
2753
    emit linksChanged();
2754
}
2755

dogmaphobic's avatar
dogmaphobic committed
2756
2757
2758
2759
2760
void Vehicle::_imageReady(UASInterface*)
{
    if(_uas)
    {
        QImage img = _uas->getImage();
2761
        _toolbox->imageProvider()->setImage(&img, _id);
dogmaphobic's avatar
dogmaphobic committed
2762
2763
2764
2765
        _flowImageIndex++;
        emit flowImageIndexChanged();
    }
}
Don Gagne's avatar
Don Gagne committed
2766
2767
2768

void Vehicle::_remoteControlRSSIChanged(uint8_t rssi)
{
2769
2770
2771
2772
2773
2774
2775
2776
2777
2778
2779
    //-- 0 <= rssi <= 100 - 255 means "invalid/unknown"
    if(rssi > 100) { // Anything over 100 doesn't make sense
        if(_rcRSSI != 255) {
            _rcRSSI = 255;
            emit rcRSSIChanged(_rcRSSI);
        }
        return;
    }
    //-- Initialize it
    if(_rcRSSIstore == 255.) {
        _rcRSSIstore = (double)rssi;
2780
    }
Don Gagne's avatar
Don Gagne committed
2781
2782
2783
2784
2785
2786
2787
2788
2789
2790
2791
    // Low pass to git rid of jitter
    _rcRSSIstore = (_rcRSSIstore * 0.9f) + ((float)rssi * 0.1);
    uint8_t filteredRSSI = (uint8_t)ceil(_rcRSSIstore);
    if(_rcRSSIstore < 0.1) {
        filteredRSSI = 0;
    }
    if(_rcRSSI != filteredRSSI) {
        _rcRSSI = filteredRSSI;
        emit rcRSSIChanged(_rcRSSI);
    }
}
Don Gagne's avatar
Don Gagne committed
2792

Gus Grubba's avatar
Gus Grubba committed
2793
void Vehicle::virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust)
Don Gagne's avatar
Don Gagne committed
2794
{
2795
    // The following if statement prevents the virtualTabletJoystick from sending values if the standard joystick is enabled
2796
    if ( !_joystickEnabled && !_highLatencyLink) {
Gus Grubba's avatar
Gus Grubba committed
2797
2798
2799
2800
2801
2802
        _uas->setExternalControlSetpoint(
            static_cast<float>(roll),
            static_cast<float>(pitch),
            static_cast<float>(yaw),
            static_cast<float>(thrust),
            0, JoystickModeRC);
2803
    }
Don Gagne's avatar
Don Gagne committed
2804
}
2805
2806
2807
2808
2809
2810
2811
2812
2813

void Vehicle::setConnectionLostEnabled(bool connectionLostEnabled)
{
    if (_connectionLostEnabled != connectionLostEnabled) {
        _connectionLostEnabled = connectionLostEnabled;
        emit connectionLostEnabledChanged(_connectionLostEnabled);
    }
}

2814
void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID)
2815
{
2816
2817
    // only continue if the vehicle id is correct
    if (vehicleID != _id) {
2818
2819
2820
        return;
    }

acfloria's avatar
acfloria committed
2821
    emit linksPropertiesChanged();
2822

2823
2824
2825
    bool communicationLost = false;
    bool communicationRegained = false;

2826
2827
2828
2829
    if (link == _priorityLink) {
        if (active && _connectionLost) {
            // communication to priority link regained
            _connectionLost = false;
2830
            communicationRegained = true;
2831
            emit connectionLostChanged(false);
2832

2833
2834
2835
2836
2837
2838
2839
2840
            if (_priorityLink->highLatency()) {
                _setMaxProtoVersion(100);
            } else {
                // Re-negotiate protocol version for the link
                sendMavCommand(MAV_COMP_ID_ALL,                         // Don't know default component id yet.
                               MAV_CMD_REQUEST_PROTOCOL_VERSION,
                               false,                                   // No error shown if fails
                               1);                                     // Request protocol version
2841
            }
2842
        } else if (!active && !_connectionLost) {
2843
            _updatePriorityLink(false /* updateActive */, false /* sendCommand */);
2844

2845
            if (link == _priorityLink) {
Don Gagne's avatar
   
Don Gagne committed
2846
                // No other link to switch to was found, notify user of comm lossf
2847
2848
2849
2850
2851
2852
2853
2854
2855
                _connectionLost = true;
                communicationLost = true;
                _heardFrom = false;
                emit connectionLostChanged(true);

                if (_autoDisconnect) {
                    // Reset link state
                    for (int i = 0; i < _links.length(); i++) {
                        _mavlink->resetMetadataForLink(_links.at(i));
2856
                    }
2857
2858

                    disconnectInactiveVehicle();
2859
2860
2861
2862
                }
            }
        }
    } else {
2863
        qgcApp()->showMessage((tr("%1 communication to auxiliary link %2 %3")).arg(_vehicleIdSpeech()).arg(link->getName()).arg(active ? "regained" : "lost"));
acfloria's avatar
acfloria committed
2864
        _updatePriorityLink(false /* updateActive */, true /* sendCommand */);
2865
    }
2866
2867
2868
2869
2870
2871
2872
2873
2874
2875
2876
2877
2878
2879
2880
2881
2882
2883
2884
2885
2886
2887
2888
2889
2890

    QString commSpeech;
    bool multiVehicle = _toolbox->multiVehicleManager()->vehicles()->count() > 1;
    if (communicationRegained) {
        commSpeech = tr("Communication regained");
        if (_links.count() > 1) {
            qgcApp()->showMessage(tr("Communication regained to vehicle %1 on %2 link %3").arg(_id).arg(_links.count() > 1 ? tr("priority") : tr("auxiliary")).arg(link->getName()));
        } else if (multiVehicle) {
            qgcApp()->showMessage(tr("Communication regained to vehicle %1").arg(_id));
        }
    }
    if (communicationLost) {
        commSpeech = tr("Communication lost");
        if (_links.count() > 1) {
            qgcApp()->showMessage(tr("Communication lost to vehicle %1 on %2 link %3").arg(_id).arg(_links.count() > 1 ? tr("priority") : tr("auxiliary")).arg(link->getName()));
        } else if (multiVehicle) {
            qgcApp()->showMessage(tr("Communication lost to vehicle %1").arg(_id));
        }
    }
    if (multiVehicle && (communicationLost || communicationRegained)) {
        commSpeech.append(tr(" to vehicle %1").arg(_id));
    }
    if (!commSpeech.isEmpty()) {
        _say(commSpeech);
    }
2891
2892
}

Don Gagne's avatar
Don Gagne committed
2893
void Vehicle::_say(const QString& text)
2894
{
2895
    _toolbox->audioOutput()->say(text.toLower());
2896
}
2897

2898
bool Vehicle::fixedWing() const
2899
{
2900
    return QGCMAVLink::isFixedWing(vehicleType());
2901
2902
}

2903
bool Vehicle::rover() const
Don Gagne's avatar
Don Gagne committed
2904
{
2905
    return QGCMAVLink::isRover(vehicleType());
Don Gagne's avatar
Don Gagne committed
2906
2907
}

2908
bool Vehicle::sub() const
2909
{
2910
    return QGCMAVLink::isSub(vehicleType());
2911
2912
}

2913
bool Vehicle::multiRotor() const
2914
{
2915
    return QGCMAVLink::isMultiRotor(vehicleType());
2916
}
Don Gagne's avatar
Don Gagne committed
2917

2918
bool Vehicle::vtol() const
Don Gagne's avatar
Don Gagne committed
2919
{
2920
    return _firmwarePlugin->isVtol(this);
Don Gagne's avatar
Don Gagne committed
2921
2922
}

2923
bool Vehicle::supportsThrottleModeCenterZero() const
2924
2925
2926
2927
{
    return _firmwarePlugin->supportsThrottleModeCenterZero();
}

2928
bool Vehicle::supportsNegativeThrust()
2929
{
2930
    return _firmwarePlugin->supportsNegativeThrust(this);
2931
2932
}

2933
bool Vehicle::supportsRadio() const
2934
2935
2936
2937
{
    return _firmwarePlugin->supportsRadio();
}

2938
bool Vehicle::supportsJSButton() const
2939
2940
2941
2942
{
    return _firmwarePlugin->supportsJSButton();
}

2943
bool Vehicle::supportsMotorInterference() const
Jacob Walser's avatar
Jacob Walser committed
2944
2945
2946
2947
{
    return _firmwarePlugin->supportsMotorInterference();
}

2948
bool Vehicle::supportsTerrainFrame() const
2949
2950
2951
2952
{
    return _firmwarePlugin->supportsTerrainFrame();
}

2953
2954
2955
2956
2957
2958
2959
2960
2961
2962
2963
2964
2965
2966
2967
2968
2969
2970
2971
2972
2973
2974
2975
2976
2977
2978
2979
2980
2981
2982
2983
2984
2985
2986
QString Vehicle::vehicleTypeName() const {
    static QMap<int, QString> typeNames = {
        { MAV_TYPE_GENERIC,         tr("Generic micro air vehicle" )},
        { MAV_TYPE_FIXED_WING,      tr("Fixed wing aircraft")},
        { MAV_TYPE_QUADROTOR,       tr("Quadrotor")},
        { MAV_TYPE_COAXIAL,         tr("Coaxial helicopter")},
        { MAV_TYPE_HELICOPTER,      tr("Normal helicopter with tail rotor.")},
        { MAV_TYPE_ANTENNA_TRACKER, tr("Ground installation")},
        { MAV_TYPE_GCS,             tr("Operator control unit / ground control station")},
        { MAV_TYPE_AIRSHIP,         tr("Airship, controlled")},
        { MAV_TYPE_FREE_BALLOON,    tr("Free balloon, uncontrolled")},
        { MAV_TYPE_ROCKET,          tr("Rocket")},
        { MAV_TYPE_GROUND_ROVER,    tr("Ground rover")},
        { MAV_TYPE_SURFACE_BOAT,    tr("Surface vessel, boat, ship")},
        { MAV_TYPE_SUBMARINE,       tr("Submarine")},
        { MAV_TYPE_HEXAROTOR,       tr("Hexarotor")},
        { MAV_TYPE_OCTOROTOR,       tr("Octorotor")},
        { MAV_TYPE_TRICOPTER,       tr("Octorotor")},
        { MAV_TYPE_FLAPPING_WING,   tr("Flapping wing")},
        { MAV_TYPE_KITE,            tr("Flapping wing")},
        { MAV_TYPE_ONBOARD_CONTROLLER, tr("Onboard companion controller")},
        { MAV_TYPE_VTOL_DUOROTOR,   tr("Two-rotor VTOL using control surfaces in vertical operation in addition. Tailsitter")},
        { MAV_TYPE_VTOL_QUADROTOR,  tr("Quad-rotor VTOL using a V-shaped quad config in vertical operation. Tailsitter")},
        { MAV_TYPE_VTOL_TILTROTOR,  tr("Tiltrotor VTOL")},
        { MAV_TYPE_VTOL_RESERVED2,  tr("VTOL reserved 2")},
        { MAV_TYPE_VTOL_RESERVED3,  tr("VTOL reserved 3")},
        { MAV_TYPE_VTOL_RESERVED4,  tr("VTOL reserved 4")},
        { MAV_TYPE_VTOL_RESERVED5,  tr("VTOL reserved 5")},
        { MAV_TYPE_GIMBAL,          tr("Onboard gimbal")},
        { MAV_TYPE_ADSB,            tr("Onboard ADSB peripheral")},
    };
    return typeNames[_vehicleType];
}

Don Gagne's avatar
Don Gagne committed
2987
/// Returns the string to speak to identify the vehicle
2988
QString Vehicle::_vehicleIdSpeech()
Don Gagne's avatar
Don Gagne committed
2989
{
2990
    if (_toolbox->multiVehicleManager()->vehicles()->count() > 1) {
2991
        return tr("vehicle %1").arg(id());
Don Gagne's avatar
Don Gagne committed
2992
    } else {
2993
        return QString();
Don Gagne's avatar
Don Gagne committed
2994
2995
2996
    }
}

Don Gagne's avatar
Don Gagne committed
2997
void Vehicle::_handleFlightModeChanged(const QString& flightMode)
Don Gagne's avatar
Don Gagne committed
2998
{
2999
    _say(tr("%1 %2 flight mode").arg(_vehicleIdSpeech()).arg(flightMode));
Don Gagne's avatar
Don Gagne committed
3000
    emit guidedModeChanged(_firmwarePlugin->isGuidedMode(this));
3001
3002
3003
3004
}

void Vehicle::_announceArmedChanged(bool armed)
{
3005
    _say(QString("%1 %2").arg(_vehicleIdSpeech()).arg(armed ? tr("armed") : tr("disarmed")));
Gus Grubba's avatar
Gus Grubba committed
3006
3007
3008
3009
3010
    if(armed) {
        //-- Keep track of armed coordinates
        _armedPosition = _coordinate;
        emit armedPositionChanged();
    }
Don Gagne's avatar
Don Gagne committed
3011
3012
}

3013
void Vehicle::_setFlying(bool flying)
Don Gagne's avatar
Don Gagne committed
3014
{
3015
    if (_flying != flying) {
Don Gagne's avatar
Don Gagne committed
3016
3017
3018
3019
3020
        _flying = flying;
        emit flyingChanged(flying);
    }
}

3021
3022
3023
3024
3025
3026
3027
3028
void Vehicle::_setLanding(bool landing)
{
    if (armed() && _landing != landing) {
        _landing = landing;
        emit landingChanged(landing);
    }
}

3029
bool Vehicle::guidedModeSupported() const
Don Gagne's avatar
Don Gagne committed
3030
{
3031
    return _firmwarePlugin->isCapable(this, FirmwarePlugin::GuidedModeCapability);
Don Gagne's avatar
Don Gagne committed
3032
3033
}

3034
bool Vehicle::pauseVehicleSupported() const
Don Gagne's avatar
Don Gagne committed
3035
{
3036
3037
3038
3039
3040
3041
    return _firmwarePlugin->isCapable(this, FirmwarePlugin::PauseVehicleCapability);
}

bool Vehicle::orbitModeSupported() const
{
    return _firmwarePlugin->isCapable(this, FirmwarePlugin::OrbitModeCapability);
Don Gagne's avatar
Don Gagne committed
3042
3043
}

Gus Grubba's avatar
Gus Grubba committed
3044
3045
3046
3047
3048
bool Vehicle::roiModeSupported() const
{
    return _firmwarePlugin->isCapable(this, FirmwarePlugin::ROIModeCapability);
}

3049
3050
3051
3052
3053
bool Vehicle::takeoffVehicleSupported() const
{
    return _firmwarePlugin->isCapable(this, FirmwarePlugin::TakeoffVehicleCapability);
}

Don Gagne's avatar
   
Don Gagne committed
3054
3055
3056
3057
3058
QString Vehicle::gotoFlightMode() const
{
    return _firmwarePlugin->gotoFlightMode();
}

DonLakeFlyer's avatar
   
DonLakeFlyer committed
3059
void Vehicle::guidedModeRTL(bool smartRTL)
Don Gagne's avatar
Don Gagne committed
3060
3061
{
    if (!guidedModeSupported()) {
3062
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
3063
3064
        return;
    }
DonLakeFlyer's avatar
   
DonLakeFlyer committed
3065
    _firmwarePlugin->guidedModeRTL(this, smartRTL);
Don Gagne's avatar
Don Gagne committed
3066
3067
}

3068
void Vehicle::guidedModeLand()
Don Gagne's avatar
Don Gagne committed
3069
3070
{
    if (!guidedModeSupported()) {
3071
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
3072
3073
3074
3075
3076
        return;
    }
    _firmwarePlugin->guidedModeLand(this);
}

3077
void Vehicle::guidedModeTakeoff(double altitudeRelative)
Don Gagne's avatar
Don Gagne committed
3078
3079
{
    if (!guidedModeSupported()) {
3080
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
3081
3082
        return;
    }
3083
    _firmwarePlugin->guidedModeTakeoff(this, altitudeRelative);
3084
3085
}

3086
double Vehicle::minimumTakeoffAltitude()
3087
3088
3089
3090
{
    return _firmwarePlugin->minimumTakeoffAltitude(this);
}

3091
void Vehicle::startMission()
3092
3093
{
    _firmwarePlugin->startMission(this);
Don Gagne's avatar
Don Gagne committed
3094
3095
3096
3097
3098
}

void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord)
{
    if (!guidedModeSupported()) {
3099
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
3100
3101
        return;
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
3102
3103
3104
    if (!coordinate().isValid()) {
        return;
    }
Don Gagne's avatar
   
Don Gagne committed
3105
    double maxDistance = _settingsManager->flyViewSettings()->maxGoToLocationDistance()->rawValue().toDouble();
DonLakeFlyer's avatar
DonLakeFlyer committed
3106
    if (coordinate().distanceTo(gotoCoord) > maxDistance) {
Don Gagne's avatar
   
Don Gagne committed
3107
        qgcApp()->showMessage(QString("New location is too far. Must be less than %1 %2.").arg(qRound(FactMetaData::metersToAppSettingsDistanceUnits(maxDistance).toDouble())).arg(FactMetaData::appSettingsDistanceUnitsString()));
DonLakeFlyer's avatar
DonLakeFlyer committed
3108
3109
        return;
    }
Don Gagne's avatar
Don Gagne committed
3110
3111
3112
    _firmwarePlugin->guidedModeGotoLocation(this, gotoCoord);
}

DonLakeFlyer's avatar
DonLakeFlyer committed
3113
void Vehicle::guidedModeChangeAltitude(double altitudeChange)
Don Gagne's avatar
Don Gagne committed
3114
3115
{
    if (!guidedModeSupported()) {
3116
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
3117
3118
        return;
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
3119
    _firmwarePlugin->guidedModeChangeAltitude(this, altitudeChange);
Don Gagne's avatar
Don Gagne committed
3120
3121
}

DonLakeFlyer's avatar
DonLakeFlyer committed
3122
void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude)
dogmaphobic's avatar
dogmaphobic committed
3123
{
3124
3125
    if (!orbitModeSupported()) {
        qgcApp()->showMessage(QStringLiteral("Orbit mode not supported by Vehicle."));
dogmaphobic's avatar
dogmaphobic committed
3126
3127
        return;
    }
Don Gagne's avatar
   
Don Gagne committed
3128
    if (capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
Gus Grubba's avatar
Gus Grubba committed
3129
3130
3131
3132
3133
3134
3135
3136
3137
3138
        sendMavCommandInt(
            defaultComponentId(),
            MAV_CMD_DO_ORBIT,
            MAV_FRAME_GLOBAL,
            true,                           // show error if fails
            static_cast<float>(radius),
            static_cast<float>(qQNaN()),    // Use default velocity
            0,                              // Vehicle points to center
            static_cast<float>(qQNaN()),    // reserved
            centerCoord.latitude(), centerCoord.longitude(), static_cast<float>(amslAltitude));
3139
    } else {
Gus Grubba's avatar
Gus Grubba committed
3140
3141
3142
3143
3144
3145
3146
3147
3148
3149
3150
        sendMavCommand(
            defaultComponentId(),
            MAV_CMD_DO_ORBIT,
            true,                           // show error if fails
            static_cast<float>(radius),
            static_cast<float>(qQNaN()),    // Use default velocity
            0,                              // Vehicle points to center
            static_cast<float>(qQNaN()),    // reserved
            static_cast<float>(centerCoord.latitude()),
            static_cast<float>(centerCoord.longitude()),
            static_cast<float>(amslAltitude));
3151
    }
dogmaphobic's avatar
dogmaphobic committed
3152
3153
}

Gus Grubba's avatar
Gus Grubba committed
3154
3155
3156
3157
3158
3159
3160
3161
3162
3163
3164
3165
3166
3167
3168
3169
void Vehicle::guidedModeROI(const QGeoCoordinate& centerCoord)
{
    if (!roiModeSupported()) {
        qgcApp()->showMessage(QStringLiteral("ROI mode not supported by Vehicle."));
        return;
    }
    if (capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
        sendMavCommandInt(
            defaultComponentId(),
            MAV_CMD_DO_SET_ROI_LOCATION,
            MAV_FRAME_GLOBAL,
            true,                           // show error if fails
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()),    // Empty
Gus Grubba's avatar
Gus Grubba committed
3170
3171
3172
            centerCoord.latitude(),
            centerCoord.longitude(),
            static_cast<float>(centerCoord.altitude()));
Gus Grubba's avatar
Gus Grubba committed
3173
3174
3175
3176
3177
3178
3179
3180
3181
3182
3183
3184
3185
3186
3187
    } else {
        sendMavCommand(
            defaultComponentId(),
            MAV_CMD_DO_SET_ROI_LOCATION,
            true,                           // show error if fails
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(centerCoord.latitude()),
            static_cast<float>(centerCoord.longitude()),
            static_cast<float>(centerCoord.altitude()));
    }
}

3188
3189
3190
3191
3192
3193
3194
3195
3196
3197
3198
3199
3200
3201
3202
3203
3204
3205
3206
3207
3208
3209
3210
3211
3212
3213
3214
3215
3216
3217
3218
3219
3220
3221
void Vehicle::stopGuidedModeROI()
{
    if (!roiModeSupported()) {
        qgcApp()->showMessage(QStringLiteral("ROI mode not supported by Vehicle."));
        return;
    }
    if (capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
        sendMavCommandInt(
            defaultComponentId(),
            MAV_CMD_DO_SET_ROI_NONE,
            MAV_FRAME_GLOBAL,
            true,                           // show error if fails
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()),    // Empty
            static_cast<double>(qQNaN()),   // Empty
            static_cast<double>(qQNaN()),   // Empty
            static_cast<float>(qQNaN()));   // Empty
    } else {
        sendMavCommand(
            defaultComponentId(),
            MAV_CMD_DO_SET_ROI_NONE,
            true,                           // show error if fails
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()),    // Empty
            static_cast<float>(qQNaN()));   // Empty
    }
}

3222
void Vehicle::pauseVehicle()
Don Gagne's avatar
Don Gagne committed
3223
3224
3225
3226
3227
3228
3229
3230
{
    if (!pauseVehicleSupported()) {
        qgcApp()->showMessage(QStringLiteral("Pause not supported by vehicle."));
        return;
    }
    _firmwarePlugin->pauseVehicle(this);
}

3231
void Vehicle::abortLanding(double climbOutAltitude)
3232
{
Gus Grubba's avatar
Gus Grubba committed
3233
3234
3235
3236
3237
    sendMavCommand(
        defaultComponentId(),
        MAV_CMD_DO_GO_AROUND,
        true,        // show error if fails
        static_cast<float>(climbOutAltitude));
3238
3239
}

3240
bool Vehicle::guidedMode() const
Don Gagne's avatar
Don Gagne committed
3241
3242
3243
3244
3245
3246
3247
3248
3249
{
    return _firmwarePlugin->isGuidedMode(this);
}

void Vehicle::setGuidedMode(bool guidedMode)
{
    return _firmwarePlugin->setGuidedMode(this, guidedMode);
}

3250
void Vehicle::emergencyStop()
Don Gagne's avatar
Don Gagne committed
3251
{
Gus Grubba's avatar
Gus Grubba committed
3252
3253
3254
3255
3256
3257
    sendMavCommand(
        _defaultComponentId,
        MAV_CMD_COMPONENT_ARM_DISARM,
        true,        // show error if fails
        0.0f,
        21196.0f);  // Magic number for emergency stop
Don Gagne's avatar
Don Gagne committed
3258
3259
}

3260
3261
3262
3263
3264
3265
void Vehicle::setCurrentMissionSequence(int seq)
{
    if (!_firmwarePlugin->sendHomePositionToVehicle()) {
        seq--;
    }
    mavlink_message_t msg;
Gus Grubba's avatar
Gus Grubba committed
3266
3267
3268
3269
3270
3271
3272
    mavlink_msg_mission_set_current_pack_chan(
        static_cast<uint8_t>(_mavlink->getSystemId()),
        static_cast<uint8_t>(_mavlink->getComponentId()),
        priorityLink()->mavlinkChannel(),
        &msg,
        static_cast<uint8_t>(id()),
        _compID,
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
3273
        static_cast<uint16_t>(seq));
3274
    sendMessageOnLink(priorityLink(), msg);
3275
3276
}

3277
void Vehicle::sendMavCommand(int component, MAV_CMD command, bool showError, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
Don Gagne's avatar
Don Gagne committed
3278
{
3279
3280
    MavCommandQueueEntry_t entry;

3281
    entry.commandInt = false;
3282
3283
3284
    entry.component = component;
    entry.command = command;
    entry.showError = showError;
Gus Grubba's avatar
Gus Grubba committed
3285
3286
3287
3288
3289
3290
3291
    entry.rgParam[0] = static_cast<double>(param1);
    entry.rgParam[1] = static_cast<double>(param2);
    entry.rgParam[2] = static_cast<double>(param3);
    entry.rgParam[3] = static_cast<double>(param4);
    entry.rgParam[4] = static_cast<double>(param5);
    entry.rgParam[5] = static_cast<double>(param6);
    entry.rgParam[6] = static_cast<double>(param7);
3292
3293
3294
3295
3296
3297
3298
3299
3300

    _mavCommandQueue.append(entry);

    if (_mavCommandQueue.count() == 1) {
        _mavCommandRetryCount = 0;
        _sendMavCommandAgain();
    }
}

3301
3302
3303
3304
3305
void Vehicle::sendMavCommandInt(int component, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7)
{
    MavCommandQueueEntry_t entry;

    entry.commandInt = true;
3306
3307
    entry.component = component;
    entry.command = command;
3308
    entry.frame = frame;
3309
    entry.showError = showError;
Gus Grubba's avatar
Gus Grubba committed
3310
3311
3312
3313
    entry.rgParam[0] = static_cast<double>(param1);
    entry.rgParam[1] = static_cast<double>(param2);
    entry.rgParam[2] = static_cast<double>(param3);
    entry.rgParam[3] = static_cast<double>(param4);
3314
3315
    entry.rgParam[4] = param5;
    entry.rgParam[5] = param6;
Gus Grubba's avatar
Gus Grubba committed
3316
    entry.rgParam[6] = static_cast<double>(param7);
3317
3318
3319
3320
3321
3322
3323
3324
3325

    _mavCommandQueue.append(entry);

    if (_mavCommandQueue.count() == 1) {
        _mavCommandRetryCount = 0;
        _sendMavCommandAgain();
    }
}

3326
void Vehicle::_sendMavCommandAgain()
3327
{
3328
3329
3330
3331
3332
3333
    if(!_mavCommandQueue.size()) {
        qWarning() << "Command resend with no commands in queue";
        _mavCommandAckTimer.stop();
        return;
    }

3334
3335
3336
    MavCommandQueueEntry_t& queuedCommand = _mavCommandQueue[0];

    if (_mavCommandRetryCount++ > _mavCommandMaxRetryCount) {
3337
        if (queuedCommand.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) {
Don Gagne's avatar
   
Don Gagne committed
3338
3339
            qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES.";
            _handleUnsupportedRequestAutopilotCapabilities();
3340
3341
        }

3342
        if (queuedCommand.command == MAV_CMD_REQUEST_PROTOCOL_VERSION) {
Don Gagne's avatar
   
Don Gagne committed
3343
3344
            qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_PROTOCOL_VERSION.";
            _handleUnsupportedRequestProtocolVersion();
3345
3346
        }

3347
3348
        emit mavCommandResult(_id, queuedCommand.component, queuedCommand.command, MAV_RESULT_FAILED, true /* noResponsefromVehicle */);
        if (queuedCommand.showError) {
3349
            qgcApp()->showMessage(tr("Vehicle did not respond to command: %1").arg(_toolbox->missionCommandTree()->friendlyName(queuedCommand.command)));
3350
3351
3352
3353
3354
3355
        }
        _mavCommandQueue.removeFirst();
        _sendNextQueuedMavCommand();
        return;
    }

3356
    if (_mavCommandRetryCount > 1) {
Don Gagne's avatar
   
Don Gagne committed
3357
3358
3359
3360
        if (!px4Firmware() && queuedCommand.command == MAV_CMD_START_RX_PAIR) {
            // The implementation of this command comes from the IO layer and is shared across stacks. So for other firmwares
            // we aren't really sure whether they are correct or not.
            return;
3361
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
3362
        qCDebug(VehicleLog) << "Vehicle::_sendMavCommandAgain retrying command:_mavCommandRetryCount" << queuedCommand.command << _mavCommandRetryCount;
3363
3364
    }

3365
3366
    _mavCommandAckTimer.start();

DonLakeFlyer's avatar
   
DonLakeFlyer committed
3367
3368
    qCDebug(VehicleLog) << "_sendMavCommandAgain sending" << queuedCommand.command;

Don Gagne's avatar
Don Gagne committed
3369
    mavlink_message_t       msg;
3370
3371
3372
3373
3374
3375
3376
3377
3378
3379
3380
3381
3382
3383
3384
3385
3386
3387
3388
3389
3390
3391
3392
3393
3394
3395
3396
3397
3398
3399
3400
3401
3402
3403
3404
3405
3406
3407
3408
3409
3410
    if (queuedCommand.commandInt) {
        mavlink_command_int_t  cmd;

        memset(&cmd, 0, sizeof(cmd));
        cmd.target_system =     _id;
        cmd.target_component =  queuedCommand.component;
        cmd.command =           queuedCommand.command;
        cmd.frame =             queuedCommand.frame;
        cmd.param1 =            queuedCommand.rgParam[0];
        cmd.param2 =            queuedCommand.rgParam[1];
        cmd.param3 =            queuedCommand.rgParam[2];
        cmd.param4 =            queuedCommand.rgParam[3];
        cmd.x =                 queuedCommand.rgParam[4] * qPow(10.0, 7.0);
        cmd.y =                 queuedCommand.rgParam[5] * qPow(10.0, 7.0);
        cmd.z =                 queuedCommand.rgParam[6];
        mavlink_msg_command_int_encode_chan(_mavlink->getSystemId(),
                                            _mavlink->getComponentId(),
                                            priorityLink()->mavlinkChannel(),
                                            &msg,
                                            &cmd);
    } else {
        mavlink_command_long_t  cmd;

        memset(&cmd, 0, sizeof(cmd));
        cmd.target_system =     _id;
        cmd.target_component =  queuedCommand.component;
        cmd.command =           queuedCommand.command;
        cmd.confirmation =      0;
        cmd.param1 =            queuedCommand.rgParam[0];
        cmd.param2 =            queuedCommand.rgParam[1];
        cmd.param3 =            queuedCommand.rgParam[2];
        cmd.param4 =            queuedCommand.rgParam[3];
        cmd.param5 =            queuedCommand.rgParam[4];
        cmd.param6 =            queuedCommand.rgParam[5];
        cmd.param7 =            queuedCommand.rgParam[6];
        mavlink_msg_command_long_encode_chan(_mavlink->getSystemId(),
                                             _mavlink->getComponentId(),
                                             priorityLink()->mavlinkChannel(),
                                             &msg,
                                             &cmd);
    }
Don Gagne's avatar
Don Gagne committed
3411

3412
    sendMessageOnLink(priorityLink(), msg);
Don Gagne's avatar
Don Gagne committed
3413
}
3414

3415
void Vehicle::_sendNextQueuedMavCommand()
3416
3417
3418
3419
3420
3421
3422
{
    if (_mavCommandQueue.count()) {
        _mavCommandRetryCount = 0;
        _sendMavCommandAgain();
    }
}

3423
void Vehicle::_handleUnsupportedRequestProtocolVersion()
Don Gagne's avatar
   
Don Gagne committed
3424
3425
3426
3427
{
    // We end up here if either the vehicle does not support the MAV_CMD_REQUEST_PROTOCOL_VERSION command or if
    // we never received an Ack back for the command.

DonLakeFlyer's avatar
   
DonLakeFlyer committed
3428
    // _mavlinkProtocolRequestMaxProtoVersion stays at 0 to indicate unknown
Don Gagne's avatar
   
Don Gagne committed
3429
    _mavlinkProtocolRequestComplete = true;
DonLakeFlyer's avatar
   
DonLakeFlyer committed
3430
    _setMaxProtoVersionFromBothSources();
Don Gagne's avatar
   
Don Gagne committed
3431
3432
3433
3434
3435

    // Determining protocol version is one of the triggers to possibly start downloading the plan
    _startPlanRequest();
}

3436
void Vehicle::_protocolVersionTimeOut()
Don Gagne's avatar
   
Don Gagne committed
3437
3438
{
    // The PROTOCOL_VERSION message didn't make it through the pipe from Vehicle->QGC.
Don Gagne's avatar
   
Don Gagne committed
3439
    // This means although the vehicle may support mavlink 2, the pipe does not.
Don Gagne's avatar
   
Don Gagne committed
3440
    qCDebug(VehicleLog) << QStringLiteral("Setting _maxProtoVersion to 100 due to timeout on receiving PROTOCOL_VERSION message.");
DonLakeFlyer's avatar
   
DonLakeFlyer committed
3441
    _mavlinkProtocolRequestMaxProtoVersion = 100;
Don Gagne's avatar
   
Don Gagne committed
3442
    _mavlinkProtocolRequestComplete = true;
DonLakeFlyer's avatar
   
DonLakeFlyer committed
3443
    _setMaxProtoVersionFromBothSources();
Don Gagne's avatar
   
Don Gagne committed
3444
3445
3446
    _startPlanRequest();
}

3447
void Vehicle::_handleUnsupportedRequestAutopilotCapabilities()
Don Gagne's avatar
   
Don Gagne committed
3448
3449
3450
3451
3452
3453
3454
3455
3456
{
    // We end up here if either the vehicle does not support the MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES command or if
    // we never received an Ack back for the command.

    _setCapabilities(0);

    // Determining vehicle capabilities is one of the triggers to possibly start downloading the plan
    _startPlanRequest();
}
3457

DonLakeFlyer's avatar
DonLakeFlyer committed
3458
3459
3460
3461
3462
3463
3464
void Vehicle::_handleCommandAck(mavlink_message_t& message)
{
    bool showError = false;

    mavlink_command_ack_t ack;
    mavlink_msg_command_ack_decode(&message, &ack);

DonLakeFlyer's avatar
   
DonLakeFlyer committed
3465
3466
    qCDebug(VehicleLog) << QStringLiteral("_handleCommandAck command(%1) result(%2)").arg(ack.command).arg(ack.result);

DonLakeFlyer's avatar
DonLakeFlyer committed
3467
    if (ack.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES && ack.result != MAV_RESULT_ACCEPTED) {
Don Gagne's avatar
   
Don Gagne committed
3468
3469
        qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error(%1). Setting no capabilities.").arg(ack.result);
        _handleUnsupportedRequestAutopilotCapabilities();
DonLakeFlyer's avatar
DonLakeFlyer committed
3470
3471
    }

Don Gagne's avatar
   
Don Gagne committed
3472
3473
3474
3475
3476
3477
3478
    if (ack.command == MAV_CMD_REQUEST_PROTOCOL_VERSION) {
        if (ack.result == MAV_RESULT_ACCEPTED) {
            // The vehicle should be sending a PROTOCOL_VERSION message in a mavlink 2 packet. This may or may not make it through the pipe.
            // So we wait for it to come and timeout if it doesn't.
            if (!_mavlinkProtocolRequestComplete) {
                QTimer::singleShot(1000, this, &Vehicle::_protocolVersionTimeOut);
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
3479
        } else {
Don Gagne's avatar
   
Don Gagne committed
3480
3481
            qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_PROTOCOL_VERSION with error(%1).").arg(ack.result);
            _handleUnsupportedRequestProtocolVersion();
DonLakeFlyer's avatar
DonLakeFlyer committed
3482
3483
3484
        }
    }

3485
3486
3487
3488
3489
3490
3491
3492
3493
3494
3495
3496
3497
3498
    if (ack.command == MAV_CMD_DO_SET_ROI_LOCATION) {
        if (ack.result == MAV_RESULT_ACCEPTED) {
            _isROIEnabled = true;
            emit isROIEnabledChanged();
        }
    }

    if (ack.command == MAV_CMD_DO_SET_ROI_NONE) {
        if (ack.result == MAV_RESULT_ACCEPTED) {
            _isROIEnabled = false;
            emit isROIEnabledChanged();
        }
    }

Gus Grubba's avatar
Gus Grubba committed
3499
#if !defined(NO_ARDUPILOT_DIALECT)
Don Gagne's avatar
   
Don Gagne committed
3500
3501
3502
    if (ack.command == MAV_CMD_FLASH_BOOTLOADER && ack.result == MAV_RESULT_ACCEPTED) {
        qgcApp()->showMessage(tr("Bootloader flash succeeded"));
    }
Gus Grubba's avatar
Gus Grubba committed
3503
#endif
Don Gagne's avatar
   
Don Gagne committed
3504

DonLakeFlyer's avatar
DonLakeFlyer committed
3505
3506
3507
3508
    if (_mavCommandQueue.count() && ack.command == _mavCommandQueue[0].command) {
        _mavCommandAckTimer.stop();
        showError = _mavCommandQueue[0].showError;
        _mavCommandQueue.removeFirst();
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
3509
        _sendNextQueuedMavCommand();
DonLakeFlyer's avatar
DonLakeFlyer committed
3510
3511
3512
3513
3514
    }

    emit mavCommandResult(_id, message.compid, ack.command, ack.result, false /* noResponsefromVehicle */);

    if (showError) {
Gus Grubba's avatar
Gus Grubba committed
3515
        QString commandName = _toolbox->missionCommandTree()->friendlyName(static_cast<MAV_CMD>(ack.command));
DonLakeFlyer's avatar
DonLakeFlyer committed
3516
3517
3518
3519
3520
3521
3522
3523
3524
3525
3526
3527
3528
3529
3530
3531
3532
3533
3534
3535
        switch (ack.result) {
        case MAV_RESULT_TEMPORARILY_REJECTED:
            qgcApp()->showMessage(tr("%1 command temporarily rejected").arg(commandName));
            break;
        case MAV_RESULT_DENIED:
            qgcApp()->showMessage(tr("%1 command denied").arg(commandName));
            break;
        case MAV_RESULT_UNSUPPORTED:
            qgcApp()->showMessage(tr("%1 command not supported").arg(commandName));
            break;
        case MAV_RESULT_FAILED:
            qgcApp()->showMessage(tr("%1 command failed").arg(commandName));
            break;
        default:
            // Do nothing
            break;
        }
    }
}

Don Gagne's avatar
Don Gagne committed
3536
3537
3538
3539
3540
3541
3542
3543
3544
void Vehicle::setPrearmError(const QString& prearmError)
{
    _prearmError = prearmError;
    emit prearmErrorChanged(_prearmError);
    if (!_prearmError.isEmpty()) {
        _prearmErrorTimer.start();
    }
}

3545
void Vehicle::_prearmErrorTimeout()
Don Gagne's avatar
Don Gagne committed
3546
3547
3548
{
    setPrearmError(QString());
}
3549

3550
void Vehicle::setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType)
Don Gagne's avatar
Don Gagne committed
3551
3552
3553
3554
{
    _firmwareMajorVersion = majorVersion;
    _firmwareMinorVersion = minorVersion;
    _firmwarePatchVersion = patchVersion;
3555
    _firmwareVersionType = versionType;
3556
3557
3558
3559
3560
3561
3562
3563
3564
    emit firmwareVersionChanged();
}

void Vehicle::setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion)
{
    _firmwareCustomMajorVersion = majorVersion;
    _firmwareCustomMinorVersion = minorVersion;
    _firmwareCustomPatchVersion = patchVersion;
    emit firmwareCustomVersionChanged();
3565
3566
}

3567
QString Vehicle::firmwareVersionTypeString() const
3568
3569
3570
3571
3572
3573
3574
3575
3576
3577
3578
3579
3580
3581
{
    switch (_firmwareVersionType) {
    case FIRMWARE_VERSION_TYPE_DEV:
        return QStringLiteral("dev");
    case FIRMWARE_VERSION_TYPE_ALPHA:
        return QStringLiteral("alpha");
    case FIRMWARE_VERSION_TYPE_BETA:
        return QStringLiteral("beta");
    case FIRMWARE_VERSION_TYPE_RC:
        return QStringLiteral("rc");
    case FIRMWARE_VERSION_TYPE_OFFICIAL:
    default:
        return QStringLiteral("");
    }
Don Gagne's avatar
Don Gagne committed
3582
3583
}

dogmaphobic's avatar
dogmaphobic committed
3584
3585
void Vehicle::rebootVehicle()
{
3586
    _autoDisconnect = true;
DonLakeFlyer's avatar
   
DonLakeFlyer committed
3587
3588
3589
3590
3591
3592
3593
3594
3595
3596
3597
3598
3599
3600
3601
3602
3603

    mavlink_message_t       msg;
    mavlink_command_long_t  cmd;

    memset(&cmd, 0, sizeof(cmd));
    cmd.target_system =     _id;
    cmd.target_component =  _defaultComponentId;
    cmd.command =           MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN;
    cmd.confirmation =      0;
    cmd.param1 =            1;
    cmd.param2 = cmd.param3 = cmd.param4 = cmd.param5 = cmd.param6 = cmd.param7 = 0;
    mavlink_msg_command_long_encode_chan(_mavlink->getSystemId(),
                                         _mavlink->getComponentId(),
                                         priorityLink()->mavlinkChannel(),
                                         &msg,
                                         &cmd);
    sendMessageOnLink(priorityLink(), msg);
Don Gagne's avatar
Don Gagne committed
3604
3605
}

Don Gagne's avatar
Don Gagne committed
3606
3607
3608
3609
3610
3611
3612
3613
void Vehicle::setSoloFirmware(bool soloFirmware)
{
    if (soloFirmware != _soloFirmware) {
        _soloFirmware = soloFirmware;
        emit soloFirmwareChanged(soloFirmware);
    }
}

Don Gagne's avatar
   
Don Gagne committed
3614
void Vehicle::motorTest(int motor, int percent, int timeoutSecs)
Don Gagne's avatar
Don Gagne committed
3615
{
Don Gagne's avatar
   
Don Gagne committed
3616
    sendMavCommand(_defaultComponentId, MAV_CMD_DO_MOTOR_TEST, true, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, timeoutSecs, 0, MOTOR_TEST_ORDER_BOARD);
Don Gagne's avatar
Don Gagne committed
3617
3618
}

3619
QString Vehicle::brandImageIndoor() const
3620
{
3621
3622
3623
    return _firmwarePlugin->brandImageIndoor(this);
}

3624
QString Vehicle::brandImageOutdoor() const
3625
3626
{
    return _firmwarePlugin->brandImageOutdoor(this);
3627
3628
}

3629
QStringList Vehicle::unhealthySensors() const
3630
3631
3632
3633
3634
3635
3636
3637
3638
3639
3640
3641
3642
3643
3644
3645
3646
3647
3648
3649
3650
3651
3652
3653
3654
3655
3656
3657
3658
3659
3660
3661
3662
3663
{
    QStringList sensorList;

    struct sensorInfo_s {
        uint32_t    bit;
        const char* sensorName;
    };

    static const sensorInfo_s rgSensorInfo[] = {
        { MAV_SYS_STATUS_SENSOR_3D_GYRO,                "Gyro" },
        { MAV_SYS_STATUS_SENSOR_3D_ACCEL,               "Accelerometer" },
        { MAV_SYS_STATUS_SENSOR_3D_MAG,                 "Magnetometer" },
        { MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE,      "Absolute pressure" },
        { MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,  "Differential pressure" },
        { MAV_SYS_STATUS_SENSOR_GPS,                    "GPS" },
        { MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW,           "Optical flow" },
        { MAV_SYS_STATUS_SENSOR_VISION_POSITION,        "Computer vision position" },
        { MAV_SYS_STATUS_SENSOR_LASER_POSITION,         "Laser based position" },
        { MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH,  "External ground truth" },
        { MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL,   "Angular rate control" },
        { MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION, "Attitude stabilization" },
        { MAV_SYS_STATUS_SENSOR_YAW_POSITION,           "Yaw position" },
        { MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL,     "Z/altitude control" },
        { MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL,    "X/Y position control" },
        { MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS,          "Motor outputs / control" },
        { MAV_SYS_STATUS_SENSOR_RC_RECEIVER,            "RC receiver" },
        { MAV_SYS_STATUS_SENSOR_3D_GYRO2,               "Gyro 2" },
        { MAV_SYS_STATUS_SENSOR_3D_ACCEL2,              "Accelerometer 2" },
        { MAV_SYS_STATUS_SENSOR_3D_MAG2,                "Magnetometer 2" },
        { MAV_SYS_STATUS_GEOFENCE,                      "GeoFence" },
        { MAV_SYS_STATUS_AHRS,                          "AHRS" },
        { MAV_SYS_STATUS_TERRAIN,                       "Terrain" },
        { MAV_SYS_STATUS_REVERSE_MOTOR,                 "Motors reversed" },
        { MAV_SYS_STATUS_LOGGING,                       "Logging" },
3664
        { MAV_SYS_STATUS_SENSOR_BATTERY,                "Battery" },
3665
3666
3667
3668
3669
3670
3671
3672
3673
3674
3675
3676
    };

    for (size_t i=0; i<sizeof(rgSensorInfo)/sizeof(sensorInfo_s); i++) {
        const sensorInfo_s* pSensorInfo = &rgSensorInfo[i];
        if ((_onboardControlSensorsEnabled & pSensorInfo->bit) && !(_onboardControlSensorsHealth & pSensorInfo->bit)) {
            sensorList << pSensorInfo->sensorName;
        }
    }

    return sensorList;
}

3677
3678
3679
3680
3681
3682
3683
3684
void Vehicle::setOfflineEditingDefaultComponentId(int defaultComponentId)
{
    if (_offlineEditingVehicle) {
        _defaultComponentId = defaultComponentId;
    } else {
        qWarning() << "Call to Vehicle::setOfflineEditingDefaultComponentId on vehicle which is not offline";
    }
}
3685

3686
void Vehicle::triggerCamera()
Don Gagne's avatar
Don Gagne committed
3687
{
DonLakeFlyer's avatar
DonLakeFlyer committed
3688
    sendMavCommand(_defaultComponentId,
Don Gagne's avatar
Don Gagne committed
3689
3690
3691
                   MAV_CMD_DO_DIGICAM_CONTROL,
                   true,                            // show errors
                   0.0, 0.0, 0.0, 0.0,              // param 1-4 unused
3692
3693
3694
                   1.0,                             // trigger camera
                   0.0,                             // param 6 unused
                   1.0);                            // test shot flag
Don Gagne's avatar
Don Gagne committed
3695
3696
}

Don Gagne's avatar
Don Gagne committed
3697
3698
3699
void Vehicle::setVtolInFwdFlight(bool vtolInFwdFlight)
{
    if (_vtolInFwdFlight != vtolInFwdFlight) {
DonLakeFlyer's avatar
DonLakeFlyer committed
3700
3701
3702
3703
3704
        sendMavCommand(_defaultComponentId,
                       MAV_CMD_DO_VTOL_TRANSITION,
                       true,                                                    // show errors
                       vtolInFwdFlight ? MAV_VTOL_STATE_FW : MAV_VTOL_STATE_MC, // transition state
                       0, 0, 0, 0, 0, 0);                                       // param 2-7 unused
Don Gagne's avatar
Don Gagne committed
3705
3706
3707
    }
}

3708
3709
const char* VehicleGPSFactGroup::_latFactName =                 "lat";
const char* VehicleGPSFactGroup::_lonFactName =                 "lon";
Matej Frančeškin's avatar
Matej Frančeškin committed
3710
const char* VehicleGPSFactGroup::_mgrsFactName =                "mgrs";
Don Gagne's avatar
Don Gagne committed
3711
3712
3713
3714
3715
const char* VehicleGPSFactGroup::_hdopFactName =                "hdop";
const char* VehicleGPSFactGroup::_vdopFactName =                "vdop";
const char* VehicleGPSFactGroup::_courseOverGroundFactName =    "courseOverGround";
const char* VehicleGPSFactGroup::_countFactName =               "count";
const char* VehicleGPSFactGroup::_lockFactName =                "lock";
Don Gagne's avatar
Don Gagne committed
3716
3717
3718

VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent)
    : FactGroup(1000, ":/json/Vehicle/GPSFact.json", parent)
3719
3720
    , _latFact              (0, _latFactName,               FactMetaData::valueTypeDouble)
    , _lonFact              (0, _lonFactName,               FactMetaData::valueTypeDouble)
Matej Frančeškin's avatar
Matej Frančeškin committed
3721
    , _mgrsFact             (0, _mgrsFactName,              FactMetaData::valueTypeString)
Don Gagne's avatar
Don Gagne committed
3722
3723
3724
3725
3726
3727
    , _hdopFact             (0, _hdopFactName,              FactMetaData::valueTypeDouble)
    , _vdopFact             (0, _vdopFactName,              FactMetaData::valueTypeDouble)
    , _courseOverGroundFact (0, _courseOverGroundFactName,  FactMetaData::valueTypeDouble)
    , _countFact            (0, _countFactName,             FactMetaData::valueTypeInt32)
    , _lockFact             (0, _lockFactName,              FactMetaData::valueTypeInt32)
{
3728
3729
    _addFact(&_latFact,                 _latFactName);
    _addFact(&_lonFact,                 _lonFactName);
Matej Frančeškin's avatar
Matej Frančeškin committed
3730
    _addFact(&_mgrsFact,                _mgrsFactName);
Don Gagne's avatar
Don Gagne committed
3731
3732
3733
3734
3735
    _addFact(&_hdopFact,                _hdopFactName);
    _addFact(&_vdopFact,                _vdopFactName);
    _addFact(&_courseOverGroundFact,    _courseOverGroundFactName);
    _addFact(&_lockFact,                _lockFactName);
    _addFact(&_countFact,               _countFactName);
3736

3737
3738
    _latFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _lonFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
Matej Frančeškin's avatar
Matej Frančeškin committed
3739
    _mgrsFact.setRawValue("");
3740
3741
3742
    _hdopFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _vdopFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _courseOverGroundFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
Don Gagne's avatar
Don Gagne committed
3743
3744
}

3745
void Vehicle::startMavlinkLog()
3746
{
3747
    sendMavCommand(_defaultComponentId, MAV_CMD_LOGGING_START, false /* showError */);
3748
3749
}

3750
void Vehicle::stopMavlinkLog()
3751
{
3752
    sendMavCommand(_defaultComponentId, MAV_CMD_LOGGING_STOP, false /* showError */);
3753
3754
}

3755
void Vehicle::_ackMavlinkLogData(uint16_t sequence)
3756
3757
3758
{
    mavlink_message_t msg;
    mavlink_logging_ack_t ack;
Don Gagne's avatar
Don Gagne committed
3759
    memset(&ack, 0, sizeof(ack));
3760
    ack.sequence = sequence;
3761
    ack.target_component = _defaultComponentId;
3762
3763
    ack.target_system = id();
    mavlink_msg_logging_ack_encode_chan(
DonLakeFlyer's avatar
DonLakeFlyer committed
3764
3765
3766
3767
3768
                _mavlink->getSystemId(),
                _mavlink->getComponentId(),
                priorityLink()->mavlinkChannel(),
                &msg,
                &ack);
3769
3770
3771
    sendMessageOnLink(priorityLink(), msg);
}

3772
void Vehicle::_handleMavlinkLoggingData(mavlink_message_t& message)
3773
3774
3775
{
    mavlink_logging_data_t log;
    mavlink_msg_logging_data_decode(&message, &log);
Gus Grubba's avatar
Gus Grubba committed
3776
    emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence,
DonLakeFlyer's avatar
DonLakeFlyer committed
3777
                        log.first_message_offset, QByteArray((const char*)log.data, log.length), false);
3778
3779
}

3780
void Vehicle::_handleMavlinkLoggingDataAcked(mavlink_message_t& message)
3781
{
3782
3783
    mavlink_logging_data_acked_t log;
    mavlink_msg_logging_data_acked_decode(&message, &log);
3784
    _ackMavlinkLogData(log.sequence);
Gus Grubba's avatar
Gus Grubba committed
3785
    emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence,
DonLakeFlyer's avatar
DonLakeFlyer committed
3786
                        log.first_message_offset, QByteArray((const char*)log.data, log.length), true);
3787
3788
}

3789
3790
3791
3792
3793
3794
void Vehicle::setFirmwarePluginInstanceData(QObject* firmwarePluginInstanceData)
{
    firmwarePluginInstanceData->setParent(this);
    _firmwarePluginInstanceData = firmwarePluginInstanceData;
}

3795
QString Vehicle::missionFlightMode() const
3796
3797
3798
3799
{
    return _firmwarePlugin->missionFlightMode();
}

3800
QString Vehicle::pauseFlightMode() const
DonLakeFlyer's avatar
DonLakeFlyer committed
3801
3802
3803
3804
{
    return _firmwarePlugin->pauseFlightMode();
}

3805
QString Vehicle::rtlFlightMode() const
3806
3807
3808
3809
{
    return _firmwarePlugin->rtlFlightMode();
}

3810
QString Vehicle::smartRTLFlightMode() const
DonLakeFlyer's avatar
   
DonLakeFlyer committed
3811
3812
3813
3814
{
    return _firmwarePlugin->smartRTLFlightMode();
}

3815
bool Vehicle::supportsSmartRTL() const
DonLakeFlyer's avatar
   
DonLakeFlyer committed
3816
3817
3818
3819
{
    return _firmwarePlugin->supportsSmartRTL();
}

3820
QString Vehicle::landFlightMode() const
DonLakeFlyer's avatar
DonLakeFlyer committed
3821
3822
3823
3824
{
    return _firmwarePlugin->landFlightMode();
}

3825
QString Vehicle::takeControlFlightMode() const
3826
3827
3828
3829
{
    return _firmwarePlugin->takeControlFlightMode();
}

3830
QString Vehicle::followFlightMode() const
Don Gagne's avatar
   
Don Gagne committed
3831
3832
3833
3834
{
    return _firmwarePlugin->followFlightMode();
}

3835
3836
3837
3838
3839
3840
3841
3842
3843
3844
3845
3846
3847
3848
3849
3850
3851
3852
3853
3854
3855
3856
3857
3858
QString Vehicle::vehicleImageOpaque() const
{
    if(_firmwarePlugin)
        return _firmwarePlugin->vehicleImageOpaque(this);
    else
        return QString();
}

QString Vehicle::vehicleImageOutline() const
{
    if(_firmwarePlugin)
        return _firmwarePlugin->vehicleImageOutline(this);
    else
        return QString();
}

QString Vehicle::vehicleImageCompass() const
{
    if(_firmwarePlugin)
        return _firmwarePlugin->vehicleImageCompass(this);
    else
        return QString();
}

3859
const QVariantList& Vehicle::toolBarIndicators()
3860
3861
3862
3863
3864
3865
3866
3867
{
    if(_firmwarePlugin) {
        return _firmwarePlugin->toolBarIndicators(this);
    }
    static QVariantList emptyList;
    return emptyList;
}

3868
const QVariantList& Vehicle::staticCameraList() const
3869
3870
3871
3872
3873
3874
3875
3876
{
    if (_firmwarePlugin) {
        return _firmwarePlugin->cameraList(this);
    }
    static QVariantList emptyList;
    return emptyList;
}

3877
bool Vehicle::vehicleYawsToNextWaypointInMission() const
3878
3879
3880
{
    return _firmwarePlugin->vehicleYawsToNextWaypointInMission(this);
}
3881

3882
void Vehicle::_setupAutoDisarmSignalling()
3883
3884
3885
3886
3887
3888
3889
3890
3891
3892
{
    QString param = _firmwarePlugin->autoDisarmParameter(this);

    if (!param.isEmpty() && _parameterManager->parameterExists(FactSystem::defaultComponentId, param)) {
        Fact* fact = _parameterManager->getParameter(FactSystem::defaultComponentId,param);
        connect(fact, &Fact::rawValueChanged, this, &Vehicle::autoDisarmChanged);
        emit autoDisarmChanged();
    }
}

3893
bool Vehicle::autoDisarm()
3894
3895
3896
3897
3898
3899
3900
3901
3902
3903
3904
{
    QString param = _firmwarePlugin->autoDisarmParameter(this);

    if (!param.isEmpty() && _parameterManager->parameterExists(FactSystem::defaultComponentId, param)) {
        Fact* fact = _parameterManager->getParameter(FactSystem::defaultComponentId,param);
        return fact->rawValue().toDouble() > 0;
    }

    return false;
}

3905
3906
void Vehicle::_handleADSBVehicle(const mavlink_message_t& message)
{
DonLakeFlyer's avatar
   
DonLakeFlyer committed
3907
    mavlink_adsb_vehicle_t adsbVehicleMsg;
Don Gagne's avatar
Don Gagne committed
3908
    static const int maxTimeSinceLastSeen = 15;
3909

DonLakeFlyer's avatar
   
DonLakeFlyer committed
3910
3911
3912
3913
3914
3915
3916
    mavlink_msg_adsb_vehicle_decode(&message, &adsbVehicleMsg);
    if (adsbVehicleMsg.flags | ADSB_FLAGS_VALID_COORDS && adsbVehicleMsg.tslc <= maxTimeSinceLastSeen) {
        ADSBVehicle::VehicleInfo_t vehicleInfo;

        vehicleInfo.availableFlags = 0;

        vehicleInfo.location.setLatitude(adsbVehicleMsg.lat / 1e7);
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
3917
3918
        vehicleInfo.location.setLongitude(adsbVehicleMsg.lon / 1e7);
        vehicleInfo.availableFlags |= ADSBVehicle::LocationAvailable;
DonLakeFlyer's avatar
   
DonLakeFlyer committed
3919
3920
3921
3922
3923
3924
3925
3926
3927
3928
3929
3930

        vehicleInfo.callsign = adsbVehicleMsg.callsign;
        vehicleInfo.availableFlags |= ADSBVehicle::CallsignAvailable;

        if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_ALTITUDE) {
            vehicleInfo.altitude = (double)adsbVehicleMsg.altitude / 1e3;
            vehicleInfo.availableFlags |= ADSBVehicle::AltitudeAvailable;
        }

        if (adsbVehicleMsg.flags & ADSB_FLAGS_VALID_HEADING) {
            vehicleInfo.heading = (double)adsbVehicleMsg.heading / 100.0;
            vehicleInfo.availableFlags |= ADSBVehicle::HeadingAvailable;
3931
        }
DonLakeFlyer's avatar
   
DonLakeFlyer committed
3932
3933

        _toolbox->adsbVehicleManager()->adsbVehicleUpdate(vehicleInfo);
3934
3935
3936
    }
}

3937
void Vehicle::_updateDistanceHeadingToHome()
3938
3939
3940
{
    if (coordinate().isValid() && homePosition().isValid()) {
        _distanceToHomeFact.setRawValue(coordinate().distanceTo(homePosition()));
Don Gagne's avatar
   
Don Gagne committed
3941
3942
3943
3944
3945
        if (_distanceToHomeFact.rawValue().toDouble() > 1.0) {
            _headingToHomeFact.setRawValue(coordinate().azimuthTo(homePosition()));
        } else {
            _headingToHomeFact.setRawValue(qQNaN());
        }
3946
3947
    } else {
        _distanceToHomeFact.setRawValue(qQNaN());
Don Gagne's avatar
   
Don Gagne committed
3948
        _headingToHomeFact.setRawValue(qQNaN());
3949
3950
3951
    }
}

3952
void Vehicle::_updateHeadingToNextWP()
3953
3954
3955
3956
3957
3958
3959
3960
3961
3962
3963
3964
3965
3966
3967
3968
{
    const int _currentIndex = _missionManager->currentIndex();
    MissionItem _currentItem;
    QList<MissionItem*> llist = _missionManager->missionItems();

    if(llist.size()>_currentIndex && _currentIndex!=-1
            && llist[_currentIndex]->coordinate().longitude()!=0.0
            && coordinate().distanceTo(llist[_currentIndex]->coordinate())>5.0 ){

        _headingToNextWPFact.setRawValue(coordinate().azimuthTo(llist[_currentIndex]->coordinate()));
    }
    else{
        _headingToNextWPFact.setRawValue(qQNaN());
    }
}

3969
void Vehicle::_updateDistanceToGCS()
Don Gagne's avatar
   
Don Gagne committed
3970
3971
3972
3973
3974
3975
3976
3977
3978
{
    QGeoCoordinate gcsPosition = _toolbox->qgcPositionManager()->gcsPosition();
    if (coordinate().isValid() && gcsPosition.isValid()) {
        _distanceToGCSFact.setRawValue(coordinate().distanceTo(gcsPosition));
    } else {
        _distanceToGCSFact.setRawValue(qQNaN());
    }
}

3979
void Vehicle::_updateHobbsMeter()
3980
3981
3982
3983
{
    _hobbsFact.setRawValue(hobbsMeter());
}

3984
void Vehicle::forceInitialPlanRequestComplete()
Don Gagne's avatar
Don Gagne committed
3985
3986
3987
3988
3989
3990
3991
3992
3993
3994
{
    _initialPlanRequestComplete = true;
    emit initialPlanRequestCompleteChanged(true);
}

void Vehicle::sendPlan(QString planFile)
{
    PlanMasterController::sendPlanToVehicle(this, planFile);
}

3995
3996
3997
3998
3999
4000
QString Vehicle::hobbsMeter()
{
    static const char* HOOBS_HI = "LND_FLIGHT_T_HI";
    static const char* HOOBS_LO = "LND_FLIGHT_T_LO";
    //-- TODO: Does this exist on non PX4?
    if (_parameterManager->parameterExists(FactSystem::defaultComponentId, HOOBS_HI) &&
DonLakeFlyer's avatar
DonLakeFlyer committed
4001
            _parameterManager->parameterExists(FactSystem::defaultComponentId, HOOBS_LO)) {
4002
4003
        Fact* factHi = _parameterManager->getParameter(FactSystem::defaultComponentId, HOOBS_HI);
        Fact* factLo = _parameterManager->getParameter(FactSystem::defaultComponentId, HOOBS_LO);
4004
        uint64_t hobbsTimeSeconds = ((uint64_t)factHi->rawValue().toUInt() << 32 | (uint64_t)factLo->rawValue().toUInt()) / 1000000;
4005
4006
4007
4008
4009
        int hours   = hobbsTimeSeconds / 3600;
        int minutes = (hobbsTimeSeconds % 3600) / 60;
        int seconds = hobbsTimeSeconds % 60;
        QString timeStr;
        timeStr.sprintf("%04d:%02d:%02d", hours, minutes, seconds);
4010
        qCDebug(VehicleLog) << "Hobbs Meter:" << timeStr << "(" << factHi->rawValue().toUInt() << factLo->rawValue().toUInt() << ")";
4011
4012
4013
4014
        return timeStr;
    }
    return QString("0000:00:00");
}
Don Gagne's avatar
Don Gagne committed
4015

4016
4017
4018
4019
4020
4021
4022
4023
4024
void Vehicle::_vehicleParamLoaded(bool ready)
{
    //-- TODO: This seems silly but can you think of a better
    //   way to update this?
    if(ready) {
        emit hobbsMeterChanged();
    }
}

4025
void Vehicle::_updateHighLatencyLink(bool sendCommand)
Don Gagne's avatar
Don Gagne committed
4026
{
4027
4028
4029
4030
    if (!_priorityLink) {
        return;
    }

Don Gagne's avatar
Don Gagne committed
4031
4032
    if (_priorityLink->highLatency() != _highLatencyLink) {
        _highLatencyLink = _priorityLink->highLatency();
DonLakeFlyer's avatar
DonLakeFlyer committed
4033
        _mavCommandAckTimer.setInterval(_highLatencyLink ? _mavCommandAckTimeoutMSecsHighLatency : _mavCommandAckTimeoutMSecs);
Don Gagne's avatar
Don Gagne committed
4034
        emit highLatencyLinkChanged(_highLatencyLink);
4035
4036

        if (sendCommand) {
acfloria's avatar
acfloria committed
4037
4038
4039
4040
            sendMavCommand(defaultComponentId(),
                           MAV_CMD_CONTROL_HIGH_LATENCY,
                           true,
                           _highLatencyLink ? 1.0f : 0.0f); // request start/stop transmitting over high latency telemetry
4041
        }
Don Gagne's avatar
Don Gagne committed
4042
4043
4044
    }
}

DonLakeFlyer's avatar
   
DonLakeFlyer committed
4045
void Vehicle::_trafficUpdate(bool /*alert*/, QString /*traffic_id*/, QString /*vehicle_id*/, QGeoCoordinate /*location*/, float /*heading*/)
4046
{
DonLakeFlyer's avatar
   
DonLakeFlyer committed
4047
4048
4049
#if 0
    // This is ifdef'ed out for now since this code doesn't mesh with the recent ADSB manager changes. Also airmap isn't in any
    // released build. So not going to waste time trying to fix up unused code.
4050
    if (_trafficVehicleMap.contains(traffic_id)) {
Gus Grubba's avatar
Gus Grubba committed
4051
        _trafficVehicleMap[traffic_id]->update(alert, location, heading);
4052
    } else {
Gus Grubba's avatar
Gus Grubba committed
4053
        ADSBVehicle* vehicle = new ADSBVehicle(location, heading, alert, this);
4054
4055
4056
        _trafficVehicleMap[traffic_id] = vehicle;
        _adsbVehicles.append(vehicle);
    }
DonLakeFlyer's avatar
   
DonLakeFlyer committed
4057
#endif
4058
}
4059

Gus Grubba's avatar
Gus Grubba committed
4060
4061
4062
4063
4064
4065
4066
4067
4068
4069
4070
void Vehicle::_mavlinkMessageStatus(int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent)
{
    if(uasId == _id) {
        _mavlinkSentCount       = totalSent;
        _mavlinkReceivedCount   = totalReceived;
        _mavlinkLossCount       = totalLoss;
        _mavlinkLossPercent     = lossPercent;
        emit mavlinkStatusChanged();
    }
}

4071
4072
4073
4074
4075
4076
4077
4078
4079
4080
int  Vehicle::versionCompare(QString& compare)
{
    return _firmwarePlugin->versionCompare(this, compare);
}

int  Vehicle::versionCompare(int major, int minor, int patch)
{
    return _firmwarePlugin->versionCompare(this, major, minor, patch);
}

Don Gagne's avatar
   
Don Gagne committed
4081
void Vehicle::_handleMessageInterval(const mavlink_message_t& message)
Don Gagne's avatar
   
Don Gagne committed
4082
{
Don Gagne's avatar
   
Don Gagne committed
4083
4084
4085
4086
4087
4088
4089
4090
4091
    if (_pidTuningWaitingForRates) {
        mavlink_message_interval_t messageInterval;

        mavlink_msg_message_interval_decode(&message, &messageInterval);

        int msgId = messageInterval.message_id;
        if (_pidTuningMessages.contains(msgId)) {
            _pidTuningMessageRatesUsecs[msgId] = messageInterval.interval_us;
        }
Don Gagne's avatar
   
Don Gagne committed
4092

Don Gagne's avatar
   
Don Gagne committed
4093
4094
4095
4096
4097
4098
4099
4100
4101
4102
        if (_pidTuningMessageRatesUsecs.count() == _pidTuningMessages.count()) {
            // We have back all the rates we requested
            _pidTuningWaitingForRates = false;
            _pidTuningAdjustRates(true);
        }
    }
}

void Vehicle::setPIDTuningTelemetryMode(bool pidTuning)
{
Don Gagne's avatar
   
Don Gagne committed
4103
    if (pidTuning) {
Don Gagne's avatar
   
Don Gagne committed
4104
4105
4106
4107
4108
4109
4110
4111
4112
4113
4114
4115
4116
4117
4118
4119
4120
4121
4122
4123
4124
4125
4126
4127
4128
4129
4130
4131
4132
4133
4134
4135
        if (!_pidTuningTelemetryMode) {
            // First step is to get the current message rates before we adjust them
            _pidTuningTelemetryMode = true;
            _pidTuningWaitingForRates = true;
            _pidTuningMessageRatesUsecs.clear();
            for (int telemetry: _pidTuningMessages) {
                sendMavCommand(defaultComponentId(),
                               MAV_CMD_GET_MESSAGE_INTERVAL,
                               true,                        // show error
                               telemetry);
            }
        }
    } else {
        if (_pidTuningTelemetryMode) {
            _pidTuningTelemetryMode = false;
            if (_pidTuningWaitingForRates) {
                // We never finished waiting for previous rates
                _pidTuningWaitingForRates = false;
            } else {
                _pidTuningAdjustRates(false);
            }
        }
    }
}

void Vehicle::_pidTuningAdjustRates(bool setRatesForTuning)
{
    int requestedRate = (int)(1000000.0 / 30.0); // 30 Hz in usecs

    for (int telemetry: _pidTuningMessages) {

        if (requestedRate < _pidTuningMessageRatesUsecs[telemetry]) {
Don Gagne's avatar
   
Don Gagne committed
4136
4137
4138
4139
            sendMavCommand(defaultComponentId(),
                           MAV_CMD_SET_MESSAGE_INTERVAL,
                           true,                        // show error
                           telemetry,
Don Gagne's avatar
   
Don Gagne committed
4140
                           setRatesForTuning ? requestedRate : _pidTuningMessageRatesUsecs[telemetry]);
Don Gagne's avatar
   
Don Gagne committed
4141
4142
4143
        }
    }

Don Gagne's avatar
   
Don Gagne committed
4144
4145
    setLiveUpdates(setRatesForTuning);
    _setpointFactGroup.setLiveUpdates(setRatesForTuning);
Don Gagne's avatar
   
Don Gagne committed
4146
4147
}

4148
4149
void Vehicle::_initializeCsv()
{
Willian Galvani's avatar
Willian Galvani committed
4150
4151
4152
    if(!_toolbox->settingsManager()->appSettings()->saveCsvTelemetry()->rawValue().toBool()){
        return;
    }
4153
4154
4155
4156
4157
4158
4159
4160
4161
4162
4163
4164
4165
4166
4167
4168
4169
4170
4171
4172
4173
4174
4175
4176
    QString now = QDateTime::currentDateTime().toString("yyyy-MM-dd hh-mm-ss");
    QString fileName = QString("%1 vehicle%2.csv").arg(now).arg(_id);
    QDir saveDir(_toolbox->settingsManager()->appSettings()->telemetrySavePath());
    _csvLogFile.setFileName(saveDir.absoluteFilePath(fileName));

    if (!_csvLogFile.open(QIODevice::Append)) {
        qCWarning(VehicleLog) << "unable to open file for csv logging, Stopping csv logging!";
        return;
    }

    QTextStream stream(&_csvLogFile);
    QStringList allFactNames;
    allFactNames << factNames();
    for (const QString& groupName: factGroupNames()) {
        for(const QString& factName: getFactGroup(groupName)->factNames()){
            allFactNames << QString("%1.%2").arg(groupName, factName);
        }
    }
    qCDebug(VehicleLog) << "Facts logged to csv:" << allFactNames;
    stream << "Timestamp," << allFactNames.join(",") << "\n";
}

void Vehicle::_writeCsvLine()
{
Willian Galvani's avatar
Willian Galvani committed
4177
4178
4179
4180
4181
4182
4183
4184
4185
4186
    // Only save the logs after the the vehicle gets armed, unless "Save logs even if vehicle was not armed" is checked
    if(!_csvLogFile.isOpen() &&
           (_armed || _toolbox->settingsManager()->appSettings()->telemetrySaveNotArmed()->rawValue().toBool())){
        _initializeCsv();
    }

    if(!_csvLogFile.isOpen()){
        return;
    }

4187
4188
4189
4190
    QStringList allFactValues;
    QTextStream stream(&_csvLogFile);

    // Write timestamp to csv file
4191
    allFactValues << QDateTime::currentDateTime().toString(QStringLiteral("yyyy-MM-dd hh:mm:ss.zzz"));
4192
4193
4194
4195
4196
4197
4198
4199
4200
4201
4202
4203
4204
    // Write Vehicle's own facts
    for (const QString& factName : factNames()) {
        allFactValues << getFact(factName)->cookedValueString();
    }
    // write facts from Vehicle's FactGroups
    for (const QString& groupName: factGroupNames()) {
        for (const QString& factName : getFactGroup(groupName)->factNames()) {
            allFactValues << getFactGroup(groupName)->getFact(factName)->cookedValueString();
        }
    }

    stream << allFactValues.join(",") << "\n";
}
Don Gagne's avatar
   
Don Gagne committed
4205

Don Gagne's avatar
   
Don Gagne committed
4206
#if !defined(NO_ARDUPILOT_DIALECT)
4207
void Vehicle::flashBootloader()
Don Gagne's avatar
   
Don Gagne committed
4208
4209
4210
4211
4212
4213
4214
4215
4216
4217
{
    sendMavCommand(defaultComponentId(),
                   MAV_CMD_FLASH_BOOTLOADER,
                   true,        // show error
                   0, 0, 0, 0,  // param 1-4 not used
                   290876);     // magic number

}
#endif

4218
4219
void Vehicle::gimbalControlValue(double pitch, double yaw)
{
Gus Grubba's avatar
Gus Grubba committed
4220
    //qDebug() << "Gimbal:" << pitch << yaw;
4221
4222
4223
4224
4225
4226
4227
4228
4229
4230
4231
4232
    sendMavCommand(
        _defaultComponentId,
        MAV_CMD_DO_MOUNT_CONTROL,
        false,                               // show errors
        static_cast<float>(pitch),           // Pitch 0 - 90
        0,                                   // Roll (not used)
        static_cast<float>(yaw),             // Yaw -180 - 180
        0,                                   // Altitude (not used)
        0,                                   // Latitude (not used)
        0,                                   // Longitude (not used)
        MAV_MOUNT_MODE_MAVLINK_TARGETING);   // MAVLink Roll,Pitch,Yaw
}
Don Gagne's avatar
   
Don Gagne committed
4233

Gus Grubba's avatar
Gus Grubba committed
4234
4235
void Vehicle::gimbalPitchStep(int direction)
{
Gus Grubba's avatar
Gus Grubba committed
4236
4237
    if(_haveGimbalData) {
        //qDebug() << "Pitch:" << _curGimbalPitch << direction << (_curGimbalPitch + direction);
Gus Grubba's avatar
Gus Grubba committed
4238
4239
4240
4241
4242
4243
4244
        double p = static_cast<double>(_curGimbalPitch + direction);
        gimbalControlValue(p, static_cast<double>(_curGinmbalYaw));
    }
}

void Vehicle::gimbalYawStep(int direction)
{
Gus Grubba's avatar
Gus Grubba committed
4245
4246
    if(_haveGimbalData) {
        //qDebug() << "Yaw:" << _curGinmbalYaw << direction << (_curGinmbalYaw + direction);
Gus Grubba's avatar
Gus Grubba committed
4247
        double y = static_cast<double>(_curGinmbalYaw + direction);
Gus Grubba's avatar
Gus Grubba committed
4248
        gimbalControlValue(static_cast<double>(_curGimbalPitch), y);
Gus Grubba's avatar
Gus Grubba committed
4249
4250
4251
4252
4253
    }
}

void Vehicle::centerGimbal()
{
Gus Grubba's avatar
Gus Grubba committed
4254
    if(_haveGimbalData) {
Gus Grubba's avatar
Gus Grubba committed
4255
4256
4257
4258
4259
4260
4261
4262
4263
4264
4265
4266
4267
4268
4269
4270
4271
4272
4273
4274
4275
4276
4277
4278
4279
4280
        gimbalControlValue(0.0, 0.0);
    }
}

void Vehicle::_handleGimbalOrientation(const mavlink_message_t& message)
{
    mavlink_mount_orientation_t o;
    mavlink_msg_mount_orientation_decode(&message, &o);
    if(fabsf(_curGimbalRoll - o.roll) > 0.5f) {
        _curGimbalRoll = o.roll;
        emit gimbalRollChanged();
    }
    if(fabsf(_curGimbalPitch - o.pitch) > 0.5f) {
        _curGimbalPitch = o.pitch;
        emit gimbalPitchChanged();
    }
    if(fabsf(_curGinmbalYaw - o.yaw) > 0.5f) {
        _curGinmbalYaw = o.yaw;
        emit gimbalYawChanged();
    }
    if(!_haveGimbalData) {
        _haveGimbalData = true;
        emit gimbalDataChanged();
    }
}

Gus Grubba's avatar
Gus Grubba committed
4281
4282
void Vehicle::_handleObstacleDistance(const mavlink_message_t& message)
{
4283
4284
4285
      mavlink_obstacle_distance_t o;
      mavlink_msg_obstacle_distance_decode(&message, &o);
      _objectAvoidance->update(&o);
Gus Grubba's avatar
Gus Grubba committed
4286
4287
}

Gus Grubba's avatar
Gus Grubba committed
4288
void Vehicle::updateFlightDistance(double distance)
4289
4290
4291
4292
{
    _flightDistanceFact.setRawValue(_flightDistanceFact.rawValue().toDouble() + distance);
}

4293
4294
4295
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------

Don Gagne's avatar
Don Gagne committed
4296
4297
4298
4299
4300
const char* VehicleBatteryFactGroup::_voltageFactName =                     "voltage";
const char* VehicleBatteryFactGroup::_percentRemainingFactName =            "percentRemaining";
const char* VehicleBatteryFactGroup::_mahConsumedFactName =                 "mahConsumed";
const char* VehicleBatteryFactGroup::_currentFactName =                     "current";
const char* VehicleBatteryFactGroup::_temperatureFactName =                 "temperature";
4301
const char* VehicleBatteryFactGroup::_instantPowerFactName =                "instantPower";
4302
4303
const char* VehicleBatteryFactGroup::_timeRemainingFactName =               "timeRemaining";
const char* VehicleBatteryFactGroup::_chargeStateFactName =                 "chargeState";
Don Gagne's avatar
Don Gagne committed
4304
4305
4306

const char* VehicleBatteryFactGroup::_settingsGroup =                       "Vehicle.battery";

Don Gagne's avatar
Don Gagne committed
4307
4308
VehicleBatteryFactGroup::VehicleBatteryFactGroup(QObject* parent)
    : FactGroup(1000, ":/json/Vehicle/BatteryFact.json", parent)
Don Gagne's avatar
Don Gagne committed
4309
    , _voltageFact                  (0, _voltageFactName,                   FactMetaData::valueTypeDouble)
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
4310
4311
4312
    , _percentRemainingFact         (0, _percentRemainingFactName,          FactMetaData::valueTypeDouble)
    , _mahConsumedFact              (0, _mahConsumedFactName,               FactMetaData::valueTypeDouble)
    , _currentFact                  (0, _currentFactName,                   FactMetaData::valueTypeDouble)
Don Gagne's avatar
Don Gagne committed
4313
    , _temperatureFact              (0, _temperatureFactName,               FactMetaData::valueTypeDouble)
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
4314
4315
    , _instantPowerFact             (0, _instantPowerFactName,              FactMetaData::valueTypeDouble)
    , _timeRemainingFact            (0, _timeRemainingFactName,             FactMetaData::valueTypeDouble)
4316
    , _chargeStateFact              (0, _chargeStateFactName,               FactMetaData::valueTypeUint8)
Don Gagne's avatar
Don Gagne committed
4317
{
4318
4319
4320
4321
4322
    _addFact(&_voltageFact,                 _voltageFactName);
    _addFact(&_percentRemainingFact,        _percentRemainingFactName);
    _addFact(&_mahConsumedFact,             _mahConsumedFactName);
    _addFact(&_currentFact,                 _currentFactName);
    _addFact(&_temperatureFact,             _temperatureFactName);
4323
    _addFact(&_instantPowerFact,            _instantPowerFactName);
4324
4325
    _addFact(&_timeRemainingFact,           _timeRemainingFactName);
    _addFact(&_chargeStateFact,             _chargeStateFactName);
Don Gagne's avatar
Don Gagne committed
4326
4327

    // Start out as not available
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
4328
4329
4330
4331
4332
4333
    _voltageFact.setRawValue            (qQNaN());
    _percentRemainingFact.setRawValue   (qQNaN());
    _mahConsumedFact.setRawValue        (qQNaN());
    _currentFact.setRawValue            (qQNaN());
    _temperatureFact.setRawValue        (qQNaN());
    _instantPowerFact.setRawValue       (qQNaN());
DoinLakeFlyer's avatar
   
DoinLakeFlyer committed
4334
4335
    _timeRemainingFact.setRawValue      (qQNaN());
    _chargeStateFact.setRawValue        (MAV_BATTERY_CHARGE_STATE_UNDEFINED);
Don Gagne's avatar
Don Gagne committed
4336
4337
}

Don Gagne's avatar
Don Gagne committed
4338
4339
4340
4341
const char* VehicleWindFactGroup::_directionFactName =      "direction";
const char* VehicleWindFactGroup::_speedFactName =          "speed";
const char* VehicleWindFactGroup::_verticalSpeedFactName =  "verticalSpeed";

Don Gagne's avatar
Don Gagne committed
4342
4343
4344
4345
4346
4347
4348
4349
4350
4351
4352
4353
4354
4355
4356
4357
VehicleWindFactGroup::VehicleWindFactGroup(QObject* parent)
    : FactGroup(1000, ":/json/Vehicle/WindFact.json", parent)
    , _directionFact    (0, _directionFactName,     FactMetaData::valueTypeDouble)
    , _speedFact        (0, _speedFactName,         FactMetaData::valueTypeDouble)
    , _verticalSpeedFact(0, _verticalSpeedFactName, FactMetaData::valueTypeDouble)
{
    _addFact(&_directionFact,       _directionFactName);
    _addFact(&_speedFact,           _speedFactName);
    _addFact(&_verticalSpeedFact,   _verticalSpeedFactName);

    // Start out as not available "--.--"
    _directionFact.setRawValue      (std::numeric_limits<float>::quiet_NaN());
    _speedFact.setRawValue          (std::numeric_limits<float>::quiet_NaN());
    _verticalSpeedFact.setRawValue  (std::numeric_limits<float>::quiet_NaN());
}

Don Gagne's avatar
Don Gagne committed
4358
4359
4360
4361
4362
4363
4364
const char* VehicleVibrationFactGroup::_xAxisFactName =      "xAxis";
const char* VehicleVibrationFactGroup::_yAxisFactName =      "yAxis";
const char* VehicleVibrationFactGroup::_zAxisFactName =      "zAxis";
const char* VehicleVibrationFactGroup::_clipCount1FactName = "clipCount1";
const char* VehicleVibrationFactGroup::_clipCount2FactName = "clipCount2";
const char* VehicleVibrationFactGroup::_clipCount3FactName = "clipCount3";

Don Gagne's avatar
Don Gagne committed
4365
4366
4367
4368
4369
4370
4371
4372
4373
4374
4375
4376
4377
4378
4379
4380
4381
4382
4383
4384
4385
VehicleVibrationFactGroup::VehicleVibrationFactGroup(QObject* parent)
    : FactGroup(1000, ":/json/Vehicle/VibrationFact.json", parent)
    , _xAxisFact        (0, _xAxisFactName,         FactMetaData::valueTypeDouble)
    , _yAxisFact        (0, _yAxisFactName,         FactMetaData::valueTypeDouble)
    , _zAxisFact        (0, _zAxisFactName,         FactMetaData::valueTypeDouble)
    , _clipCount1Fact   (0, _clipCount1FactName,    FactMetaData::valueTypeUint32)
    , _clipCount2Fact   (0, _clipCount2FactName,    FactMetaData::valueTypeUint32)
    , _clipCount3Fact   (0, _clipCount3FactName,    FactMetaData::valueTypeUint32)
{
    _addFact(&_xAxisFact,       _xAxisFactName);
    _addFact(&_yAxisFact,       _yAxisFactName);
    _addFact(&_zAxisFact,       _zAxisFactName);
    _addFact(&_clipCount1Fact,  _clipCount1FactName);
    _addFact(&_clipCount2Fact,  _clipCount2FactName);
    _addFact(&_clipCount3Fact,  _clipCount3FactName);

    // Start out as not available "--.--"
    _xAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _yAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _zAxisFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
}
4386
4387
4388
4389
4390
4391
4392
4393
4394
4395
4396
4397
4398
4399
4400
4401
4402
4403
4404
4405

const char* VehicleTemperatureFactGroup::_temperature1FactName =      "temperature1";
const char* VehicleTemperatureFactGroup::_temperature2FactName =      "temperature2";
const char* VehicleTemperatureFactGroup::_temperature3FactName =      "temperature3";

VehicleTemperatureFactGroup::VehicleTemperatureFactGroup(QObject* parent)
    : FactGroup(1000, ":/json/Vehicle/TemperatureFact.json", parent)
    , _temperature1Fact    (0, _temperature1FactName,     FactMetaData::valueTypeDouble)
    , _temperature2Fact    (0, _temperature2FactName,     FactMetaData::valueTypeDouble)
    , _temperature3Fact    (0, _temperature3FactName,     FactMetaData::valueTypeDouble)
{
    _addFact(&_temperature1Fact,       _temperature1FactName);
    _addFact(&_temperature2Fact,       _temperature2FactName);
    _addFact(&_temperature3Fact,       _temperature3FactName);

    // Start out as not available "--.--"
    _temperature1Fact.setRawValue      (std::numeric_limits<float>::quiet_NaN());
    _temperature2Fact.setRawValue      (std::numeric_limits<float>::quiet_NaN());
    _temperature3Fact.setRawValue      (std::numeric_limits<float>::quiet_NaN());
}
dheideman's avatar
dheideman committed
4406
4407
4408
4409
4410
4411
4412
4413
4414
4415
4416
4417
4418
4419
4420
4421
4422

const char* VehicleClockFactGroup::_currentTimeFactName = "currentTime";
const char* VehicleClockFactGroup::_currentDateFactName = "currentDate";

VehicleClockFactGroup::VehicleClockFactGroup(QObject* parent)
    : FactGroup(1000, ":/json/Vehicle/ClockFact.json", parent)
    , _currentTimeFact  (0, _currentTimeFactName,    FactMetaData::valueTypeString)
    , _currentDateFact  (0, _currentDateFactName,    FactMetaData::valueTypeString)
{
    _addFact(&_currentTimeFact, _currentTimeFactName);
    _addFact(&_currentDateFact, _currentDateFactName);

    // Start out as not available "--.--"
    _currentTimeFact.setRawValue    (std::numeric_limits<float>::quiet_NaN());
    _currentDateFact.setRawValue    (std::numeric_limits<float>::quiet_NaN());
}

4423
void VehicleClockFactGroup::_updateAllValues()
dheideman's avatar
dheideman committed
4424
4425
4426
4427
4428
4429
{
    _currentTimeFact.setRawValue(QTime::currentTime().toString());
    _currentDateFact.setRawValue(QDateTime::currentDateTime().toString(QLocale::system().dateFormat(QLocale::ShortFormat)));

    FactGroup::_updateAllValues();
}
DonLakeFlyer's avatar
DonLakeFlyer committed
4430
4431
4432
4433
4434
4435
4436
4437
4438
4439
4440
4441
4442
4443
4444
4445
4446
4447
4448
4449
4450
4451
4452
4453
4454
4455
4456
4457
4458
4459
4460
4461

const char* VehicleSetpointFactGroup::_rollFactName =       "roll";
const char* VehicleSetpointFactGroup::_pitchFactName =      "pitch";
const char* VehicleSetpointFactGroup::_yawFactName =        "yaw";
const char* VehicleSetpointFactGroup::_rollRateFactName =   "rollRate";
const char* VehicleSetpointFactGroup::_pitchRateFactName =  "pitchRate";
const char* VehicleSetpointFactGroup::_yawRateFactName =    "yawRate";

VehicleSetpointFactGroup::VehicleSetpointFactGroup(QObject* parent)
    : FactGroup     (1000, ":/json/Vehicle/SetpointFact.json", parent)
    , _rollFact     (0, _rollFactName,      FactMetaData::valueTypeDouble)
    , _pitchFact    (0, _pitchFactName,     FactMetaData::valueTypeDouble)
    , _yawFact      (0, _yawFactName,       FactMetaData::valueTypeDouble)
    , _rollRateFact (0, _rollRateFactName,  FactMetaData::valueTypeDouble)
    , _pitchRateFact(0, _pitchRateFactName, FactMetaData::valueTypeDouble)
    , _yawRateFact  (0, _yawRateFactName,   FactMetaData::valueTypeDouble)
{
    _addFact(&_rollFact,        _rollFactName);
    _addFact(&_pitchFact,       _pitchFactName);
    _addFact(&_yawFact,         _yawFactName);
    _addFact(&_rollRateFact,    _rollRateFactName);
    _addFact(&_pitchRateFact,   _pitchRateFactName);
    _addFact(&_yawRateFact,     _yawRateFactName);

    // Start out as not available "--.--"
    _rollFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _pitchFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _yawFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _rollRateFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _pitchRateFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _yawRateFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
}
4462
4463

const char* VehicleDistanceSensorFactGroup::_rotationNoneFactName =     "rotationNone";
4464
const char* VehicleDistanceSensorFactGroup::_rotationYaw45FactName =    "rotationYaw45";
4465
const char* VehicleDistanceSensorFactGroup::_rotationYaw90FactName =    "rotationYaw90";
4466
const char* VehicleDistanceSensorFactGroup::_rotationYaw135FactName =   "rotationYaw135";
4467
const char* VehicleDistanceSensorFactGroup::_rotationYaw180FactName =   "rotationYaw180";
4468
const char* VehicleDistanceSensorFactGroup::_rotationYaw225FactName =   "rotationYaw225";
4469
const char* VehicleDistanceSensorFactGroup::_rotationYaw270FactName =   "rotationYaw270";
4470
4471
4472
const char* VehicleDistanceSensorFactGroup::_rotationYaw315FactName =   "rotationYaw315";
const char* VehicleDistanceSensorFactGroup::_rotationPitch90FactName =  "rotationPitch90";
const char* VehicleDistanceSensorFactGroup::_rotationPitch270FactName = "rotationPitch270";
4473
4474
4475
4476

VehicleDistanceSensorFactGroup::VehicleDistanceSensorFactGroup(QObject* parent)
    : FactGroup             (1000, ":/json/Vehicle/DistanceSensorFact.json", parent)
    , _rotationNoneFact     (0, _rotationNoneFactName,      FactMetaData::valueTypeDouble)
4477
    , _rotationYaw45Fact    (0, _rotationYaw45FactName,     FactMetaData::valueTypeDouble)
4478
    , _rotationYaw90Fact    (0, _rotationYaw90FactName,     FactMetaData::valueTypeDouble)
4479
    , _rotationYaw135Fact   (0, _rotationYaw135FactName,    FactMetaData::valueTypeDouble)
4480
    , _rotationYaw180Fact   (0, _rotationYaw180FactName,    FactMetaData::valueTypeDouble)
4481
    , _rotationYaw225Fact   (0, _rotationYaw225FactName,    FactMetaData::valueTypeDouble)
4482
    , _rotationYaw270Fact   (0, _rotationYaw270FactName,    FactMetaData::valueTypeDouble)
4483
4484
4485
4486
4487
4488
4489
4490
4491
4492
4493
4494
4495
4496
    , _rotationYaw315Fact   (0, _rotationYaw315FactName,    FactMetaData::valueTypeDouble)
    , _rotationPitch90Fact  (0, _rotationPitch90FactName,   FactMetaData::valueTypeDouble)
    , _rotationPitch270Fact (0, _rotationPitch270FactName,  FactMetaData::valueTypeDouble)
{
    _addFact(&_rotationNoneFact,        _rotationNoneFactName);
    _addFact(&_rotationYaw45Fact,       _rotationYaw45FactName);
    _addFact(&_rotationYaw90Fact,       _rotationYaw90FactName);
    _addFact(&_rotationYaw135Fact,      _rotationYaw135FactName);
    _addFact(&_rotationYaw180Fact,      _rotationYaw180FactName);
    _addFact(&_rotationYaw225Fact,      _rotationYaw225FactName);
    _addFact(&_rotationYaw270Fact,      _rotationYaw270FactName);
    _addFact(&_rotationYaw315Fact,      _rotationYaw315FactName);
    _addFact(&_rotationPitch90Fact,     _rotationPitch90FactName);
    _addFact(&_rotationPitch270Fact,    _rotationPitch270FactName);
4497
4498
4499

    // Start out as not available "--.--"
    _rotationNoneFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4500
4501
    _rotationYaw45Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _rotationYaw135Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4502
4503
    _rotationYaw90Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _rotationYaw180Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4504
    _rotationYaw225Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4505
    _rotationYaw270Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4506
4507
    _rotationPitch90Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _rotationPitch270Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4508
}
4509
4510
4511
4512
4513
4514
4515
4516
4517
4518
4519
4520
4521
4522
4523
4524
4525
4526
4527
4528
4529
4530
4531
4532
4533
4534
4535
4536
4537
4538
4539
4540
4541
4542
4543
4544
4545
4546
4547
4548
4549
4550
4551
4552
4553
4554
4555
4556
4557
4558
4559
4560
4561
4562
4563
4564
4565
4566
4567
4568
4569
4570
4571
4572
4573
4574

const char* VehicleEstimatorStatusFactGroup::_goodAttitudeEstimateFactName =        "goodAttitudeEsimate";
const char* VehicleEstimatorStatusFactGroup::_goodHorizVelEstimateFactName =        "goodHorizVelEstimate";
const char* VehicleEstimatorStatusFactGroup::_goodVertVelEstimateFactName =         "goodVertVelEstimate";
const char* VehicleEstimatorStatusFactGroup::_goodHorizPosRelEstimateFactName =     "goodHorizPosRelEstimate";
const char* VehicleEstimatorStatusFactGroup::_goodHorizPosAbsEstimateFactName =     "goodHorizPosAbsEstimate";
const char* VehicleEstimatorStatusFactGroup::_goodVertPosAbsEstimateFactName =      "goodVertPosAbsEstimate";
const char* VehicleEstimatorStatusFactGroup::_goodVertPosAGLEstimateFactName =      "goodVertPosAGLEstimate";
const char* VehicleEstimatorStatusFactGroup::_goodConstPosModeEstimateFactName =    "goodConstPosModeEstimate";
const char* VehicleEstimatorStatusFactGroup::_goodPredHorizPosRelEstimateFactName = "goodPredHorizPosRelEstimate";
const char* VehicleEstimatorStatusFactGroup::_goodPredHorizPosAbsEstimateFactName = "goodPredHorizPosAbsEstimate";
const char* VehicleEstimatorStatusFactGroup::_gpsGlitchFactName =                   "gpsGlitch";
const char* VehicleEstimatorStatusFactGroup::_accelErrorFactName =                  "accelError";
const char* VehicleEstimatorStatusFactGroup::_velRatioFactName =                    "velRatio";
const char* VehicleEstimatorStatusFactGroup::_horizPosRatioFactName =               "horizPosRatio";
const char* VehicleEstimatorStatusFactGroup::_vertPosRatioFactName =                "vertPosRatio";
const char* VehicleEstimatorStatusFactGroup::_magRatioFactName =                    "magRatio";
const char* VehicleEstimatorStatusFactGroup::_haglRatioFactName =                   "haglRatio";
const char* VehicleEstimatorStatusFactGroup::_tasRatioFactName =                    "tasRatio";
const char* VehicleEstimatorStatusFactGroup::_horizPosAccuracyFactName =            "horizPosAccuracy";
const char* VehicleEstimatorStatusFactGroup::_vertPosAccuracyFactName =             "vertPosAccuracy";

VehicleEstimatorStatusFactGroup::VehicleEstimatorStatusFactGroup(QObject* parent)
    : FactGroup                         (500, ":/json/Vehicle/EstimatorStatusFactGroup.json", parent)
    , _goodAttitudeEstimateFact         (0, _goodAttitudeEstimateFactName,          FactMetaData::valueTypeBool)
    , _goodHorizVelEstimateFact         (0, _goodHorizVelEstimateFactName,          FactMetaData::valueTypeBool)
    , _goodVertVelEstimateFact          (0, _goodVertVelEstimateFactName,           FactMetaData::valueTypeBool)
    , _goodHorizPosRelEstimateFact      (0, _goodHorizPosRelEstimateFactName,       FactMetaData::valueTypeBool)
    , _goodHorizPosAbsEstimateFact      (0, _goodHorizPosAbsEstimateFactName,       FactMetaData::valueTypeBool)
    , _goodVertPosAbsEstimateFact       (0, _goodVertPosAbsEstimateFactName,        FactMetaData::valueTypeBool)
    , _goodVertPosAGLEstimateFact       (0, _goodVertPosAGLEstimateFactName,        FactMetaData::valueTypeBool)
    , _goodConstPosModeEstimateFact     (0, _goodConstPosModeEstimateFactName,      FactMetaData::valueTypeBool)
    , _goodPredHorizPosRelEstimateFact  (0, _goodPredHorizPosRelEstimateFactName,   FactMetaData::valueTypeBool)
    , _goodPredHorizPosAbsEstimateFact  (0, _goodPredHorizPosAbsEstimateFactName,   FactMetaData::valueTypeBool)
    , _gpsGlitchFact                    (0, _gpsGlitchFactName,                     FactMetaData::valueTypeBool)
    , _accelErrorFact                   (0, _accelErrorFactName,                    FactMetaData::valueTypeBool)
    , _velRatioFact                     (0, _velRatioFactName,                      FactMetaData::valueTypeFloat)
    , _horizPosRatioFact                (0, _horizPosRatioFactName,                 FactMetaData::valueTypeFloat)
    , _vertPosRatioFact                 (0, _vertPosRatioFactName,                  FactMetaData::valueTypeFloat)
    , _magRatioFact                     (0, _magRatioFactName,                      FactMetaData::valueTypeFloat)
    , _haglRatioFact                    (0, _haglRatioFactName,                     FactMetaData::valueTypeFloat)
    , _tasRatioFact                     (0, _tasRatioFactName,                      FactMetaData::valueTypeFloat)
    , _horizPosAccuracyFact             (0, _horizPosAccuracyFactName,              FactMetaData::valueTypeFloat)
    , _vertPosAccuracyFact              (0, _vertPosAccuracyFactName,               FactMetaData::valueTypeFloat)
{
    _addFact(&_goodAttitudeEstimateFact,        _goodAttitudeEstimateFactName);
    _addFact(&_goodHorizVelEstimateFact,        _goodHorizVelEstimateFactName);
    _addFact(&_goodVertVelEstimateFact,         _goodVertVelEstimateFactName);
    _addFact(&_goodHorizPosRelEstimateFact,     _goodHorizPosRelEstimateFactName);
    _addFact(&_goodHorizPosAbsEstimateFact,     _goodHorizPosAbsEstimateFactName);
    _addFact(&_goodVertPosAbsEstimateFact,      _goodVertPosAbsEstimateFactName);
    _addFact(&_goodVertPosAGLEstimateFact,      _goodVertPosAGLEstimateFactName);
    _addFact(&_goodConstPosModeEstimateFact,    _goodConstPosModeEstimateFactName);
    _addFact(&_goodPredHorizPosRelEstimateFact, _goodPredHorizPosRelEstimateFactName);
    _addFact(&_goodPredHorizPosAbsEstimateFact, _goodPredHorizPosAbsEstimateFactName);
    _addFact(&_gpsGlitchFact,                   _gpsGlitchFactName);
    _addFact(&_accelErrorFact,                  _accelErrorFactName);
    _addFact(&_velRatioFact,                    _velRatioFactName);
    _addFact(&_horizPosRatioFact,               _horizPosRatioFactName);
    _addFact(&_vertPosRatioFact,                _vertPosRatioFactName);
    _addFact(&_magRatioFact,                    _magRatioFactName);
    _addFact(&_haglRatioFact,                   _haglRatioFactName);
    _addFact(&_tasRatioFact,                    _tasRatioFactName);
    _addFact(&_horizPosAccuracyFact,            _horizPosAccuracyFactName);
    _addFact(&_vertPosAccuracyFact,             _vertPosAccuracyFactName);
}