Vehicle.cc 160 KB
Newer Older
1
2
3
4
5
6
7
8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
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
17
18
19

#include "Vehicle.h"
#include "MAVLinkProtocol.h"
#include "FirmwarePluginManager.h"
#include "LinkManager.h"
#include "FirmwarePlugin.h"
20
#include "UAS.h"
Don Gagne's avatar
Don Gagne committed
21
#include "JoystickManager.h"
Don Gagne's avatar
Don Gagne committed
22
#include "MissionManager.h"
Don Gagne's avatar
Don Gagne committed
23
#include "MissionController.h"
24
#include "PlanMasterController.h"
25
26
#include "GeoFenceManager.h"
#include "RallyPointManager.h"
Don Gagne's avatar
Don Gagne committed
27
#include "CoordinateVector.h"
28
#include "ParameterManager.h"
29
#include "QGCApplication.h"
dogmaphobic's avatar
dogmaphobic committed
30
#include "QGCImageProvider.h"
DonLakeFlyer's avatar
DonLakeFlyer committed
31
#include "AudioOutput.h"
Jimmy Johnson's avatar
Jimmy Johnson committed
32
#include "FollowMe.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"
39
#include "ADSBVehicle.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"
45
46
47
48
#if defined(QGC_AIRMAP_ENABLED)
#include "AirspaceVehicleManager.h"
#endif

49
50
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")

51
52
53
54
#define UPDATE_TIMER 50
#define DEFAULT_LAT  38.965767f
#define DEFAULT_LON -120.083923f

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

Don Gagne's avatar
Don Gagne committed
57
58
59
const char* Vehicle::_settingsGroup =               "Vehicle%1";        // %1 replaced with mavlink system id
const char* Vehicle::_joystickModeSettingsKey =     "JoystickMode";
const char* Vehicle::_joystickEnabledSettingsKey =  "JoystickEnabled";
60

Don Gagne's avatar
Don Gagne committed
61
62
63
const char* Vehicle::_rollFactName =                "roll";
const char* Vehicle::_pitchFactName =               "pitch";
const char* Vehicle::_headingFactName =             "heading";
DonLakeFlyer's avatar
DonLakeFlyer committed
64
65
66
const char* Vehicle::_rollRateFactName =             "rollRate";
const char* Vehicle::_pitchRateFactName =           "pitchRate";
const char* Vehicle::_yawRateFactName =             "yawRate";
Don Gagne's avatar
Don Gagne committed
67
68
69
70
71
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";
72
const char* Vehicle::_flightDistanceFactName =      "flightDistance";
73
const char* Vehicle::_flightTimeFactName =          "flightTime";
74
const char* Vehicle::_distanceToHomeFactName =      "distanceToHome";
Don Gagne's avatar
   
Don Gagne committed
75
const char* Vehicle::_headingToHomeFactName =       "headingToHome";
Don Gagne's avatar
   
Don Gagne committed
76
const char* Vehicle::_distanceToGCSFactName =       "distanceToGCS";
77
const char* Vehicle::_hobbsFactName =               "hobbs";
Don Gagne's avatar
Don Gagne committed
78

79
80
81
82
83
84
85
86
87
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
88

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

218
    _mavlink = _toolbox->mavlinkProtocol();
dogmaphobic's avatar
dogmaphobic committed
219

Gus Grubba's avatar
Gus Grubba committed
220
221
    connect(_mavlink, &MAVLinkProtocol::messageReceived,        this, &Vehicle::_mavlinkMessageReceived);
    connect(_mavlink, &MAVLinkProtocol::mavlinkMessageStatus,   this, &Vehicle::_mavlinkMessageStatus);
Don Gagne's avatar
Don Gagne committed
222

223
224
    _addLink(link);

225
    connect(this, &Vehicle::_sendMessageOnLinkOnThread, this, &Vehicle::_sendMessageOnLink, Qt::QueuedConnection);
Don Gagne's avatar
Don Gagne committed
226
    connect(this, &Vehicle::flightModeChanged,          this, &Vehicle::_handleFlightModeChanged);
227
    connect(this, &Vehicle::armedChanged,               this, &Vehicle::_announceArmedChanged);
228

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

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

Don Gagne's avatar
Don Gagne committed
233
234
    connect(_uas, &UAS::imageReady,                     this, &Vehicle::_imageReady);
    connect(this, &Vehicle::remoteControlRSSIChanged,   this, &Vehicle::_remoteControlRSSIChanged);
dogmaphobic's avatar
dogmaphobic committed
235

236
    _commonInit();
Don Gagne's avatar
Don Gagne committed
237
    _autopilotPlugin = _firmwarePlugin->autopilotPlugin(this);
dogmaphobic's avatar
dogmaphobic committed
238

Jimmy Johnson's avatar
Jimmy Johnson committed
239
    // connect this vehicle to the follow me handle manager
240
    connect(this, &Vehicle::flightModeChanged,_toolbox->followMe(), &FollowMe::followMeHandleManager);
Jimmy Johnson's avatar
Jimmy Johnson committed
241

Don Gagne's avatar
Don Gagne committed
242
243
244
245
246
    // PreArm Error self-destruct timer
    connect(&_prearmErrorTimer, &QTimer::timeout, this, &Vehicle::_prearmErrorTimeout);
    _prearmErrorTimer.setInterval(_prearmErrorTimeoutMSecs);
    _prearmErrorTimer.setSingleShot(true);

247
248
    // Send MAV_CMD ack timer
    _mavCommandAckTimer.setSingleShot(true);
DonLakeFlyer's avatar
DonLakeFlyer committed
249
    _mavCommandAckTimer.setInterval(_highLatencyLink ? _mavCommandAckTimeoutMSecsHighLatency : _mavCommandAckTimeoutMSecs);
250
251
    connect(&_mavCommandAckTimer, &QTimer::timeout, this, &Vehicle::_sendMavCommandAgain);

252
    _mav = uas();
253

254
    // Listen for system messages
255
256
    connect(_toolbox->uasMessageHandler(), &UASMessageHandler::textMessageCountChanged,  this, &Vehicle::_handleTextMessage);
    connect(_toolbox->uasMessageHandler(), &UASMessageHandler::textMessageReceived,      this, &Vehicle::_handletextMessageReceived);
Tomaz Canabrava's avatar
Tomaz Canabrava committed
257

DonLakeFlyer's avatar
DonLakeFlyer committed
258
259
    if (_highLatencyLink || link->isPX4Flow()) {
        // These links don't request information
DonLakeFlyer's avatar
DonLakeFlyer committed
260
261
262
263
264
265
266
267
268
269
270
271
        _setMaxProtoVersion(100);
        _setCapabilities(0);
        _initialPlanRequestComplete = true;
        _missionManagerInitialRequestSent = true;
        _geoFenceManagerInitialRequestSent = true;
        _rallyPointManagerInitialRequestSent = true;
    } else {
        // Ask the vehicle for protocol version info.
        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
dogmaphobic's avatar
dogmaphobic committed
272

DonLakeFlyer's avatar
DonLakeFlyer committed
273
274
275
276
277
278
        // Ask the vehicle for firmware version info.
        sendMavCommand(MAV_COMP_ID_ALL,                         // Don't know default component id yet.
                       MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
                       false,                                   // No error shown if fails
                       1);                                      // Request firmware version
    }
279

280
    _firmwarePlugin->initializeVehicle(this);
dogmaphobic's avatar
dogmaphobic committed
281

282
283
    _sendMultipleTimer.start(_sendMessageMultipleIntraMessageDelay);
    connect(&_sendMultipleTimer, &QTimer::timeout, this, &Vehicle::_sendMessageMultipleNext);
dogmaphobic's avatar
dogmaphobic committed
284

Don Gagne's avatar
Don Gagne committed
285
286
    _mapTrajectoryTimer.setInterval(_mapTrajectoryMsecsBetweenPoints);
    connect(&_mapTrajectoryTimer, &QTimer::timeout, this, &Vehicle::_addNewMapTrajectoryPoint);
Gus Grubba's avatar
Gus Grubba committed
287

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

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

294
295
296
    connect(&_adsbTimer, &QTimer::timeout, this, &Vehicle::_adsbTimerTimeout);
    _adsbTimer.setSingleShot(false);
    _adsbTimer.start(1000);
297
298
}

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

    // 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);

419
    _firmwarePlugin->initializeVehicle(this);
420
421
422
423
424
}

void Vehicle::_commonInit(void)
{
    _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
425

426
427
    connect(_firmwarePlugin, &FirmwarePlugin::toolbarIndicatorsChanged, this, &Vehicle::toolBarIndicatorsChanged);

Don Gagne's avatar
   
Don Gagne committed
428
    connect(this, &Vehicle::coordinateChanged,      this, &Vehicle::_updateDistanceHeadingToHome);
Don Gagne's avatar
   
Don Gagne committed
429
    connect(this, &Vehicle::coordinateChanged,      this, &Vehicle::_updateDistanceToGCS);
Don Gagne's avatar
   
Don Gagne committed
430
    connect(this, &Vehicle::homePositionChanged,    this, &Vehicle::_updateDistanceHeadingToHome);
431
    connect(this, &Vehicle::hobbsMeterChanged,      this, &Vehicle::_updateHobbsMeter);
432

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

435
    _missionManager = new MissionManager(this);
436
    connect(_missionManager, &MissionManager::error,                    this, &Vehicle::_missionManagerError);
DonLakeFlyer's avatar
DonLakeFlyer committed
437
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_missionLoadComplete);
438
439
440
441
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_clearCameraTriggerPoints);
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_clearTrajectoryPoints);
    connect(_missionManager, &MissionManager::sendComplete,             this, &Vehicle::_clearCameraTriggerPoints);
    connect(_missionManager, &MissionManager::sendComplete,             this, &Vehicle::_clearTrajectoryPoints);
442

443
    _parameterManager = new ParameterManager(this);
Don Gagne's avatar
Don Gagne committed
444
    connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
445

446
    // GeoFenceManager needs to access ParameterManager so make sure to create after
447
    _geoFenceManager = new GeoFenceManager(this);
448
    connect(_geoFenceManager, &GeoFenceManager::error,          this, &Vehicle::_geoFenceManagerError);
DonLakeFlyer's avatar
DonLakeFlyer committed
449
    connect(_geoFenceManager, &GeoFenceManager::loadComplete,   this, &Vehicle::_geoFenceLoadComplete);
450

451
    _rallyPointManager = new RallyPointManager(this);
DonLakeFlyer's avatar
DonLakeFlyer committed
452
453
    connect(_rallyPointManager, &RallyPointManager::error,          this, &Vehicle::_rallyPointManagerError);
    connect(_rallyPointManager, &RallyPointManager::loadComplete,   this, &Vehicle::_rallyPointLoadComplete);
454

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

Don Gagne's avatar
Don Gagne committed
458
459
460
461
462
    // Build FactGroup object model

    _addFact(&_rollFact,                _rollFactName);
    _addFact(&_pitchFact,               _pitchFactName);
    _addFact(&_headingFact,             _headingFactName);
DonLakeFlyer's avatar
DonLakeFlyer committed
463
464
465
    _addFact(&_rollRateFact,            _rollRateFactName);
    _addFact(&_pitchRateFact,           _pitchRateFactName);
    _addFact(&_yawRateFact,             _yawRateFactName);
Don Gagne's avatar
Don Gagne committed
466
467
468
469
470
    _addFact(&_groundSpeedFact,         _groundSpeedFactName);
    _addFact(&_airSpeedFact,            _airSpeedFactName);
    _addFact(&_climbRateFact,           _climbRateFactName);
    _addFact(&_altitudeRelativeFact,    _altitudeRelativeFactName);
    _addFact(&_altitudeAMSLFact,        _altitudeAMSLFactName);
471
    _addFact(&_flightDistanceFact,      _flightDistanceFactName);
472
    _addFact(&_flightTimeFact,          _flightTimeFactName);
473
    _addFact(&_distanceToHomeFact,      _distanceToHomeFactName);
Don Gagne's avatar
   
Don Gagne committed
474
    _addFact(&_headingToHomeFact,       _headingToHomeFactName);
Don Gagne's avatar
   
Don Gagne committed
475
    _addFact(&_distanceToGCSFact,       _distanceToGCSFactName);
476
477

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

480
    _addFactGroup(&_gpsFactGroup,               _gpsFactGroupName);
DonLakeFlyer's avatar
comit    
DonLakeFlyer committed
481
482
    _addFactGroup(&_battery1FactGroup,          _battery1FactGroupName);
    _addFactGroup(&_battery2FactGroup,          _battery2FactGroupName);
483
484
485
486
487
    _addFactGroup(&_windFactGroup,              _windFactGroupName);
    _addFactGroup(&_vibrationFactGroup,         _vibrationFactGroupName);
    _addFactGroup(&_temperatureFactGroup,       _temperatureFactGroupName);
    _addFactGroup(&_clockFactGroup,             _clockFactGroupName);
    _addFactGroup(&_distanceSensorFactGroup,    _distanceSensorFactGroupName);
488
    _addFactGroup(&_estimatorStatusFactGroup,   _estimatorStatusFactGroupName);
489

Jacob Walser's avatar
Jacob Walser committed
490
    // Add firmware-specific fact groups, if provided
491
492
493
494
495
496
497
    QMap<QString, FactGroup*>* fwFactGroups = _firmwarePlugin->factGroups();
    if (fwFactGroups) {
        QMapIterator<QString, FactGroup*> i(*fwFactGroups);
        while(i.hasNext()) {
            i.next();
            _addFactGroup(i.value(), i.key());
        }
498
499
    }

500
    _flightDistanceFact.setRawValue(0);
501
    _flightTimeFact.setRawValue(0);
502

503
504
505
506
507
508
    // Set video stream to udp if running ArduSub and Video is disabled
    if (sub() && _settingsManager->videoSettings()->videoSource()->rawValue() == VideoSettings::videoDisabled)
    {
        _settingsManager->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceUDP);
    }

509
510
511
512
513
514
515
516
517
518
    //-- 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
519
520
}

521
522
Vehicle::~Vehicle()
{
Don Gagne's avatar
Don Gagne committed
523
524
    qCDebug(VehicleLog) << "~Vehicle" << this;

525
    delete _missionManager;
526
    _missionManager = nullptr;
Don Gagne's avatar
Don Gagne committed
527

528
    delete _autopilotPlugin;
529
    _autopilotPlugin = nullptr;
530

Don Gagne's avatar
Don Gagne committed
531
    delete _mav;
532
    _mav = nullptr;
dogmaphobic's avatar
dogmaphobic committed
533

534
#if defined(QGC_AIRMAP_ENABLED)
Gus Grubba's avatar
Gus Grubba committed
535
536
    if (_airspaceVehicleManager) {
        delete _airspaceVehicleManager;
537
    }
538
#endif
539
540
}

541
542
543
544
void Vehicle::prepareDelete()
{
    if(_cameras) {
        delete _cameras;
545
        _cameras = nullptr;
546
547
548
549
550
        emit dynamicCamerasChanged();
        qApp->processEvents();
    }
}

551
552
553
void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant value)
{
    _firmwareType = static_cast<MAV_AUTOPILOT>(value.toInt());
554
    _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
555
    emit firmwareTypeChanged();
556
557
558
559
560
561
    if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
        _capabilityBits = 0;
    } else {
        _capabilityBits = MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY;
    }
    emit capabilityBitsChanged(_capabilityBits);
562
563
564
565
566
567
568
569
570
571
}

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

void Vehicle::_offlineCruiseSpeedSettingChanged(QVariant value)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
572
573
    _defaultCruiseSpeed = value.toDouble();
    emit defaultCruiseSpeedChanged(_defaultCruiseSpeed);
574
575
576
577
}

void Vehicle::_offlineHoverSpeedSettingChanged(QVariant value)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
578
579
    _defaultHoverSpeed = value.toDouble();
    emit defaultHoverSpeedChanged(_defaultHoverSpeed);
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
}

QString Vehicle::firmwareTypeString(void) const
{
    if (px4Firmware()) {
        return QStringLiteral("PX4 Pro");
    } else if (apmFirmware()) {
        return QStringLiteral("ArduPilot");
    } else {
        return tr("MAVLink Generic");
    }
}

QString Vehicle::vehicleTypeString(void) const
{
    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()
611
612
613
614
615
616
617
618
{
    _messagesReceived   = 0;
    _messagesSent       = 0;
    _messagesLost       = 0;
    _messageSeq         = 0;
    _heardFrom          = false;
}

619
620
void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
621
622
623
624
625
626
627
628
    // if the minimum supported version of MAVLink is already 2.0
    // set our max proto version to it.
    unsigned mavlinkVersion = _mavlink->getCurrentVersion();
    if (_maxProtoVersion != mavlinkVersion && mavlinkVersion >= 200) {
        _maxProtoVersion = _mavlink->getCurrentVersion();
        qCDebug(VehicleLog) << "Vehicle::_mavlinkMessageReceived setting _maxProtoVersion" << _maxProtoVersion;
    }

Don Gagne's avatar
Don Gagne committed
629
    if (message.sysid != _id && message.sysid != 0) {
630
631
632
633
        // 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;
        }
634
    }
635

636
637
638
    if (!_containsLink(link)) {
        _addLink(link);
    }
dogmaphobic's avatar
dogmaphobic committed
639

640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
    //-- 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) {
            uint16_t seq_received = (uint16_t)message.seq;
            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
666
    // Give the plugin a change to adjust the message contents
667
668
669
    if (!_firmwarePlugin->adjustIncomingMavlinkMessage(this, &message)) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
670

671
672
673
674
675
    // Give the Core Plugin access to all mavlink traffic
    if (!_toolbox->corePlugin()->mavlinkMessage(this, link, message)) {
        return;
    }

Don Gagne's avatar
Don Gagne committed
676
    switch (message.msgid) {
Don Gagne's avatar
Don Gagne committed
677
678
679
680
681
682
    case MAVLINK_MSG_ID_HOME_POSITION:
        _handleHomePosition(message);
        break;
    case MAVLINK_MSG_ID_HEARTBEAT:
        _handleHeartbeat(message);
        break;
683
684
685
    case MAVLINK_MSG_ID_RADIO_STATUS:
        _handleRadioStatus(message);
        break;
Don Gagne's avatar
Don Gagne committed
686
687
688
689
690
691
    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
692
693
694
695
696
697
    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
698
699
700
701
702
703
704
705
706
707
708
709
    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
710
711
712
    case MAVLINK_MSG_ID_VIBRATION:
        _handleVibration(message);
        break;
Don Gagne's avatar
Don Gagne committed
713
714
715
    case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
        _handleExtendedSysState(message);
        break;
716
717
718
    case MAVLINK_MSG_ID_COMMAND_ACK:
        _handleCommandAck(message);
        break;
719
720
721
    case MAVLINK_MSG_ID_COMMAND_LONG:
        _handleCommandLong(message);
        break;
722
    case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
Gus Grubba's avatar
Gus Grubba committed
723
        _handleAutopilotVersion(link, message);
724
        break;
725
726
727
    case MAVLINK_MSG_ID_PROTOCOL_VERSION:
        _handleProtocolVersion(link, message);
        break;
728
729
730
    case MAVLINK_MSG_ID_WIND_COV:
        _handleWindCov(message);
        break;
Bart Slinger's avatar
Bart Slinger committed
731
732
733
    case MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS:
        _handleHilActuatorControls(message);
        break;
734
735
736
737
738
739
    case MAVLINK_MSG_ID_LOGGING_DATA:
        _handleMavlinkLoggingData(message);
        break;
    case MAVLINK_MSG_ID_LOGGING_DATA_ACKED:
        _handleMavlinkLoggingDataAcked(message);
        break;
740
741
742
743
744
745
746
747
748
749
750
751
    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;
752
753
754
755
756
757
758
759
    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
760
        break;
761
762
    case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED:
        _handleCameraImageCaptured(message);
763
        break;
764
765
766
    case MAVLINK_MSG_ID_ADSB_VEHICLE:
        _handleADSBVehicle(message);
        break;
DonLakeFlyer's avatar
DonLakeFlyer committed
767
768
769
    case MAVLINK_MSG_ID_HIGH_LATENCY2:
        _handleHighLatency2(message);
        break;
770
771
772
    case MAVLINK_MSG_ID_ATTITUDE:
        _handleAttitude(message);
        break;
773
774
    case MAVLINK_MSG_ID_ATTITUDE_QUATERNION:
        _handleAttitudeQuaternion(message);
DonLakeFlyer's avatar
DonLakeFlyer committed
775
776
777
778
        break;
    case MAVLINK_MSG_ID_ATTITUDE_TARGET:
        _handleAttitudeTarget(message);
        break;
779
780
781
    case MAVLINK_MSG_ID_DISTANCE_SENSOR:
        _handleDistanceSensor(message);
        break;
782
783
784
    case MAVLINK_MSG_ID_ESTIMATOR_STATUS:
        _handleEstimatorStatus(message);
        break;
Don Gagne's avatar
   
Don Gagne committed
785
786
787
    case MAVLINK_MSG_ID_STATUSTEXT:
        _handleStatusText(message);
        break;
Don Gagne's avatar
   
Don Gagne committed
788
789
790
    case MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS:
        _handleOrbitExecutionStatus(message);
        break;
Don Gagne's avatar
   
Don Gagne committed
791

DonLakeFlyer's avatar
DonLakeFlyer committed
792
793
794
    case MAVLINK_MSG_ID_PING:
        _handlePing(link, message);
        break;
Don Gagne's avatar
Don Gagne committed
795

Nate Weibley's avatar
Nate Weibley committed
796
797
798
799
800
801
802
    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
803

DonLakeFlyer's avatar
DonLakeFlyer committed
804
        // Following are ArduPilot dialect messages
805
806
807
808
#if !defined(NO_ARDUPILOT_DIALECT)
    case MAVLINK_MSG_ID_CAMERA_FEEDBACK:
        _handleCameraFeedback(message);
        break;
Don Gagne's avatar
Don Gagne committed
809
810
811
    case MAVLINK_MSG_ID_WIND:
        _handleWind(message);
        break;
812
#endif
Don Gagne's avatar
Don Gagne committed
813
    }
dogmaphobic's avatar
dogmaphobic committed
814

815
816
    // 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
817
    emit mavlinkMessageReceived(message);
dogmaphobic's avatar
dogmaphobic committed
818

819
820
821
    _uas->receiveMessage(message);
}

822
#if !defined(NO_ARDUPILOT_DIALECT)
823
824
825
826
827
828
829
830
831
832
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));
}
833
#endif
834

Don Gagne's avatar
   
Don Gagne committed
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
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);
}

void Vehicle::_orbitTelemetryTimeout(void)
{
    _orbitActive = false;
    emit orbitActiveChanged(false);
}

871
872
873
874
875
876
877
878
879
880
881
882
883
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
884
885
886
887
888
889
890
891
void Vehicle::_handleStatusText(mavlink_message_t& message)
{
    QByteArray b;

    b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
    mavlink_msg_statustext_get_text(&message, b.data());
    b[b.length()-1] = '\0';
    QString messageText = QString(b);
Don Gagne's avatar
   
Don Gagne committed
892
    int severity = mavlink_msg_statustext_get_severity(&message);
Don Gagne's avatar
   
Don Gagne committed
893
894

    bool skipSpoken = false;
Don Gagne's avatar
   
Don Gagne committed
895
    bool ardupilotPrearm = messageText.startsWith(QStringLiteral("PreArm"));
Don Gagne's avatar
   
Don Gagne committed
896
    bool px4Prearm = messageText.startsWith(QStringLiteral("preflight"), Qt::CaseInsensitive) && severity >= MAV_SEVERITY_CRITICAL;
Don Gagne's avatar
   
Don Gagne committed
897
    if (ardupilotPrearm || px4Prearm) {
Don Gagne's avatar
   
Don Gagne committed
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
        // 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);
}

919
920
921
922
923
924
925
926
927
928
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);
}

929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
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
982
983
        } mavlink_estimator_status_t;
    };
984
985
986
#endif
}

987
988
989
990
void Vehicle::_handleDistanceSensor(mavlink_message_t& message)
{
    mavlink_distance_sensor_t distanceSensor;

991
992
993
994
    mavlink_msg_distance_sensor_decode(&message, &distanceSensor);\

    if (!_distanceSensorFactGroup.idSet()) {
        _distanceSensorFactGroup.setIdSet(true);
995
        _distanceSensorFactGroup.setId(distanceSensor.id);
996
997
    }

998
    if (_distanceSensorFactGroup.id() != distanceSensor.id) {
999
1000
1001
        // We can only handle a single sensor reporting
        return;
    }
1002
1003
1004
1005
1006
1007
1008
1009

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

    orientation2Fact_s rgOrientation2Fact[] =
    {
1010
1011
1012
1013
1014
1015
1016
1017
1018
1019
        { 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() },
1020
1021
1022
1023
1024
    };

    for (size_t i=0; i<sizeof(rgOrientation2Fact)/sizeof(rgOrientation2Fact[0]); i++) {
        const orientation2Fact_s& orientation2Fact = rgOrientation2Fact[i];
        if (orientation2Fact.orientation == distanceSensor.orientation) {
1025
            orientation2Fact.fact->setRawValue(distanceSensor.current_distance / 100.0); // cm to meters
1026
1027
1028
1029
        }
    }
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1030
1031
1032
1033
1034
1035
1036
1037
1038
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
1039
1040
1041
    _setpointFactGroup.roll()->setRawValue(qRadiansToDegrees(roll));
    _setpointFactGroup.pitch()->setRawValue(qRadiansToDegrees(pitch));
    _setpointFactGroup.yaw()->setRawValue(qRadiansToDegrees(yaw));
DonLakeFlyer's avatar
DonLakeFlyer committed
1042
1043
1044
1045
1046
1047

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

1048
void Vehicle::_handleAttitudeWorker(double rollRadians, double pitchRadians, double yawRadians)
DonLakeFlyer's avatar
DonLakeFlyer committed
1049
{
1050
    double roll, pitch, yaw;
1051

1052
1053
1054
    roll = QGC::limitAngleToPMPIf(rollRadians);
    pitch = QGC::limitAngleToPMPIf(pitchRadians);
    yaw = QGC::limitAngleToPMPIf(yawRadians);
1055
1056
1057
1058
1059
1060
1061
1062
1063
1064
1065
1066
1067
1068

    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);
1069
1070
1071
1072
1073
1074
1075
1076
1077
1078
1079
1080
1081
1082
1083
1084
1085
1086
1087
1088
1089
1090
1091
1092
1093
1094
}

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);

    float roll, pitch, yaw;
    float q[] = { attitudeQuaternion.q1, attitudeQuaternion.q2, attitudeQuaternion.q3, attitudeQuaternion.q4 };
    mavlink_quaternion_to_euler(q, &roll, &pitch, &yaw);

    _handleAttitudeWorker(roll, pitch, yaw);
1095
1096
1097
1098

    rollRate()->setRawValue(qRadiansToDegrees(attitudeQuaternion.rollspeed));
    pitchRate()->setRawValue(qRadiansToDegrees(attitudeQuaternion.pitchspeed));
    yawRate()->setRawValue(qRadiansToDegrees(attitudeQuaternion.yawspeed));
DonLakeFlyer's avatar
DonLakeFlyer committed
1099
1100
}

1101
1102
1103
1104
1105
void Vehicle::_handleGpsRawInt(mavlink_message_t& message)
{
    mavlink_gps_raw_int_t gpsRawInt;
    mavlink_msg_gps_raw_int_decode(&message, &gpsRawInt);

1106
1107
    _gpsRawIntMessageAvailable = true;

1108
    if (gpsRawInt.fix_type >= GPS_FIX_TYPE_3D_FIX) {
1109
        if (!_globalPositionIntMessageAvailable) {
1110
1111
1112
1113
1114
            QGeoCoordinate newPosition(gpsRawInt.lat  / (double)1E7, gpsRawInt.lon / (double)1E7, gpsRawInt.alt  / 1000.0);
            if (newPosition != _coordinate) {
                _coordinate = newPosition;
                emit coordinateChanged(_coordinate);
            }
1115
            _altitudeAMSLFact.setRawValue(gpsRawInt.alt / 1000.0);
1116
1117
1118
        }
    }

1119
1120
    _gpsFactGroup.lat()->setRawValue(gpsRawInt.lat * 1e-7);
    _gpsFactGroup.lon()->setRawValue(gpsRawInt.lon * 1e-7);
1121
    _gpsFactGroup.count()->setRawValue(gpsRawInt.satellites_visible == 255 ? 0 : gpsRawInt.satellites_visible);
1122
1123
1124
    _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);
1125
1126
1127
1128
1129
1130
1131
1132
    _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);

1133
1134
1135
1136
1137
    _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.
1138
    if (globalPositionInt.lat == 0 && globalPositionInt.lon == 0) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1139
1140
1141
        return;
    }

1142
    _globalPositionIntMessageAvailable = true;
1143
1144
1145
1146
1147
    QGeoCoordinate newPosition(globalPositionInt.lat  / (double)1E7, globalPositionInt.lon / (double)1E7, globalPositionInt.alt  / 1000.0);
    if (newPosition != _coordinate) {
        _coordinate = newPosition;
        emit coordinateChanged(_coordinate);
    }
1148
1149
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1150
1151
1152
1153
1154
void Vehicle::_handleHighLatency2(mavlink_message_t& message)
{
    mavlink_high_latency2_t highLatency2;
    mavlink_msg_high_latency2_decode(&message, &highLatency2);

1155
1156
1157
1158
1159
1160
1161
1162
1163
1164
1165
1166
1167
1168
1169
1170
1171
1172
    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
1173
1174
1175
1176
1177
1178
1179
1180
1181
    _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
1182
1183
    _altitudeRelativeFact.setRawValue(std::numeric_limits<double>::quiet_NaN());
    _altitudeAMSLFact.setRawValue(highLatency2.altitude);
DonLakeFlyer's avatar
DonLakeFlyer committed
1184
1185
1186
1187

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

DonLakeFlyer's avatar
comit    
DonLakeFlyer committed
1188
    _battery1FactGroup.percentRemaining()->setRawValue(highLatency2.battery);
DonLakeFlyer's avatar
DonLakeFlyer committed
1189
1190
1191
1192
1193
1194
1195
1196

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

    _gpsFactGroup.lat()->setRawValue(highLatency2.latitude * 1e-7);
    _gpsFactGroup.lon()->setRawValue(highLatency2.longitude * 1e-7);
    _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);
1197
1198

    struct failure2Sensor_s {
1199
        HL_FAILURE_FLAG         failureBit;
1200
1201
1202
1203
        MAV_SYS_STATUS_SENSOR   sensorBit;
    };

    static const failure2Sensor_s rgFailure2Sensor[] = {
1204
1205
1206
1207
1208
1209
        { 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 },
1210
1211
1212
1213
1214
1215
1216
1217
1218
1219
1220
1221
1222
1223
1224
1225
1226
    };

    // 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
1227
1228
}

1229
1230
1231
1232
1233
void Vehicle::_handleAltitude(mavlink_message_t& message)
{
    mavlink_altitude_t altitude;
    mavlink_msg_altitude_decode(&message, &altitude);

1234
1235
1236
1237
1238
1239
1240
    // 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);
        }
    }
1241
1242
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1243
1244
void Vehicle::_setCapabilities(uint64_t capabilityBits)
{
1245
    _capabilityBits = capabilityBits;
DonLakeFlyer's avatar
DonLakeFlyer committed
1246
    _vehicleCapabilitiesKnown = true;
1247
    emit capabilitiesKnownChanged(true);
1248
    emit capabilityBitsChanged(_capabilityBits);
DonLakeFlyer's avatar
DonLakeFlyer committed
1249

1250
1251
1252
1253
1254
1255
1256
    // This should potentially be turned into a user-facing warning
    // if the general experience after deployment is that users want MAVLink 2
    // but forget to upgrade their radio firmware
    if (capabilityBits & MAV_PROTOCOL_CAPABILITY_MAVLINK2 && maxProtoVersion() < 200) {
        qCDebug(VehicleLog) << QString("Vehicle does support MAVLink 2 but the link does not allow for it.");
    }

1257
1258
1259
1260
1261
    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);
1262
    qCDebug(VehicleLog) << QString("Vehicle %1 MISSION_COMMAND_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_COMMAND_INT ? supports : doesNotSupport);
1263
1264
    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
1265
1266
}

Gus Grubba's avatar
Gus Grubba committed
1267
void Vehicle::_handleAutopilotVersion(LinkInterface *link, mavlink_message_t& message)
1268
{
Don Gagne's avatar
Don Gagne committed
1269
1270
    Q_UNUSED(link);

1271
1272
1273
    mavlink_autopilot_version_t autopilotVersion;
    mavlink_msg_autopilot_version_decode(&message, &autopilotVersion);

Gus Grubba's avatar
Gus Grubba committed
1274
1275
1276
    _uid = (quint64)autopilotVersion.uid;
    emit vehicleUIDChanged();

1277
1278
1279
1280
1281
1282
1283
1284
    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
1285
        setFirmwareVersion(majorVersion, minorVersion, patchVersion, versionType);
1286
    }
1287

Don Gagne's avatar
Don Gagne committed
1288
1289
1290
1291
1292
1293
1294
1295
    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);

1296
        // 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
1297
1298
1299
1300
        _gitHash = "";
        QByteArray array((char*)autopilotVersion.flight_custom_version, 8);
        for (int i = 7; i >= 0; i--) {
            _gitHash.append(QString("%1").arg(autopilotVersion.flight_custom_version[i], 2, 16, QChar('0')));
1301
        }
Don Gagne's avatar
Don Gagne committed
1302
1303
1304
    } else {
        // APM Firmware stores the first 8 characters of the git hash as an ASCII character string
        _gitHash = QString::fromUtf8((char*)autopilotVersion.flight_custom_version, 8);
1305
    }
Don Gagne's avatar
   
Don Gagne committed
1306
1307
1308
    if (_toolbox->corePlugin()->options()->checkFirmwareVersion()) {
        _firmwarePlugin->checkIfIsLatestStable(this);
    }
Don Gagne's avatar
Don Gagne committed
1309
    emit gitHashChanged(_gitHash);
1310

DonLakeFlyer's avatar
DonLakeFlyer committed
1311
1312
    _setCapabilities(autopilotVersion.capabilities);
    _startPlanRequest();
1313
1314
}

1315
1316
1317
1318
1319
1320
1321
1322
1323
1324
1325
void Vehicle::_handleProtocolVersion(LinkInterface *link, mavlink_message_t& message)
{
    Q_UNUSED(link);

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

    _setMaxProtoVersion(protoVersion.max_version);
}

void Vehicle::_setMaxProtoVersion(unsigned version) {
1326
1327
1328

    // Set only once or if we need to reduce the max version
    if (_maxProtoVersion == 0 || version < _maxProtoVersion) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1329
        qCDebug(VehicleLog) << "_setMaxProtoVersion before:after" << _maxProtoVersion << version;
1330
1331
        _maxProtoVersion = version;
        emit requestProtocolVersion(_maxProtoVersion);
1332
1333
1334
1335
1336

        // Now that the protocol version is known, the mission load is safe
        // as it will use the right MAVLink version to enable all features
        // the vehicle supports
        _startPlanRequest();
1337
    }
1338
1339
}

Gus Grubba's avatar
Gus Grubba committed
1340
1341
1342
1343
1344
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
1345
1346
1347
1348
1349
1350
1351
1352
                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
1353
1354
1355
    return uid;
}

Bart Slinger's avatar
Bart Slinger committed
1356
1357
1358
1359
1360
1361
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
1362
1363
1364
1365
1366
1367
1368
1369
1370
1371
1372
1373
1374
1375
1376
1377
            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
1378
1379
}

1380
1381
void Vehicle::_handleCommandLong(mavlink_message_t& message)
{
1382
1383
#ifdef NO_SERIAL_LINK
    // If not using serial link, bail out.
DonLakeFlyer's avatar
DonLakeFlyer committed
1384
1385
    Q_UNUSED(message)
#else
1386
1387
1388
1389
    mavlink_command_long_t cmd;
    mavlink_msg_command_long_decode(&message, &cmd);

    switch (cmd.command) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1390
1391
1392
1393
1394
1395
1396
1397
1398
1399
    // 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
1400
                    emit linksChanged();
1401
1402
                }
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
1403
        }
1404
1405
        break;
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1406
#endif
1407
1408
}

Don Gagne's avatar
Don Gagne committed
1409
1410
1411
1412
1413
1414
1415
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:
1416
1417
        _setFlying(false);
        _setLanding(false);
Don Gagne's avatar
Don Gagne committed
1418
        break;
1419
    case MAV_LANDED_STATE_TAKEOFF:
Don Gagne's avatar
Don Gagne committed
1420
    case MAV_LANDED_STATE_IN_AIR:
1421
1422
1423
1424
1425
1426
1427
1428
1429
        _setFlying(true);
        _setLanding(false);
        break;
    case MAV_LANDED_STATE_LANDING:
        _setFlying(true);
        _setLanding(true);
        break;
    default:
        break;
Don Gagne's avatar
Don Gagne committed
1430
    }
Don Gagne's avatar
Don Gagne committed
1431
1432

    if (vtol()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1433
1434
1435
1436
1437
        bool vtolInFwdFlight = extendedState.vtol_state == MAV_VTOL_STATE_FW;
        if (vtolInFwdFlight != _vtolInFwdFlight) {
            _vtolInFwdFlight = vtolInFwdFlight;
            emit vtolInFwdFlightChanged(vtolInFwdFlight);
        }
Don Gagne's avatar
Don Gagne committed
1438
    }
Don Gagne's avatar
Don Gagne committed
1439
1440
}

Don Gagne's avatar
Don Gagne committed
1441
1442
1443
1444
1445
1446
1447
1448
1449
1450
1451
1452
1453
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);
}

1454
1455
1456
1457
1458
1459
1460
1461
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
1462
1463
1464
1465
    if (direction < 0) {
        direction += 360;
    }

1466
1467
1468
1469
1470
    _windFactGroup.direction()->setRawValue(direction);
    _windFactGroup.speed()->setRawValue(speed);
    _windFactGroup.verticalSpeed()->setRawValue(0);
}

1471
#if !defined(NO_ARDUPILOT_DIALECT)
Don Gagne's avatar
Don Gagne committed
1472
1473
1474
1475
1476
void Vehicle::_handleWind(mavlink_message_t& message)
{
    mavlink_wind_t wind;
    mavlink_msg_wind_decode(&message, &wind);

1477
1478
1479
1480
1481
1482
    // 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
1483
1484
1485
    _windFactGroup.speed()->setRawValue(wind.speed);
    _windFactGroup.verticalSpeed()->setRawValue(wind.speed_z);
}
1486
#endif
Don Gagne's avatar
Don Gagne committed
1487

DonLakeFlyer's avatar
DonLakeFlyer committed
1488
1489
1490
1491
1492
1493
1494
bool Vehicle::_apmArmingNotRequired(void)
{
    QString armingRequireParam("ARMING_REQUIRE");
    return _parameterManager->parameterExists(FactSystem::defaultComponentId, armingRequireParam) &&
            _parameterManager->getParameter(FactSystem::defaultComponentId, armingRequireParam)->rawValue().toInt() == 0;
}

Don Gagne's avatar
Don Gagne committed
1495
1496
1497
1498
1499
1500
void Vehicle::_handleSysStatus(mavlink_message_t& message)
{
    mavlink_sys_status_t sysStatus;
    mavlink_msg_sys_status_decode(&message, &sysStatus);

    if (sysStatus.current_battery == -1) {
DonLakeFlyer's avatar
comit    
DonLakeFlyer committed
1501
        _battery1FactGroup.current()->setRawValue(VehicleBatteryFactGroup::_currentUnavailable);
Don Gagne's avatar
Don Gagne committed
1502
    } else {
1503
        // Current is in Amps, current_battery is 10 * milliamperes (1 = 10 milliampere)
DonLakeFlyer's avatar
comit    
DonLakeFlyer committed
1504
        _battery1FactGroup.current()->setRawValue((float)sysStatus.current_battery / 100.0f);
Don Gagne's avatar
Don Gagne committed
1505
1506
    }
    if (sysStatus.voltage_battery == UINT16_MAX) {
DonLakeFlyer's avatar
comit    
DonLakeFlyer committed
1507
        _battery1FactGroup.voltage()->setRawValue(VehicleBatteryFactGroup::_voltageUnavailable);
Don Gagne's avatar
Don Gagne committed
1508
    } else {
DonLakeFlyer's avatar
comit    
DonLakeFlyer committed
1509
        _battery1FactGroup.voltage()->setRawValue((double)sysStatus.voltage_battery / 1000.0);
1510
        // current_battery is 10 mA and voltage_battery is 1mV. (10/1e3 times 1/1e3 = 1/1e5)
DonLakeFlyer's avatar
comit    
DonLakeFlyer committed
1511
        _battery1FactGroup.instantPower()->setRawValue((float)(sysStatus.current_battery*sysStatus.voltage_battery)/(100000.0));
Don Gagne's avatar
Don Gagne committed
1512
    }
DonLakeFlyer's avatar
comit    
DonLakeFlyer committed
1513
    _battery1FactGroup.percentRemaining()->setRawValue(sysStatus.battery_remaining);
Don Gagne's avatar
Don Gagne committed
1514

1515
1516
1517
    if (sysStatus.battery_remaining > 0) {
        if (sysStatus.battery_remaining < _settingsManager->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toInt() &&
                sysStatus.battery_remaining < _lastAnnouncedLowBatteryPercent) {
1518
            _say(QString(tr("%1 low battery: %2 percent remaining")).arg(_vehicleIdSpeech()).arg(sysStatus.battery_remaining));
1519
        }
1520
        _lastAnnouncedLowBatteryPercent = sysStatus.battery_remaining;
Don Gagne's avatar
Don Gagne committed
1521
    }
1522

DonLakeFlyer's avatar
DonLakeFlyer committed
1523
1524
1525
1526
1527
1528
1529
1530
1531
1532
1533
1534
    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);
    }
1535

DonLakeFlyer's avatar
DonLakeFlyer committed
1536
1537
1538
1539
1540
1541
    // 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);
    }
1542
1543
1544
1545
1546

    uint32_t newSensorsUnhealthy = _onboardControlSensorsEnabled & ~_onboardControlSensorsHealth;
    if (newSensorsUnhealthy != _onboardControlSensorsUnhealthy) {
        _onboardControlSensorsUnhealthy = newSensorsUnhealthy;
        emit unhealthySensorsChanged();
DonLakeFlyer's avatar
DonLakeFlyer committed
1547
        emit sensorsUnhealthyBitsChanged(_onboardControlSensorsUnhealthy);
1548
    }
Don Gagne's avatar
Don Gagne committed
1549
1550
1551
1552
1553
1554
1555
}

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1556
1557
    VehicleBatteryFactGroup& batteryFactGroup = bat_status.id == 0 ? _battery1FactGroup : _battery2FactGroup;

Don Gagne's avatar
Don Gagne committed
1558
    if (bat_status.temperature == INT16_MAX) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1559
        batteryFactGroup.temperature()->setRawValue(VehicleBatteryFactGroup::_temperatureUnavailable);
Don Gagne's avatar
Don Gagne committed
1560
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1561
        batteryFactGroup.temperature()->setRawValue((double)bat_status.temperature / 100.0);
Don Gagne's avatar
Don Gagne committed
1562
1563
    }
    if (bat_status.current_consumed == -1) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1564
        batteryFactGroup.mahConsumed()->setRawValue(VehicleBatteryFactGroup::_mahConsumedUnavailable);
Don Gagne's avatar
Don Gagne committed
1565
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1566
        batteryFactGroup.mahConsumed()->setRawValue(bat_status.current_consumed);
Don Gagne's avatar
Don Gagne committed
1567
1568
1569
1570
1571
1572
1573
1574
1575
1576
1577
1578
    }

    int cellCount = 0;
    for (int i=0; i<10; i++) {
        if (bat_status.voltages[i] != UINT16_MAX) {
            cellCount++;
        }
    }
    if (cellCount == 0) {
        cellCount = -1;
    }

DonLakeFlyer's avatar
DonLakeFlyer committed
1579
    batteryFactGroup.cellCount()->setRawValue(cellCount);
1580
1581

    //-- Time remaining in seconds (0 means not supported)
DonLakeFlyer's avatar
DonLakeFlyer committed
1582
    batteryFactGroup.timeRemaining()->setRawValue(bat_status.time_remaining);
1583
1584
    //-- Battery charge state (0 means not supported)
    if(bat_status.charge_state <= MAV_BATTERY_CHARGE_STATE_UNHEALTHY) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1585
        batteryFactGroup.chargeState()->setRawValue(bat_status.charge_state);
1586
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1587
        batteryFactGroup.chargeState()->setRawValue(0);
1588
1589
1590
1591
1592
1593
    }
    //-- TODO: Somewhere, actions would be taken based on this chargeState:
    //   MAV_BATTERY_CHARGE_STATE_CRITICAL:     Battery state is critical, return / abort immediately
    //   MAV_BATTERY_CHARGE_STATE_EMERGENCY:    Battery state is too low for ordinary abortion, fastest possible emergency stop preventing damage
    //   MAV_BATTERY_CHARGE_STATE_FAILED:       Battery failed, damage unavoidable
    //   MAV_BATTERY_CHARGE_STATE_UNHEALTHY:    Battery is diagnosed to be broken or an error occurred, usage is discouraged / prohibited
Don Gagne's avatar
Don Gagne committed
1594
1595
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1596
1597
1598
1599
1600
1601
1602
1603
void Vehicle::_setHomePosition(QGeoCoordinate& homeCoord)
{
    if (homeCoord != _homePosition) {
        _homePosition = homeCoord;
        emit homePositionChanged(_homePosition);
    }
}

Don Gagne's avatar
Don Gagne committed
1604
1605
1606
void Vehicle::_handleHomePosition(mavlink_message_t& message)
{
    mavlink_home_position_t homePos;
dogmaphobic's avatar
dogmaphobic committed
1607

Don Gagne's avatar
Don Gagne committed
1608
    mavlink_msg_home_position_decode(&message, &homePos);
Don Gagne's avatar
Don Gagne committed
1609
1610
1611
1612

    QGeoCoordinate newHomePosition (homePos.latitude / 10000000.0,
                                    homePos.longitude / 10000000.0,
                                    homePos.altitude / 1000.0);
DonLakeFlyer's avatar
DonLakeFlyer committed
1613
    _setHomePosition(newHomePosition);
Don Gagne's avatar
Don Gagne committed
1614
1615
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1616
void Vehicle::_updateArmed(bool armed)
Don Gagne's avatar
Don Gagne committed
1617
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1618
1619
    if (_armed != armed) {
        _armed = armed;
Don Gagne's avatar
Don Gagne committed
1620
        emit armedChanged(_armed);
dogmaphobic's avatar
dogmaphobic committed
1621

Don Gagne's avatar
Don Gagne committed
1622
1623
1624
        // We are transitioning to the armed state, begin tracking trajectory points for the map
        if (_armed) {
            _mapTrajectoryStart();
1625
            _clearCameraTriggerPoints();
Don Gagne's avatar
Don Gagne committed
1626
1627
        } else {
            _mapTrajectoryStop();
1628
1629
1630
1631
1632
            // Also handle Video Streaming
            if(_settingsManager->videoSettings()->disableWhenDisarmed()->rawValue().toBool()) {
                _settingsManager->videoSettings()->streamEnabled()->setRawValue(false);
                qgcApp()->toolbox()->videoManager()->videoReceiver()->stop();
            }
Don Gagne's avatar
Don Gagne committed
1633
        }
Don Gagne's avatar
Don Gagne committed
1634
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1635
1636
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1637
1638
1639
1640
1641
1642
1643
1644
1645
1646
1647
1648
1649
1650
1651
1652
1653
void Vehicle::_handlePing(LinkInterface* link, mavlink_message_t& message)
{
    mavlink_ping_t      ping;
    mavlink_message_t   msg;

    mavlink_msg_ping_decode(&message, &ping);
    mavlink_msg_ping_pack_chan(_mavlink->getSystemId(),
                               _mavlink->getComponentId(),
                               priorityLink()->mavlinkChannel(),
                               &msg,
                               ping.time_usec,
                               ping.seq,
                               message.sysid,
                               message.compid);
    sendMessageOnLink(link, msg);
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1654
1655
1656
1657
1658
1659
1660
1661
1662
1663
1664
1665
1666
1667
1668
1669
1670
1671
1672
1673
1674
1675
1676
1677
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
1678
1679

    if (heartbeat.base_mode != _base_mode || heartbeat.custom_mode != _custom_mode) {
1680
1681
1682
1683
1684
1685
        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();
        }
Don Gagne's avatar
Don Gagne committed
1686
1687
        _base_mode = heartbeat.base_mode;
        _custom_mode = heartbeat.custom_mode;
1688
1689
1690
        if (previousFlightMode != flightMode()) {
            emit flightModeChanged(flightMode());
        }
Don Gagne's avatar
Don Gagne committed
1691
1692
1693
    }
}

1694
1695
void Vehicle::_handleRadioStatus(mavlink_message_t& message)
{
1696

1697
1698
1699
    //-- Process telemetry status message
    mavlink_radio_status_t rstatus;
    mavlink_msg_radio_status_decode(&message, &rstatus);
1700

1701
1702
    int rssi    = rstatus.rssi;
    int remrssi = rstatus.remrssi;
1703
1704
    int lnoise = (int)(int8_t)rstatus.noise;
    int rnoise = (int)(int8_t)rstatus.remnoise;
1705
1706
1707
1708
1709
1710
1711
1712
1713
1714
1715
1716
1717
1718
    //-- 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);
1719
1720
1721
    } else {
        rssi    = (int)(int8_t)rstatus.rssi;
        remrssi = (int)(int8_t)rstatus.remrssi;
1722
1723
1724
1725
1726
1727
1728
1729
1730
1731
1732
1733
1734
1735
1736
1737
1738
1739
1740
1741
1742
1743
    }
    //-- 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);
    }
1744
1745
    if(_telemetryLNoise != lnoise) {
        _telemetryLNoise = lnoise;
1746
1747
        emit telemetryLNoiseChanged(_telemetryLNoise);
    }
1748
1749
    if(_telemetryRNoise != rnoise) {
        _telemetryRNoise = rnoise;
1750
1751
1752
1753
        emit telemetryRNoiseChanged(_telemetryRNoise);
    }
}

Don Gagne's avatar
Don Gagne committed
1754
1755
1756
1757
1758
1759
1760
1761
1762
1763
1764
1765
1766
1767
1768
1769
1770
1771
1772
1773
1774
1775
1776
1777
1778
1779
1780
1781
1782
1783
1784
1785
1786
1787
1788
1789
1790
1791
1792
1793
1794
1795
1796
1797
1798
1799
1800
1801
1802
1803
1804
1805
1806
1807
1808
1809
1810
1811
1812
1813
1814
1815
1816
1817
1818
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
1819
1820
1821
1822
    for (int i=0; i<cMaxRcChannels; i++) {
        pwmValues[i] = -1;
    }

Don Gagne's avatar
Don Gagne committed
1823
1824
1825
1826
1827
1828
    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
1829
            channelCount = i + 1;
Don Gagne's avatar
Don Gagne committed
1830
1831
1832
1833
1834
1835
1836
1837
1838
1839
1840
            pwmValues[i] = channelValue;
        }
    }
    for (int i=9; i<18; i++) {
        pwmValues[i] = -1;
    }

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

1841
1842
1843
1844
1845
1846
1847
1848
1849
1850
1851
1852
1853
1854
1855
1856
1857
1858
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);
}

1859
1860
bool Vehicle::_containsLink(LinkInterface* link)
{
Don Gagne's avatar
Don Gagne committed
1861
    return _links.contains(link);
1862
1863
1864
1865
1866
1867
}

void Vehicle::_addLink(LinkInterface* link)
{
    if (!_containsLink(link)) {
        qCDebug(VehicleLog) << "_addLink:" << QString("%1").arg((ulong)link, 0, 16);
1868
        _links += link;
1869
        if (_links.count() <= 1) {
acfloria's avatar
acfloria committed
1870
            _updatePriorityLink(true /* updateActive */, false /* sendCommand */);
1871
        } else {
acfloria's avatar
acfloria committed
1872
            _updatePriorityLink(true /* updateActive */, true /* sendCommand */);
1873
1874
        }

1875
1876
        connect(_toolbox->linkManager(), &LinkManager::linkInactive, this, &Vehicle::_linkInactiveOrDeleted);
        connect(_toolbox->linkManager(), &LinkManager::linkDeleted, this, &Vehicle::_linkInactiveOrDeleted);
Don Gagne's avatar
Don Gagne committed
1877
        connect(link, &LinkInterface::highLatencyChanged, this, &Vehicle::_updateHighLatencyLink);
1878
        connect(link, &LinkInterface::activeChanged, this, &Vehicle::_linkActiveChanged);
1879
1880
1881
    }
}

Don Gagne's avatar
Don Gagne committed
1882
void Vehicle::_linkInactiveOrDeleted(LinkInterface* link)
1883
{
Don Gagne's avatar
Don Gagne committed
1884
    qCDebug(VehicleLog) << "_linkInactiveOrDeleted linkCount" << _links.count();
dogmaphobic's avatar
dogmaphobic committed
1885

Don Gagne's avatar
Don Gagne committed
1886
    _links.removeOne(link);
1887
1888
1889
1890
1891

    if (_priorityLink.data() == link) {
        _priorityLink.clear();
    }

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

Don Gagne's avatar
Don Gagne committed
1894
    if (_links.count() == 0 && !_allLinksInactiveSent) {
Don Gagne's avatar
Don Gagne committed
1895
        qCDebug(VehicleLog) << "All links inactive";
Don Gagne's avatar
Don Gagne committed
1896
1897
1898
        // Make sure to not send this more than one time
        _allLinksInactiveSent = true;
        emit allLinksInactive(this);
1899
1900
1901
    }
}

1902
1903
1904
1905
1906
1907
1908
1909
1910
1911
1912
1913
1914
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)
{
1915
1916
1917
1918
1919
    // Make sure this is still a good link
    if (!link || !_links.contains(link) || !link->isConnected()) {
        return;
    }

Don Gagne's avatar
Don Gagne committed
1920
1921
1922
1923
1924
1925
#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

1926
    // Give the plugin a chance to adjust
1927
    _firmwarePlugin->adjustOutgoingMavlinkMessage(this, link, &message);
Don Gagne's avatar
Don Gagne committed
1928
1929
1930
1931
1932
1933

    // 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);
1934
1935
    _messagesSent++;
    emit messagesSentChanged();
1936
1937
}

1938
void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand)
1939
{
acfloria's avatar
acfloria committed
1940
    emit linksPropertiesChanged();
1941
1942
1943

    // if the priority link is commanded and still active don't change anything
    if (_priorityLinkCommanded) {
acfloria's avatar
acfloria committed
1944
        if (_priorityLink.data()->link_active(_id)) {
1945
1946
1947
1948
1949
1950
            return;
        } else {
            _priorityLinkCommanded = false;
        }
    }

1951
    LinkInterface* newPriorityLink = nullptr;
1952

1953
    // This routine specifically does not clear _priorityLink when there are no links remaining.
1954
    // By doing this we hold a reference on the last link as the Vehicle shuts down. Thus preventing shutdown
1955
    // ordering nullptr pointer crashes where priorityLink() is still called during shutdown sequence.
1956
1957
1958
1959
1960
1961
1962
    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
1963
            if (!_priorityLink.data()->highLatency() && _priorityLink->link_active(_id)) {
1964
1965
1966
1967
                // 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;
            }
1968
1969
1970
1971
        }
    }

    // The previous priority link is no longer valid. We must no find the best link available in this priority order:
1972
1973
1974
    //      First active direct USB connection
    //      Any active non high latency link
    //      An active high latency link
1975
1976
1977
    //      Any link

#ifndef NO_SERIAL_LINK
1978
    // Search for an active direct usb connection
1979
1980
    for (int i=0; i<_links.count(); i++) {
        LinkInterface* link = _links[i];
1981
1982
1983
1984
1985
1986
        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
1987
                    if (_priorityLink.data() != link && link->link_active(_id)) {
1988
1989
                        newPriorityLink = link;
                        break;
1990
1991
1992
                    }
                }
            }
1993
1994
        }
    }
1995
#endif
1996

1997
    if (!newPriorityLink) {
1998
        // Search for an active non-high latency link
1999
2000
        for (int i=0; i<_links.count(); i++) {
            LinkInterface* link = _links[i];
acfloria's avatar
acfloria committed
2001
            if (!link->highLatency() && link->link_active(_id)) {
2002
2003
2004
2005
2006
2007
2008
2009
                newPriorityLink = link;
                break;
            }
        }
    }

    if (!newPriorityLink) {
        // Search for an active high latency link
2010
2011
        for (int i=0; i<_links.count(); i++) {
            LinkInterface* link = _links[i];
acfloria's avatar
acfloria committed
2012
            if (link->highLatency() && link->link_active(_id)) {
2013
2014
2015
2016
                newPriorityLink = link;
                break;
            }
        }
2017
2018
    }

2019
2020
2021
    if (!newPriorityLink) {
        // Use any link
        newPriorityLink = _links[0];
2022
    }
2023

2024
    if (_priorityLink.data() != newPriorityLink) {
2025
2026
2027
        if (_priorityLink) {
            qgcApp()->showMessage((tr("switch to %2 as priority link")).arg(newPriorityLink->getName()));
        }
2028
        _priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink);
2029

2030
        _updateHighLatencyLink(sendCommand);
2031

2032
2033
        emit priorityLinkNameChanged(_priorityLink->getName());
        if (updateActive) {
acfloria's avatar
acfloria committed
2034
            _linkActiveChanged(_priorityLink.data(), _priorityLink->link_active(_id), _id);
2035
2036
        }
    }
2037
2038
}

Don Gagne's avatar
Don Gagne committed
2039
2040
2041
2042
2043
2044
2045
2046
2047
2048
2049
2050
2051
2052
2053
2054
int Vehicle::motorCount(void)
{
    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;
2055
2056
2057
2058
2059
2060
2061
2062
2063
2064
2065
2066
2067
2068
2069
2070
2071
2072
2073
2074
2075
2076
2077
2078
2079
2080
2081
2082
2083
2084
2085
2086
2087
2088
2089
2090
2091
2092
2093
2094
2095
    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
2096
2097
2098
2099
2100
2101
2102
2103
2104
2105
2106
2107
2108
2109
2110
    default:
        return -1;
    }
}

bool Vehicle::coaxialMotors(void)
{
    return _firmwarePlugin->multiRotorCoaxialMotors(this);
}

bool Vehicle::xConfigMotors(void)
{
    return _firmwarePlugin->multiRotorXConfig(this);
}

dogmaphobic's avatar
dogmaphobic committed
2111
2112
2113
QString Vehicle::formatedMessages()
{
    QString messages;
2114
    for(UASMessage* message: _toolbox->uasMessageHandler()->messages()) {
dogmaphobic's avatar
dogmaphobic committed
2115
2116
2117
2118
2119
        messages += message->getFormatedText();
    }
    return messages;
}

dogmaphobic's avatar
dogmaphobic committed
2120
2121
void Vehicle::clearMessages()
{
2122
    _toolbox->uasMessageHandler()->clearMessages();
dogmaphobic's avatar
dogmaphobic committed
2123
2124
}

dogmaphobic's avatar
dogmaphobic committed
2125
2126
2127
2128
2129
2130
2131
2132
2133
void Vehicle::_handletextMessageReceived(UASMessage* message)
{
    if(message)
    {
        _formatedMessage = message->getFormatedText();
        emit formatedMessageChanged();
    }
}

2134
2135
2136
2137
2138
2139
2140
2141
2142
2143
2144
2145
2146
2147
2148
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
2149

2150
    UASMessageHandler* pMh = _toolbox->uasMessageHandler();
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
2186
2187
2188
2189
2190
2191
2192
2193
2194
2195
2196
2197
2198
2199
2200
2201
2202
2203
2204
2205
2206
2207
2208
2209
2210
2211
2212
2213
2214
2215
    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();
    }
}
2216
2217
2218
2219
2220
2221
2222
2223

int Vehicle::manualControlReservedButtonCount(void)
{
    return _firmwarePlugin->manualControlReservedButtonCount();
}

void Vehicle::_loadSettings(void)
{
2224
2225
2226
2227
    if (!_active) {
        return;
    }

2228
    QSettings settings;
dogmaphobic's avatar
dogmaphobic committed
2229

2230
    settings.beginGroup(QString(_settingsGroup).arg(_id));
dogmaphobic's avatar
dogmaphobic committed
2231

2232
    bool convertOk;
dogmaphobic's avatar
dogmaphobic committed
2233

2234
2235
2236
2237
    _joystickMode = (JoystickMode_t)settings.value(_joystickModeSettingsKey, JoystickModeRC).toInt(&convertOk);
    if (!convertOk) {
        _joystickMode = JoystickModeRC;
    }
dogmaphobic's avatar
dogmaphobic committed
2238

2239
    // Joystick enabled is a global setting so first make sure there are any joysticks connected
2240
    if (_toolbox->joystickManager()->joysticks().count()) {
2241
        setJoystickEnabled(settings.value(_joystickEnabledSettingsKey, false).toBool());
2242
        _startJoystick(true);
2243
    }
2244
2245
2246
2247
2248
}

void Vehicle::_saveSettings(void)
{
    QSettings settings;
dogmaphobic's avatar
dogmaphobic committed
2249

2250
    settings.beginGroup(QString(_settingsGroup).arg(_id));
dogmaphobic's avatar
dogmaphobic committed
2251

2252
    settings.setValue(_joystickModeSettingsKey, _joystickMode);
2253
2254
2255

    // The joystick enabled setting should only be changed if a joystick is present
    // since the checkbox can only be clicked if one is present
2256
    if (_toolbox->joystickManager()->joysticks().count()) {
2257
2258
        settings.setValue(_joystickEnabledSettingsKey, _joystickEnabled);
    }
2259
2260
2261
2262
2263
2264
2265
2266
2267
2268
2269
2270
2271
}

int Vehicle::joystickMode(void)
{
    return _joystickMode;
}

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

2273
2274
2275
2276
2277
2278
2279
2280
    _joystickMode = (JoystickMode_t)mode;
    _saveSettings();
    emit joystickModeChanged(mode);
}

QStringList Vehicle::joystickModes(void)
{
    QStringList list;
dogmaphobic's avatar
dogmaphobic committed
2281

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

2284
2285
    return list;
}
Don Gagne's avatar
Don Gagne committed
2286
2287
2288
2289
2290
2291
2292
2293

bool Vehicle::joystickEnabled(void)
{
    return _joystickEnabled;
}

void Vehicle::setJoystickEnabled(bool enabled)
{
2294
    _joystickEnabled = enabled;
Don Gagne's avatar
Don Gagne committed
2295
    _saveSettings();
2296
    emit joystickEnabledChanged(_joystickEnabled);
Don Gagne's avatar
Don Gagne committed
2297
2298
2299
2300
}

void Vehicle::_startJoystick(bool start)
{
2301
    Joystick* joystick = _joystickManager->activeJoystick();
Don Gagne's avatar
Don Gagne committed
2302
2303
    if (joystick) {
        if (start) {
2304
            joystick->startPolling(this);
Don Gagne's avatar
Don Gagne committed
2305
2306
2307
2308
2309
2310
2311
2312
2313
2314
2315
2316
2317
        } else {
            joystick->stopPolling();
        }
    }
}

bool Vehicle::active(void)
{
    return _active;
}

void Vehicle::setActive(bool active)
{
2318
2319
    if (_active != active) {
        _active = active;
2320
        _startJoystick(false);
2321
2322
        emit activeChanged(_active);
    }
Don Gagne's avatar
Don Gagne committed
2323
}
2324

Don Gagne's avatar
Don Gagne committed
2325
2326
2327
2328
QGeoCoordinate Vehicle::homePosition(void)
{
    return _homePosition;
}
Don Gagne's avatar
Don Gagne committed
2329
2330
2331
2332

void Vehicle::setArmed(bool armed)
{
    // We specifically use COMMAND_LONG:MAV_CMD_COMPONENT_ARM_DISARM since it is supported by more flight stacks.
2333
    sendMavCommand(_defaultComponentId,
2334
2335
2336
                   MAV_CMD_COMPONENT_ARM_DISARM,
                   true,    // show error if fails
                   armed ? 1.0f : 0.0f);
Don Gagne's avatar
Don Gagne committed
2337
2338
2339
2340
}

bool Vehicle::flightModeSetAvailable(void)
{
2341
    return _firmwarePlugin->isCapable(this, FirmwarePlugin::SetFlightModeCapability);
Don Gagne's avatar
Don Gagne committed
2342
2343
2344
2345
}

QStringList Vehicle::flightModes(void)
{
Daniel Agar's avatar
Daniel Agar committed
2346
    return _firmwarePlugin->flightModes(this);
Don Gagne's avatar
Don Gagne committed
2347
2348
}

Don Gagne's avatar
Don Gagne committed
2349
QString Vehicle::flightMode(void) const
Don Gagne's avatar
Don Gagne committed
2350
2351
2352
2353
2354
2355
2356
2357
2358
2359
2360
2361
2362
2363
2364
2365
{
    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;
2366
2367
2368
2369
2370
2371
2372
2373
        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
2374
    } else {
Don Gagne's avatar
Don Gagne committed
2375
        qWarning() << "FirmwarePlugin::setFlightMode failed, flightMode:" << flightMode;
Don Gagne's avatar
Don Gagne committed
2376
2377
2378
    }
}

2379
2380
QString Vehicle::priorityLinkName(void) const
{
2381
    if (_priorityLink) {
2382
        return _priorityLink->getName();
2383
2384
2385
    }

    return "none";
2386
2387
}

acfloria's avatar
acfloria committed
2388
2389
2390
QVariantList Vehicle::links(void) const {
    QVariantList ret;

2391
    for( const auto &item: _links )
acfloria's avatar
acfloria committed
2392
2393
2394
2395
2396
        ret << QVariant::fromValue(item);

    return ret;
}

2397
2398
void Vehicle::setPriorityLinkByName(const QString& priorityLinkName)
{
2399
2400
2401
2402
    if (!_priorityLink) {
        return;
    }

2403
2404
2405
2406
2407
    if (priorityLinkName == _priorityLink->getName()) {
        // The link did not change
        return;
    }

2408
    LinkInterface* newPriorityLink = nullptr;
2409
2410
2411
2412
2413
2414
2415
2416
2417


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

    if (newPriorityLink) {
2418
        _priorityLinkCommanded = true;
2419
        _priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink);
2420
        _updateHighLatencyLink(true);
2421
        emit priorityLinkNameChanged(_priorityLink->getName());
acfloria's avatar
acfloria committed
2422
        _linkActiveChanged(_priorityLink.data(), _priorityLink->link_active(_id), _id);
2423
2424
2425
    }
}

Don Gagne's avatar
Don Gagne committed
2426
2427
2428
2429
2430
2431
2432
2433
2434
2435
2436
2437
2438
2439
bool Vehicle::hilMode(void)
{
    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;
    }

2440
2441
2442
2443
2444
2445
2446
2447
    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
2448
}
2449

Don Gagne's avatar
Don Gagne committed
2450
void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple)
2451
2452
2453
{
    mavlink_message_t               msg;
    mavlink_request_data_stream_t   dataStream;
dogmaphobic's avatar
dogmaphobic committed
2454

Don Gagne's avatar
Don Gagne committed
2455
2456
    memset(&dataStream, 0, sizeof(dataStream));

2457
2458
2459
2460
    dataStream.req_stream_id = stream;
    dataStream.req_message_rate = rate;
    dataStream.start_stop = 1;  // start
    dataStream.target_system = id();
2461
    dataStream.target_component = _defaultComponentId;
dogmaphobic's avatar
dogmaphobic committed
2462

2463
2464
2465
2466
2467
    mavlink_msg_request_data_stream_encode_chan(_mavlink->getSystemId(),
                                                _mavlink->getComponentId(),
                                                priorityLink()->mavlinkChannel(),
                                                &msg,
                                                &dataStream);
2468

Don Gagne's avatar
Don Gagne committed
2469
2470
2471
2472
    if (sendMultiple) {
        // We use sendMessageMultiple since we really want these to make it to the vehicle
        sendMessageMultiple(msg);
    } else {
2473
        sendMessageOnLink(priorityLink(), msg);
Don Gagne's avatar
Don Gagne committed
2474
    }
2475
2476
2477
2478
2479
2480
}

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

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

2484
2485
2486
2487
2488
2489
        if (--_sendMessageMultipleList[_nextSendMessageMultipleIndex].retryCount <= 0) {
            _sendMessageMultipleList.removeAt(_nextSendMessageMultipleIndex);
        } else {
            _nextSendMessageMultipleIndex++;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
2490

2491
2492
2493
2494
2495
2496
2497
2498
    if (_nextSendMessageMultipleIndex >= _sendMessageMultipleList.count()) {
        _nextSendMessageMultipleIndex = 0;
    }
}

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

2500
2501
    info.message =      message;
    info.retryCount =   _sendMessageMultipleRetries;
dogmaphobic's avatar
dogmaphobic committed
2502

2503
2504
    _sendMessageMultipleList.append(info);
}
2505
2506
2507
2508

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

Don Gagne's avatar
Don Gagne committed
2512
2513
2514
void Vehicle::_geoFenceManagerError(int errorCode, const QString& errorMsg)
{
    Q_UNUSED(errorCode);
DonLakeFlyer's avatar
DonLakeFlyer committed
2515
    qgcApp()->showMessage(tr("GeoFence transfer failed. Retry transfer. Error: %1").arg(errorMsg));
2516
2517
2518
2519
2520
}

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

Don Gagne's avatar
Don Gagne committed
2524
2525
2526
void Vehicle::_addNewMapTrajectoryPoint(void)
{
    if (_mapTrajectoryHaveFirstCoordinate) {
Don Gagne's avatar
Don Gagne committed
2527
2528
        // Keep three minutes of trajectory on mobile due to perf impact of lines
#ifdef __mobile__
2529
2530
2531
        if (_mapTrajectoryList.count() * _mapTrajectoryMsecsBetweenPoints > 3 * 1000 * 60) {
            _mapTrajectoryList.removeAt(0)->deleteLater();
        }
Don Gagne's avatar
Don Gagne committed
2532
#endif
2533
        _mapTrajectoryList.append(new CoordinateVector(_mapTrajectoryLastCoordinate, _coordinate, this));
2534
        _flightDistanceFact.setRawValue(_flightDistanceFact.rawValue().toDouble() + _mapTrajectoryLastCoordinate.distanceTo(_coordinate));
Don Gagne's avatar
Don Gagne committed
2535
2536
    }
    _mapTrajectoryHaveFirstCoordinate = true;
2537
    _mapTrajectoryLastCoordinate = _coordinate;
2538
    _flightTimeFact.setRawValue((double)_flightTimer.elapsed() / 1000.0);
Don Gagne's avatar
Don Gagne committed
2539
2540
}

2541
2542
2543
2544
2545
2546
2547
2548
void Vehicle::_clearTrajectoryPoints(void)
{
    _mapTrajectoryList.clearAndDeleteContents();
}

void Vehicle::_clearCameraTriggerPoints(void)
{
    _cameraTriggerPoints.clearAndDeleteContents();
Don Gagne's avatar
Don Gagne committed
2549
2550
2551
2552
2553
}

void Vehicle::_mapTrajectoryStart(void)
{
    _mapTrajectoryHaveFirstCoordinate = false;
2554
    _clearTrajectoryPoints();
Don Gagne's avatar
Don Gagne committed
2555
    _mapTrajectoryTimer.start();
2556
    _flightTimer.start();
2557
    _flightDistanceFact.setRawValue(0);
2558
    _flightTimeFact.setRawValue(0);
Don Gagne's avatar
Don Gagne committed
2559
2560
2561
2562
2563
2564
}

void Vehicle::_mapTrajectoryStop()
{
    _mapTrajectoryTimer.stop();
}
2565

DonLakeFlyer's avatar
DonLakeFlyer committed
2566
void Vehicle::_startPlanRequest(void)
2567
{
DonLakeFlyer's avatar
DonLakeFlyer committed
2568
2569
2570
2571
2572
    if (_missionManagerInitialRequestSent) {
        return;
    }

    if (_parameterManager->parametersReady() && _vehicleCapabilitiesKnown) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2573
        qCDebug(VehicleLog) << "_startPlanRequest";
2574
        _missionManagerInitialRequestSent = true;
2575
2576
2577
2578
        if (_settingsManager->appSettings()->autoLoadMissions()->rawValue().toBool()) {
            QString missionAutoLoadDirPath = _settingsManager->appSettings()->missionSavePath();
            if (!missionAutoLoadDirPath.isEmpty()) {
                QDir missionAutoLoadDir(missionAutoLoadDirPath);
2579
2580
                QString autoloadFilename = missionAutoLoadDir.absoluteFilePath(tr("AutoLoad%1.%2").arg(_id).arg(AppSettings::planFileExtension));
                if (QFile(autoloadFilename).exists()) {
2581
                    _initialPlanRequestComplete = true; // We aren't going to load from the vehicle, so we are done
2582
                    PlanMasterController::sendPlanToVehicle(this, autoloadFilename);
2583
2584
                    return;
                }
Don Gagne's avatar
Don Gagne committed
2585
2586
            }
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
2587
        _missionManager->loadFromVehicle();
2588
2589
    } else {
        if (!_parameterManager->parametersReady()) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2590
            qCDebug(VehicleLog) << "Delaying _startPlanRequest due to parameters not ready";
2591
        } else if (!_vehicleCapabilitiesKnown) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2592
            qCDebug(VehicleLog) << "Delaying _startPlanRequest due to vehicle capabilities not known";
2593
2594
2595
2596
        }
    }
}

DonLakeFlyer's avatar
DonLakeFlyer committed
2597
2598
2599
2600
2601
void Vehicle::_missionLoadComplete(void)
{
    // After the initial mission request completes we ask for the geofence
    if (!_geoFenceManagerInitialRequestSent) {
        _geoFenceManagerInitialRequestSent = true;
2602
2603
2604
2605
2606
2607
2608
        if (_geoFenceManager->supported()) {
            qCDebug(VehicleLog) << "_missionLoadComplete requesting GeoFence";
            _geoFenceManager->loadFromVehicle();
        } else {
            qCDebug(VehicleLog) << "_missionLoadComplete GeoFence not supported skipping";
            _geoFenceLoadComplete();
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
2609
2610
2611
2612
2613
2614
2615
2616
    }
}

void Vehicle::_geoFenceLoadComplete(void)
{
    // After geofence request completes we ask for the rally points
    if (!_rallyPointManagerInitialRequestSent) {
        _rallyPointManagerInitialRequestSent = true;
2617
2618
2619
2620
2621
2622
2623
        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
2624
2625
2626
2627
2628
    }
}

void Vehicle::_rallyPointLoadComplete(void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
2629
    qCDebug(VehicleLog) << "_missionLoadComplete _initialPlanRequestComplete = true";
2630
2631
    if (!_initialPlanRequestComplete) {
        _initialPlanRequestComplete = true;
Don Gagne's avatar
Don Gagne committed
2632
        emit initialPlanRequestCompleteChanged(true);
2633
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2634
2635
}

2636
2637
void Vehicle::_parametersReady(bool parametersReady)
{
2638
2639
2640
2641
    // 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();
2642
    if (parametersReady) {
2643
        _setupAutoDisarmSignalling();
DonLakeFlyer's avatar
DonLakeFlyer committed
2644
        _startPlanRequest();
Lorenz Meier's avatar
Lorenz Meier committed
2645
    }
2646
}
2647

2648
2649
2650
2651
2652
2653
2654
2655
2656
2657
void Vehicle::_sendQGCTimeToVehicle(void)
{
    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(),
2658
2659
2660
2661
                                        _mavlink->getComponentId(),
                                        priorityLink()->mavlinkChannel(),
                                        &msg,
                                        &cmd);
2662
2663
2664
2665

    sendMessageOnLink(priorityLink(), msg);
}

Don Gagne's avatar
Don Gagne committed
2666
void Vehicle::disconnectInactiveVehicle(void)
2667
{
Don Gagne's avatar
Don Gagne committed
2668
    // Vehicle is no longer communicating with us, disconnect all links
2669

2670
    LinkManager* linkMgr = _toolbox->linkManager();
2671
    for (int i=0; i<_links.count(); i++) {
2672
2673
        // 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.
2674
        if (!_toolbox->multiVehicleManager()->linkInUse(_links[i], this)) {
2675
2676
            linkMgr->disconnectLink(_links[i]);
        }
2677
    }
acfloria's avatar
acfloria committed
2678
    emit linksChanged();
2679
}
2680

dogmaphobic's avatar
dogmaphobic committed
2681
2682
2683
2684
2685
void Vehicle::_imageReady(UASInterface*)
{
    if(_uas)
    {
        QImage img = _uas->getImage();
2686
        _toolbox->imageProvider()->setImage(&img, _id);
dogmaphobic's avatar
dogmaphobic committed
2687
2688
2689
2690
        _flowImageIndex++;
        emit flowImageIndexChanged();
    }
}
Don Gagne's avatar
Don Gagne committed
2691
2692
2693

void Vehicle::_remoteControlRSSIChanged(uint8_t rssi)
{
2694
2695
2696
2697
2698
2699
2700
2701
2702
2703
2704
    //-- 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;
2705
    }
Don Gagne's avatar
Don Gagne committed
2706
2707
2708
2709
2710
2711
2712
2713
2714
2715
2716
    // 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
2717
2718
2719

void Vehicle::virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust)
{
2720
    // The following if statement prevents the virtualTabletJoystick from sending values if the standard joystick is enabled
2721
    if ( !_joystickEnabled && !_highLatencyLink) {
2722
2723
        _uas->setExternalControlSetpoint(roll, pitch, yaw, thrust, 0, JoystickModeRC);
    }
Don Gagne's avatar
Don Gagne committed
2724
}
2725
2726
2727
2728
2729
2730
2731
2732
2733

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

2734
void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID)
2735
{
2736
2737
    // only continue if the vehicle id is correct
    if (vehicleID != _id) {
2738
2739
2740
        return;
    }

acfloria's avatar
acfloria committed
2741
    emit linksPropertiesChanged();
2742

2743
2744
2745
    bool communicationLost = false;
    bool communicationRegained = false;

2746
2747
2748
2749
    if (link == _priorityLink) {
        if (active && _connectionLost) {
            // communication to priority link regained
            _connectionLost = false;
2750
            communicationRegained = true;
2751
            emit connectionLostChanged(false);
2752

2753
2754
2755
2756
2757
2758
2759
2760
            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
2761
            }
2762
        } else if (!active && !_connectionLost) {
2763
            _updatePriorityLink(false /* updateActive */, false /* sendCommand */);
2764

2765
            // check if another active link has been found
2766
            if (link == _priorityLink) {
2767
2768
2769
2770
2771
2772
2773
2774
2775
2776
                _connectionLost = true;
                communicationLost = true;
                _heardFrom = false;
                _maxProtoVersion = 0;
                emit connectionLostChanged(true);

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

                    disconnectInactiveVehicle();
2780
2781
2782
2783
                }
            }
        }
    } else {
2784
        qgcApp()->showMessage((tr("%1 communication to auxiliary link %2 %3")).arg(_vehicleIdSpeech()).arg(link->getName()).arg(active ? "regained" : "lost"));
acfloria's avatar
acfloria committed
2785
        _updatePriorityLink(false /* updateActive */, true /* sendCommand */);
2786
    }
2787
2788
2789
2790
2791
2792
2793
2794
2795
2796
2797
2798
2799
2800
2801
2802
2803
2804
2805
2806
2807
2808
2809
2810
2811

    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);
    }
2812
2813
}

Don Gagne's avatar
Don Gagne committed
2814
void Vehicle::_say(const QString& text)
2815
{
2816
    _toolbox->audioOutput()->say(text.toLower());
2817
}
2818
2819
2820

bool Vehicle::fixedWing(void) const
{
2821
    return QGCMAVLink::isFixedWing(vehicleType());
2822
2823
}

Don Gagne's avatar
Don Gagne committed
2824
2825
bool Vehicle::rover(void) const
{
2826
    return QGCMAVLink::isRover(vehicleType());
Don Gagne's avatar
Don Gagne committed
2827
2828
}

2829
2830
bool Vehicle::sub(void) const
{
2831
    return QGCMAVLink::isSub(vehicleType());
2832
2833
}

2834
2835
bool Vehicle::multiRotor(void) const
{
2836
    return QGCMAVLink::isMultiRotor(vehicleType());
2837
}
Don Gagne's avatar
Don Gagne committed
2838

Don Gagne's avatar
Don Gagne committed
2839
2840
bool Vehicle::vtol(void) const
{
2841
    return _firmwarePlugin->isVtol(this);
Don Gagne's avatar
Don Gagne committed
2842
2843
}

2844
2845
2846
2847
2848
bool Vehicle::supportsThrottleModeCenterZero(void) const
{
    return _firmwarePlugin->supportsThrottleModeCenterZero();
}

2849
2850
2851
2852
2853
bool Vehicle::supportsNegativeThrust(void) const
{
    return _firmwarePlugin->supportsNegativeThrust();
}

2854
2855
2856
2857
2858
bool Vehicle::supportsRadio(void) const
{
    return _firmwarePlugin->supportsRadio();
}

2859
2860
2861
2862
2863
bool Vehicle::supportsJSButton(void) const
{
    return _firmwarePlugin->supportsJSButton();
}

Jacob Walser's avatar
Jacob Walser committed
2864
2865
2866
2867
2868
bool Vehicle::supportsMotorInterference(void) const
{
    return _firmwarePlugin->supportsMotorInterference();
}

2869
2870
2871
2872
2873
bool Vehicle::supportsTerrainFrame(void) const
{
    return _firmwarePlugin->supportsTerrainFrame();
}

2874
2875
2876
2877
2878
2879
2880
2881
2882
2883
2884
2885
2886
2887
2888
2889
2890
2891
2892
2893
2894
2895
2896
2897
2898
2899
2900
2901
2902
2903
2904
2905
2906
2907
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
2908
2909
2910
/// Returns the string to speak to identify the vehicle
QString Vehicle::_vehicleIdSpeech(void)
{
2911
    if (_toolbox->multiVehicleManager()->vehicles()->count() > 1) {
2912
        return QString(tr("vehicle %1")).arg(id());
Don Gagne's avatar
Don Gagne committed
2913
    } else {
2914
        return QString();
Don Gagne's avatar
Don Gagne committed
2915
2916
2917
    }
}

Don Gagne's avatar
Don Gagne committed
2918
void Vehicle::_handleFlightModeChanged(const QString& flightMode)
Don Gagne's avatar
Don Gagne committed
2919
{
2920
    _say(QString(tr("%1 %2 flight mode")).arg(_vehicleIdSpeech()).arg(flightMode));
Don Gagne's avatar
Don Gagne committed
2921
    emit guidedModeChanged(_firmwarePlugin->isGuidedMode(this));
2922
2923
2924
2925
}

void Vehicle::_announceArmedChanged(bool armed)
{
2926
    _say(QString("%1 %2").arg(_vehicleIdSpeech()).arg(armed ? QString(tr("armed")) : QString(tr("disarmed"))));
Don Gagne's avatar
Don Gagne committed
2927
2928
}

2929
void Vehicle::_setFlying(bool flying)
Don Gagne's avatar
Don Gagne committed
2930
{
2931
    if (_flying != flying) {
Don Gagne's avatar
Don Gagne committed
2932
2933
2934
2935
2936
        _flying = flying;
        emit flyingChanged(flying);
    }
}

2937
2938
2939
2940
2941
2942
2943
2944
void Vehicle::_setLanding(bool landing)
{
    if (armed() && _landing != landing) {
        _landing = landing;
        emit landingChanged(landing);
    }
}

Don Gagne's avatar
Don Gagne committed
2945
2946
bool Vehicle::guidedModeSupported(void) const
{
2947
    return _firmwarePlugin->isCapable(this, FirmwarePlugin::GuidedModeCapability);
Don Gagne's avatar
Don Gagne committed
2948
2949
2950
2951
}

bool Vehicle::pauseVehicleSupported(void) const
{
2952
2953
2954
2955
2956
2957
    return _firmwarePlugin->isCapable(this, FirmwarePlugin::PauseVehicleCapability);
}

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

2960
2961
2962
2963
2964
bool Vehicle::takeoffVehicleSupported() const
{
    return _firmwarePlugin->isCapable(this, FirmwarePlugin::TakeoffVehicleCapability);
}

Don Gagne's avatar
   
Don Gagne committed
2965
2966
2967
2968
2969
QString Vehicle::gotoFlightMode() const
{
    return _firmwarePlugin->gotoFlightMode();
}

Don Gagne's avatar
Don Gagne committed
2970
2971
2972
void Vehicle::guidedModeRTL(void)
{
    if (!guidedModeSupported()) {
2973
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
2974
2975
2976
2977
2978
2979
2980
2981
        return;
    }
    _firmwarePlugin->guidedModeRTL(this);
}

void Vehicle::guidedModeLand(void)
{
    if (!guidedModeSupported()) {
2982
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
2983
2984
2985
2986
2987
        return;
    }
    _firmwarePlugin->guidedModeLand(this);
}

2988
void Vehicle::guidedModeTakeoff(double altitudeRelative)
Don Gagne's avatar
Don Gagne committed
2989
2990
{
    if (!guidedModeSupported()) {
2991
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
2992
2993
        return;
    }
2994
    _firmwarePlugin->guidedModeTakeoff(this, altitudeRelative);
2995
2996
}

2997
2998
2999
3000
3001
double Vehicle::minimumTakeoffAltitude(void)
{
    return _firmwarePlugin->minimumTakeoffAltitude(this);
}

3002
3003
3004
void Vehicle::startMission(void)
{
    _firmwarePlugin->startMission(this);
Don Gagne's avatar
Don Gagne committed
3005
3006
3007
3008
3009
}

void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord)
{
    if (!guidedModeSupported()) {
3010
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
3011
3012
        return;
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
3013
3014
3015
3016
3017
3018
3019
3020
    if (!coordinate().isValid()) {
        return;
    }
    double maxDistance = 1000.0;
    if (coordinate().distanceTo(gotoCoord) > maxDistance) {
        qgcApp()->showMessage(QString("New location is too far. Must be less than %1 %2").arg(qRound(FactMetaData::metersToAppSettingsDistanceUnits(maxDistance).toDouble())).arg(FactMetaData::appSettingsDistanceUnitsString()));
        return;
    }
Don Gagne's avatar
Don Gagne committed
3021
3022
3023
    _firmwarePlugin->guidedModeGotoLocation(this, gotoCoord);
}

DonLakeFlyer's avatar
DonLakeFlyer committed
3024
void Vehicle::guidedModeChangeAltitude(double altitudeChange)
Don Gagne's avatar
Don Gagne committed
3025
3026
{
    if (!guidedModeSupported()) {
3027
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
3028
3029
        return;
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
3030
    _firmwarePlugin->guidedModeChangeAltitude(this, altitudeChange);
Don Gagne's avatar
Don Gagne committed
3031
3032
}

DonLakeFlyer's avatar
DonLakeFlyer committed
3033
void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude)
dogmaphobic's avatar
dogmaphobic committed
3034
{
3035
3036
    if (!orbitModeSupported()) {
        qgcApp()->showMessage(QStringLiteral("Orbit mode not supported by Vehicle."));
dogmaphobic's avatar
dogmaphobic committed
3037
3038
        return;
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
3039

Don Gagne's avatar
   
Don Gagne committed
3040
    if (capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
3041
3042
3043
3044
3045
3046
3047
3048
        sendMavCommandInt(defaultComponentId(),
                          MAV_CMD_DO_ORBIT,
                          MAV_FRAME_GLOBAL,
                          true,            // show error if fails
                          radius,
                          qQNaN(),         // Use default velocity
                          0,               // Vehicle points to center
                          qQNaN(),         // reserved
DonLakeFlyer's avatar
DonLakeFlyer committed
3049
                          centerCoord.latitude(), centerCoord.longitude(), amslAltitude);
3050
3051
    } else {
        sendMavCommand(defaultComponentId(),
3052
3053
3054
3055
3056
3057
                       MAV_CMD_DO_ORBIT,
                       true,            // show error if fails
                       radius,
                       qQNaN(),         // Use default velocity
                       0,               // Vehicle points to center
                       qQNaN(),         // reserved
DonLakeFlyer's avatar
DonLakeFlyer committed
3058
                       centerCoord.latitude(), centerCoord.longitude(), amslAltitude);
3059
    }
dogmaphobic's avatar
dogmaphobic committed
3060
3061
}

Don Gagne's avatar
Don Gagne committed
3062
3063
3064
3065
3066
3067
3068
3069
3070
void Vehicle::pauseVehicle(void)
{
    if (!pauseVehicleSupported()) {
        qgcApp()->showMessage(QStringLiteral("Pause not supported by vehicle."));
        return;
    }
    _firmwarePlugin->pauseVehicle(this);
}

3071
void Vehicle::abortLanding(double climbOutAltitude)
3072
3073
3074
3075
{
    sendMavCommand(defaultComponentId(),
                   MAV_CMD_DO_GO_AROUND,
                   true,        // show error if fails
3076
                   climbOutAltitude);
3077
3078
}

Don Gagne's avatar
Don Gagne committed
3079
3080
3081
3082
3083
3084
3085
3086
3087
3088
3089
3090
bool Vehicle::guidedMode(void) const
{
    return _firmwarePlugin->isGuidedMode(this);
}

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

void Vehicle::emergencyStop(void)
{
3091
    sendMavCommand(_defaultComponentId,
3092
3093
3094
3095
                   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
3096
3097
}

3098
3099
3100
3101
3102
3103
void Vehicle::setCurrentMissionSequence(int seq)
{
    if (!_firmwarePlugin->sendHomePositionToVehicle()) {
        seq--;
    }
    mavlink_message_t msg;
3104
3105
3106
3107
3108
3109
3110
3111
    mavlink_msg_mission_set_current_pack_chan(_mavlink->getSystemId(),
                                              _mavlink->getComponentId(),
                                              priorityLink()->mavlinkChannel(),
                                              &msg,
                                              id(),
                                              _compID,
                                              seq);
    sendMessageOnLink(priorityLink(), msg);
3112
3113
}

3114
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
3115
{
3116
3117
    MavCommandQueueEntry_t entry;

3118
    entry.commandInt = false;
3119
3120
3121
3122
3123
3124
3125
3126
3127
3128
3129
3130
3131
3132
3133
3134
3135
3136
3137
    entry.component = component;
    entry.command = command;
    entry.showError = showError;
    entry.rgParam[0] = param1;
    entry.rgParam[1] = param2;
    entry.rgParam[2] = param3;
    entry.rgParam[3] = param4;
    entry.rgParam[4] = param5;
    entry.rgParam[5] = param6;
    entry.rgParam[6] = param7;

    _mavCommandQueue.append(entry);

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

3138
3139
3140
3141
3142
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;
3143
3144
    entry.component = component;
    entry.command = command;
3145
    entry.frame = frame;
3146
3147
3148
3149
3150
3151
3152
3153
3154
3155
3156
3157
3158
3159
3160
3161
3162
3163
3164
    entry.showError = showError;
    entry.rgParam[0] = param1;
    entry.rgParam[1] = param2;
    entry.rgParam[2] = param3;
    entry.rgParam[3] = param4;
    entry.rgParam[4] = param5;
    entry.rgParam[5] = param6;
    entry.rgParam[6] = param7;

    _mavCommandQueue.append(entry);

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

void Vehicle::_sendMavCommandAgain(void)
{
3165
3166
3167
3168
3169
3170
    if(!_mavCommandQueue.size()) {
        qWarning() << "Command resend with no commands in queue";
        _mavCommandAckTimer.stop();
        return;
    }

3171
3172
3173
    MavCommandQueueEntry_t& queuedCommand = _mavCommandQueue[0];

    if (_mavCommandRetryCount++ > _mavCommandMaxRetryCount) {
3174
3175
        if (queuedCommand.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) {
            // We aren't going to get a response back for capabilities, so stop waiting for it before we ask for mission items
DonLakeFlyer's avatar
DonLakeFlyer committed
3176
            qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES. Setting no capabilities. Starting Plan request.";
DonLakeFlyer's avatar
DonLakeFlyer committed
3177
            _setCapabilities(0);
DonLakeFlyer's avatar
DonLakeFlyer committed
3178
            _startPlanRequest();
3179
3180
        }

3181
        if (queuedCommand.command == MAV_CMD_REQUEST_PROTOCOL_VERSION) {
3182
3183
            // We aren't going to get a response back for the protocol version, so assume v1 is all we can do.
            // If the max protocol version is uninitialized, fall back to v1.
DonLakeFlyer's avatar
DonLakeFlyer committed
3184
            qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_PROTOCOL_VERSION. Starting Plan request.";
3185
            if (_maxProtoVersion == 0) {
DonLakeFlyer's avatar
DonLakeFlyer committed
3186
                qCDebug(VehicleLog) << "Setting _maxProtoVersion to 100 since not yet set.";
3187
                _setMaxProtoVersion(100);
DonLakeFlyer's avatar
DonLakeFlyer committed
3188
3189
            } else {
                qCDebug(VehicleLog) << "Leaving _maxProtoVersion at current value" << _maxProtoVersion;
3190
            }
3191
3192
        }

3193
3194
        emit mavCommandResult(_id, queuedCommand.component, queuedCommand.command, MAV_RESULT_FAILED, true /* noResponsefromVehicle */);
        if (queuedCommand.showError) {
3195
            qgcApp()->showMessage(tr("Vehicle did not respond to command: %1").arg(_toolbox->missionCommandTree()->friendlyName(queuedCommand.command)));
3196
3197
3198
3199
3200
3201
        }
        _mavCommandQueue.removeFirst();
        _sendNextQueuedMavCommand();
        return;
    }

3202
    if (_mavCommandRetryCount > 1) {
Don Gagne's avatar
Don Gagne committed
3203
3204
3205
3206
3207
3208
3209
3210
3211
3212
3213
3214
3215
3216
3217
3218
3219
3220
3221
        // We always let AUTOPILOT_CAPABILITIES go through multiple times even if we don't get acks. This is because
        // we really need to get capabilities and version info back over a lossy link.
        if (queuedCommand.command != MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) {
            if (px4Firmware()) {
                // Older PX4 firmwares are inconsistent with repect to sending back an Ack from a COMMAND_LONG, hence we can't support retry logic for it.
                if (_firmwareMajorVersion != versionNotSetValue) {
                    // If no version set assume lastest master dev build, so acks are suppored
                    if (_firmwareMajorVersion <= 1 && _firmwareMinorVersion <= 5 && _firmwarePatchVersion <= 3) {
                        // Acks not supported in this version
                        return;
                    }
                }
            } else {
                if (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;
                }
            }
3222
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
3223
        qCDebug(VehicleLog) << "Vehicle::_sendMavCommandAgain retrying command:_mavCommandRetryCount" << queuedCommand.command << _mavCommandRetryCount;
3224
3225
    }

3226
3227
    _mavCommandAckTimer.start();

Don Gagne's avatar
Don Gagne committed
3228
    mavlink_message_t       msg;
3229
3230
3231
3232
3233
3234
3235
3236
3237
3238
3239
3240
3241
3242
3243
3244
3245
3246
3247
3248
3249
3250
3251
3252
3253
3254
3255
3256
3257
3258
3259
3260
3261
3262
3263
3264
3265
3266
3267
3268
3269
    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
3270

3271
    sendMessageOnLink(priorityLink(), msg);
Don Gagne's avatar
Don Gagne committed
3272
}
3273

3274
3275
3276
3277
3278
3279
3280
3281
3282
void Vehicle::_sendNextQueuedMavCommand(void)
{
    if (_mavCommandQueue.count()) {
        _mavCommandRetryCount = 0;
        _sendMavCommandAgain();
    }
}


DonLakeFlyer's avatar
DonLakeFlyer committed
3283
3284
3285
3286
3287
3288
3289
3290
3291
3292
3293
3294
3295
3296
3297
3298
3299
3300
3301
3302
3303
3304
3305
3306
3307
3308
3309
3310
3311
3312
3313
3314
3315
3316
3317
3318
3319
3320
3321
3322
3323
3324
3325
3326
3327
3328
3329
3330
3331
3332
3333
3334
3335
3336
3337
3338
3339
3340
3341
3342
void Vehicle::_handleCommandAck(mavlink_message_t& message)
{
    bool showError = false;

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

    if (ack.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES && ack.result != MAV_RESULT_ACCEPTED) {
        // We aren't going to get a response back for capabilities, so stop waiting for it before we ask for mission items
        qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error(%1). Setting no capabilities. Starting Plan request.").arg(ack.result);
        _setCapabilities(0);
    }

    if (ack.command == MAV_CMD_REQUEST_PROTOCOL_VERSION && ack.result != MAV_RESULT_ACCEPTED) {
        // The autopilot does not understand the request and consequently is likely handling only
        // MAVLink 1
        qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_PROTOCOL_VERSION with error(%1).").arg(ack.result);
        if (_maxProtoVersion == 0) {
            qCDebug(VehicleLog) << "Setting _maxProtoVersion to 100 since not yet set.";
            _setMaxProtoVersion(100);
        } else {
            qCDebug(VehicleLog) << "Leaving _maxProtoVersion at current value" << _maxProtoVersion;
        }
        // FIXME: Is this missing here. I believe it is a bug. Debug to verify. May need to go into Stable.
        //_startPlanRequest();
    }

    if (_mavCommandQueue.count() && ack.command == _mavCommandQueue[0].command) {
        _mavCommandAckTimer.stop();
        showError = _mavCommandQueue[0].showError;
        _mavCommandQueue.removeFirst();
    }

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

    if (showError) {
        QString commandName = _toolbox->missionCommandTree()->friendlyName((MAV_CMD)ack.command);

        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;
        }
    }

    _sendNextQueuedMavCommand();
}

Don Gagne's avatar
Don Gagne committed
3343
3344
3345
3346
3347
3348
3349
3350
3351
3352
3353
3354
3355
void Vehicle::setPrearmError(const QString& prearmError)
{
    _prearmError = prearmError;
    emit prearmErrorChanged(_prearmError);
    if (!_prearmError.isEmpty()) {
        _prearmErrorTimer.start();
    }
}

void Vehicle::_prearmErrorTimeout(void)
{
    setPrearmError(QString());
}
3356

3357
void Vehicle::setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType)
Don Gagne's avatar
Don Gagne committed
3358
3359
3360
3361
{
    _firmwareMajorVersion = majorVersion;
    _firmwareMinorVersion = minorVersion;
    _firmwarePatchVersion = patchVersion;
3362
    _firmwareVersionType = versionType;
3363
3364
3365
3366
3367
3368
3369
3370
3371
    emit firmwareVersionChanged();
}

void Vehicle::setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion)
{
    _firmwareCustomMajorVersion = majorVersion;
    _firmwareCustomMinorVersion = minorVersion;
    _firmwareCustomPatchVersion = patchVersion;
    emit firmwareCustomVersionChanged();
3372
3373
3374
3375
3376
3377
3378
3379
3380
3381
3382
3383
3384
3385
3386
3387
3388
}

QString Vehicle::firmwareVersionTypeString(void) const
{
    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
3389
3390
}

dogmaphobic's avatar
dogmaphobic committed
3391
3392
void Vehicle::rebootVehicle()
{
3393
    _autoDisconnect = true;
3394
    sendMavCommand(_defaultComponentId, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, true, 1.0f);
Don Gagne's avatar
Don Gagne committed
3395
3396
}

Don Gagne's avatar
Don Gagne committed
3397
3398
3399
3400
3401
3402
3403
3404
void Vehicle::setSoloFirmware(bool soloFirmware)
{
    if (soloFirmware != _soloFirmware) {
        _soloFirmware = soloFirmware;
        emit soloFirmwareChanged(soloFirmware);
    }
}

3405
void Vehicle::motorTest(int motor, int percent)
Don Gagne's avatar
Don Gagne committed
3406
{
3407
    sendMavCommand(_defaultComponentId, MAV_CMD_DO_MOTOR_TEST, true, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, 0, 0, MOTOR_TEST_ORDER_BOARD);
Don Gagne's avatar
Don Gagne committed
3408
3409
}

3410
QString Vehicle::brandImageIndoor(void) const
3411
{
3412
3413
3414
3415
3416
3417
    return _firmwarePlugin->brandImageIndoor(this);
}

QString Vehicle::brandImageOutdoor(void) const
{
    return _firmwarePlugin->brandImageOutdoor(this);
3418
3419
}

3420
3421
3422
3423
3424
3425
3426
3427
3428
3429
3430
3431
3432
3433
3434
3435
3436
3437
3438
3439
3440
3441
3442
3443
3444
3445
3446
3447
3448
3449
3450
3451
3452
3453
3454
QStringList Vehicle::unhealthySensors(void) const
{
    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" },
3455
        { MAV_SYS_STATUS_SENSOR_BATTERY,                "Battery" },
3456
3457
3458
3459
3460
3461
3462
3463
3464
3465
3466
3467
    };

    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;
}

3468
3469
3470
3471
3472
3473
3474
3475
void Vehicle::setOfflineEditingDefaultComponentId(int defaultComponentId)
{
    if (_offlineEditingVehicle) {
        _defaultComponentId = defaultComponentId;
    } else {
        qWarning() << "Call to Vehicle::setOfflineEditingDefaultComponentId on vehicle which is not offline";
    }
}
3476

Don Gagne's avatar
Don Gagne committed
3477
3478
void Vehicle::triggerCamera(void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
3479
    sendMavCommand(_defaultComponentId,
Don Gagne's avatar
Don Gagne committed
3480
3481
3482
                   MAV_CMD_DO_DIGICAM_CONTROL,
                   true,                            // show errors
                   0.0, 0.0, 0.0, 0.0,              // param 1-4 unused
3483
3484
3485
                   1.0,                             // trigger camera
                   0.0,                             // param 6 unused
                   1.0);                            // test shot flag
Don Gagne's avatar
Don Gagne committed
3486
3487
}

Don Gagne's avatar
Don Gagne committed
3488
3489
3490
void Vehicle::setVtolInFwdFlight(bool vtolInFwdFlight)
{
    if (_vtolInFwdFlight != vtolInFwdFlight) {
DonLakeFlyer's avatar
DonLakeFlyer committed
3491
3492
3493
3494
3495
        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
3496
3497
3498
    }
}

3499
3500
const char* VehicleGPSFactGroup::_latFactName =                 "lat";
const char* VehicleGPSFactGroup::_lonFactName =                 "lon";
Don Gagne's avatar
Don Gagne committed
3501
3502
3503
3504
3505
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
3506
3507
3508

VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent)
    : FactGroup(1000, ":/json/Vehicle/GPSFact.json", parent)
3509
3510
    , _latFact              (0, _latFactName,               FactMetaData::valueTypeDouble)
    , _lonFact              (0, _lonFactName,               FactMetaData::valueTypeDouble)
Don Gagne's avatar
Don Gagne committed
3511
3512
3513
3514
3515
3516
    , _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)
{
3517
3518
    _addFact(&_latFact,                 _latFactName);
    _addFact(&_lonFact,                 _lonFactName);
Don Gagne's avatar
Don Gagne committed
3519
3520
3521
3522
3523
    _addFact(&_hdopFact,                _hdopFactName);
    _addFact(&_vdopFact,                _vdopFactName);
    _addFact(&_courseOverGroundFact,    _courseOverGroundFactName);
    _addFact(&_lockFact,                _lockFactName);
    _addFact(&_countFact,               _countFactName);
3524

3525
3526
    _latFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _lonFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
3527
3528
3529
    _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
3530
3531
}

3532
void Vehicle::startMavlinkLog()
3533
{
3534
    sendMavCommand(_defaultComponentId, MAV_CMD_LOGGING_START, false /* showError */);
3535
3536
}

3537
void Vehicle::stopMavlinkLog()
3538
{
3539
    sendMavCommand(_defaultComponentId, MAV_CMD_LOGGING_STOP, false /* showError */);
3540
3541
}

3542
void Vehicle::_ackMavlinkLogData(uint16_t sequence)
3543
3544
3545
{
    mavlink_message_t msg;
    mavlink_logging_ack_t ack;
Don Gagne's avatar
Don Gagne committed
3546
    memset(&ack, 0, sizeof(ack));
3547
    ack.sequence = sequence;
3548
    ack.target_component = _defaultComponentId;
3549
3550
    ack.target_system = id();
    mavlink_msg_logging_ack_encode_chan(
DonLakeFlyer's avatar
DonLakeFlyer committed
3551
3552
3553
3554
3555
                _mavlink->getSystemId(),
                _mavlink->getComponentId(),
                priorityLink()->mavlinkChannel(),
                &msg,
                &ack);
3556
3557
3558
    sendMessageOnLink(priorityLink(), msg);
}

3559
void Vehicle::_handleMavlinkLoggingData(mavlink_message_t& message)
3560
3561
3562
{
    mavlink_logging_data_t log;
    mavlink_msg_logging_data_decode(&message, &log);
Gus Grubba's avatar
Gus Grubba committed
3563
    emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence,
DonLakeFlyer's avatar
DonLakeFlyer committed
3564
                        log.first_message_offset, QByteArray((const char*)log.data, log.length), false);
3565
3566
}

3567
void Vehicle::_handleMavlinkLoggingDataAcked(mavlink_message_t& message)
3568
{
3569
3570
    mavlink_logging_data_acked_t log;
    mavlink_msg_logging_data_acked_decode(&message, &log);
3571
    _ackMavlinkLogData(log.sequence);
Gus Grubba's avatar
Gus Grubba committed
3572
    emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence,
DonLakeFlyer's avatar
DonLakeFlyer committed
3573
                        log.first_message_offset, QByteArray((const char*)log.data, log.length), true);
3574
3575
}

3576
3577
3578
3579
3580
3581
void Vehicle::setFirmwarePluginInstanceData(QObject* firmwarePluginInstanceData)
{
    firmwarePluginInstanceData->setParent(this);
    _firmwarePluginInstanceData = firmwarePluginInstanceData;
}

3582
3583
3584
3585
3586
QString Vehicle::missionFlightMode(void) const
{
    return _firmwarePlugin->missionFlightMode();
}

DonLakeFlyer's avatar
DonLakeFlyer committed
3587
3588
3589
3590
3591
QString Vehicle::pauseFlightMode(void) const
{
    return _firmwarePlugin->pauseFlightMode();
}

3592
3593
3594
3595
3596
QString Vehicle::rtlFlightMode(void) const
{
    return _firmwarePlugin->rtlFlightMode();
}

DonLakeFlyer's avatar
DonLakeFlyer committed
3597
3598
3599
3600
3601
QString Vehicle::landFlightMode(void) const
{
    return _firmwarePlugin->landFlightMode();
}

3602
3603
3604
3605
3606
QString Vehicle::takeControlFlightMode(void) const
{
    return _firmwarePlugin->takeControlFlightMode();
}

3607
3608
3609
3610
3611
3612
3613
3614
3615
3616
3617
3618
3619
3620
3621
3622
3623
3624
3625
3626
3627
3628
3629
3630
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();
}

3631
const QVariantList& Vehicle::toolBarIndicators()
3632
3633
3634
3635
3636
3637
3638
3639
{
    if(_firmwarePlugin) {
        return _firmwarePlugin->toolBarIndicators(this);
    }
    static QVariantList emptyList;
    return emptyList;
}

Gus Grubba's avatar
Gus Grubba committed
3640
const QVariantList& Vehicle::staticCameraList(void) const
3641
3642
3643
3644
3645
3646
3647
3648
{
    if (_firmwarePlugin) {
        return _firmwarePlugin->cameraList(this);
    }
    static QVariantList emptyList;
    return emptyList;
}

3649
3650
3651
3652
bool Vehicle::vehicleYawsToNextWaypointInMission(void) const
{
    return _firmwarePlugin->vehicleYawsToNextWaypointInMission(this);
}
3653

3654
3655
3656
3657
3658
3659
3660
3661
3662
3663
3664
3665
3666
3667
3668
3669
3670
3671
3672
3673
3674
3675
3676
void Vehicle::_setupAutoDisarmSignalling(void)
{
    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();
    }
}

bool Vehicle::autoDisarm(void)
{
    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;
}

3677
3678
3679
void Vehicle::_handleADSBVehicle(const mavlink_message_t& message)
{
    mavlink_adsb_vehicle_t adsbVehicle;
Don Gagne's avatar
Don Gagne committed
3680
    static const int maxTimeSinceLastSeen = 15;
3681
3682
3683
3684

    mavlink_msg_adsb_vehicle_decode(&message, &adsbVehicle);
    if (adsbVehicle.flags | ADSB_FLAGS_VALID_COORDS) {
        if (_adsbICAOMap.contains(adsbVehicle.ICAO_address)) {
DonLakeFlyer's avatar
DonLakeFlyer committed
3685
3686
3687
3688
3689
3690
            if (adsbVehicle.tslc > maxTimeSinceLastSeen) {
                ADSBVehicle* vehicle = _adsbICAOMap[adsbVehicle.ICAO_address];
                _adsbVehicles.removeOne(vehicle);
                _adsbICAOMap.remove(adsbVehicle.ICAO_address);
                vehicle->deleteLater();
            } else {
Don Gagne's avatar
Don Gagne committed
3691
                _adsbICAOMap[adsbVehicle.ICAO_address]->update(adsbVehicle);
DonLakeFlyer's avatar
DonLakeFlyer committed
3692
            }
Don Gagne's avatar
Don Gagne committed
3693
        } else if (adsbVehicle.tslc <= maxTimeSinceLastSeen) {
3694
3695
3696
3697
3698
3699
3700
            ADSBVehicle* vehicle = new ADSBVehicle(adsbVehicle, this);
            _adsbICAOMap[adsbVehicle.ICAO_address] = vehicle;
            _adsbVehicles.append(vehicle);
        }
    }
}

Don Gagne's avatar
   
Don Gagne committed
3701
void Vehicle::_updateDistanceHeadingToHome(void)
3702
3703
3704
{
    if (coordinate().isValid() && homePosition().isValid()) {
        _distanceToHomeFact.setRawValue(coordinate().distanceTo(homePosition()));
Don Gagne's avatar
   
Don Gagne committed
3705
3706
3707
3708
3709
        if (_distanceToHomeFact.rawValue().toDouble() > 1.0) {
            _headingToHomeFact.setRawValue(coordinate().azimuthTo(homePosition()));
        } else {
            _headingToHomeFact.setRawValue(qQNaN());
        }
3710
3711
    } else {
        _distanceToHomeFact.setRawValue(qQNaN());
Don Gagne's avatar
   
Don Gagne committed
3712
        _headingToHomeFact.setRawValue(qQNaN());
3713
3714
3715
    }
}

Don Gagne's avatar
   
Don Gagne committed
3716
3717
3718
3719
3720
3721
3722
3723
3724
3725
void Vehicle::_updateDistanceToGCS(void)
{
    QGeoCoordinate gcsPosition = _toolbox->qgcPositionManager()->gcsPosition();
    if (coordinate().isValid() && gcsPosition.isValid()) {
        _distanceToGCSFact.setRawValue(coordinate().distanceTo(gcsPosition));
    } else {
        _distanceToGCSFact.setRawValue(qQNaN());
    }
}

3726
3727
3728
3729
3730
void Vehicle::_updateHobbsMeter(void)
{
    _hobbsFact.setRawValue(hobbsMeter());
}

Don Gagne's avatar
Don Gagne committed
3731
3732
3733
3734
3735
3736
3737
3738
3739
3740
3741
void Vehicle::forceInitialPlanRequestComplete(void)
{
    _initialPlanRequestComplete = true;
    emit initialPlanRequestCompleteChanged(true);
}

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

3742
3743
3744
3745
3746
3747
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
3748
            _parameterManager->parameterExists(FactSystem::defaultComponentId, HOOBS_LO)) {
3749
3750
        Fact* factHi = _parameterManager->getParameter(FactSystem::defaultComponentId, HOOBS_HI);
        Fact* factLo = _parameterManager->getParameter(FactSystem::defaultComponentId, HOOBS_LO);
3751
        uint64_t hobbsTimeSeconds = ((uint64_t)factHi->rawValue().toUInt() << 32 | (uint64_t)factLo->rawValue().toUInt()) / 1000000;
3752
3753
3754
3755
3756
        int hours   = hobbsTimeSeconds / 3600;
        int minutes = (hobbsTimeSeconds % 3600) / 60;
        int seconds = hobbsTimeSeconds % 60;
        QString timeStr;
        timeStr.sprintf("%04d:%02d:%02d", hours, minutes, seconds);
3757
        qCDebug(VehicleLog) << "Hobbs Meter:" << timeStr << "(" << factHi->rawValue().toUInt() << factLo->rawValue().toUInt() << ")";
3758
3759
3760
3761
        return timeStr;
    }
    return QString("0000:00:00");
}
Don Gagne's avatar
Don Gagne committed
3762

3763
3764
3765
3766
3767
3768
3769
3770
3771
void Vehicle::_vehicleParamLoaded(bool ready)
{
    //-- TODO: This seems silly but can you think of a better
    //   way to update this?
    if(ready) {
        emit hobbsMeterChanged();
    }
}

3772
void Vehicle::_updateHighLatencyLink(bool sendCommand)
Don Gagne's avatar
Don Gagne committed
3773
{
3774
3775
3776
3777
    if (!_priorityLink) {
        return;
    }

Don Gagne's avatar
Don Gagne committed
3778
3779
    if (_priorityLink->highLatency() != _highLatencyLink) {
        _highLatencyLink = _priorityLink->highLatency();
DonLakeFlyer's avatar
DonLakeFlyer committed
3780
        _mavCommandAckTimer.setInterval(_highLatencyLink ? _mavCommandAckTimeoutMSecsHighLatency : _mavCommandAckTimeoutMSecs);
Don Gagne's avatar
Don Gagne committed
3781
        emit highLatencyLinkChanged(_highLatencyLink);
3782
3783

        if (sendCommand) {
acfloria's avatar
acfloria committed
3784
3785
3786
3787
            sendMavCommand(defaultComponentId(),
                           MAV_CMD_CONTROL_HIGH_LATENCY,
                           true,
                           _highLatencyLink ? 1.0f : 0.0f); // request start/stop transmitting over high latency telemetry
3788
        }
Don Gagne's avatar
Don Gagne committed
3789
3790
3791
    }
}

Gus Grubba's avatar
Gus Grubba committed
3792
void Vehicle::_trafficUpdate(bool alert, QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading)
3793
{
3794
    Q_UNUSED(vehicle_id);
3795
3796
3797
    // qDebug() << "traffic update:" << traffic_id << vehicle_id << heading << location;
    // TODO: filter based on minimum altitude?
    if (_trafficVehicleMap.contains(traffic_id)) {
Gus Grubba's avatar
Gus Grubba committed
3798
        _trafficVehicleMap[traffic_id]->update(alert, location, heading);
3799
    } else {
Gus Grubba's avatar
Gus Grubba committed
3800
        ADSBVehicle* vehicle = new ADSBVehicle(location, heading, alert, this);
3801
3802
3803
3804
3805
        _trafficVehicleMap[traffic_id] = vehicle;
        _adsbVehicles.append(vehicle);
    }

}
3806
3807
3808
3809
3810
3811
3812
3813
3814
3815
3816
3817
3818
3819
void Vehicle::_adsbTimerTimeout()
{
    // TODO: take into account _adsbICAOMap as well? Needs to be tested, especially the timeout

    for (auto it = _trafficVehicleMap.begin(); it != _trafficVehicleMap.end();) {
        if (it.value()->expired()) {
            _adsbVehicles.removeOne(it.value());
            delete it.value();
            it = _trafficVehicleMap.erase(it);
        } else {
            ++it;
        }
    }
}
3820

Gus Grubba's avatar
Gus Grubba committed
3821
3822
3823
3824
3825
3826
3827
3828
3829
3830
3831
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();
    }
}

3832
3833
3834
3835
3836
3837
3838
3839
3840
3841
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);
}

3842
3843
3844
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------

Don Gagne's avatar
Don Gagne committed
3845
3846
3847
3848
3849
3850
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";
const char* VehicleBatteryFactGroup::_cellCountFactName =                   "cellCount";
3851
const char* VehicleBatteryFactGroup::_instantPowerFactName =                "instantPower";
3852
3853
const char* VehicleBatteryFactGroup::_timeRemainingFactName =               "timeRemaining";
const char* VehicleBatteryFactGroup::_chargeStateFactName =                 "chargeState";
Don Gagne's avatar
Don Gagne committed
3854
3855
3856
3857
3858
3859
3860
3861
3862

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

const double VehicleBatteryFactGroup::_voltageUnavailable =           -1.0;
const int    VehicleBatteryFactGroup::_percentRemainingUnavailable =  -1;
const int    VehicleBatteryFactGroup::_mahConsumedUnavailable =       -1;
const int    VehicleBatteryFactGroup::_currentUnavailable =           -1;
const double VehicleBatteryFactGroup::_temperatureUnavailable =       -1.0;
const int    VehicleBatteryFactGroup::_cellCountUnavailable =         -1.0;
3863
const double VehicleBatteryFactGroup::_instantPowerUnavailable =      -1.0;
Don Gagne's avatar
Don Gagne committed
3864

Don Gagne's avatar
Don Gagne committed
3865
3866
VehicleBatteryFactGroup::VehicleBatteryFactGroup(QObject* parent)
    : FactGroup(1000, ":/json/Vehicle/BatteryFact.json", parent)
Don Gagne's avatar
Don Gagne committed
3867
3868
3869
    , _voltageFact                  (0, _voltageFactName,                   FactMetaData::valueTypeDouble)
    , _percentRemainingFact         (0, _percentRemainingFactName,          FactMetaData::valueTypeInt32)
    , _mahConsumedFact              (0, _mahConsumedFactName,               FactMetaData::valueTypeInt32)
Don Gagne's avatar
Don Gagne committed
3870
    , _currentFact                  (0, _currentFactName,                   FactMetaData::valueTypeFloat)
Don Gagne's avatar
Don Gagne committed
3871
3872
    , _temperatureFact              (0, _temperatureFactName,               FactMetaData::valueTypeDouble)
    , _cellCountFact                (0, _cellCountFactName,                 FactMetaData::valueTypeInt32)
3873
    , _instantPowerFact             (0, _instantPowerFactName,              FactMetaData::valueTypeFloat)
3874
3875
    , _timeRemainingFact            (0, _timeRemainingFactName,             FactMetaData::valueTypeInt32)
    , _chargeStateFact              (0, _chargeStateFactName,               FactMetaData::valueTypeUint8)
Don Gagne's avatar
Don Gagne committed
3876
{
3877
3878
3879
3880
3881
3882
    _addFact(&_voltageFact,                 _voltageFactName);
    _addFact(&_percentRemainingFact,        _percentRemainingFactName);
    _addFact(&_mahConsumedFact,             _mahConsumedFactName);
    _addFact(&_currentFact,                 _currentFactName);
    _addFact(&_temperatureFact,             _temperatureFactName);
    _addFact(&_cellCountFact,               _cellCountFactName);
3883
    _addFact(&_instantPowerFact,            _instantPowerFactName);
3884
3885
    _addFact(&_timeRemainingFact,           _timeRemainingFactName);
    _addFact(&_chargeStateFact,             _chargeStateFactName);
Don Gagne's avatar
Don Gagne committed
3886
3887
3888
3889
3890
3891
3892
3893

    // Start out as not available
    _voltageFact.setRawValue            (_voltageUnavailable);
    _percentRemainingFact.setRawValue   (_percentRemainingUnavailable);
    _mahConsumedFact.setRawValue        (_mahConsumedUnavailable);
    _currentFact.setRawValue            (_currentUnavailable);
    _temperatureFact.setRawValue        (_temperatureUnavailable);
    _cellCountFact.setRawValue          (_cellCountUnavailable);
3894
    _instantPowerFact.setRawValue       (_instantPowerUnavailable);
Don Gagne's avatar
Don Gagne committed
3895
3896
}

Don Gagne's avatar
Don Gagne committed
3897
3898
3899
3900
const char* VehicleWindFactGroup::_directionFactName =      "direction";
const char* VehicleWindFactGroup::_speedFactName =          "speed";
const char* VehicleWindFactGroup::_verticalSpeedFactName =  "verticalSpeed";

Don Gagne's avatar
Don Gagne committed
3901
3902
3903
3904
3905
3906
3907
3908
3909
3910
3911
3912
3913
3914
3915
3916
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
3917
3918
3919
3920
3921
3922
3923
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
3924
3925
3926
3927
3928
3929
3930
3931
3932
3933
3934
3935
3936
3937
3938
3939
3940
3941
3942
3943
3944
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());
}
3945
3946
3947
3948
3949
3950
3951
3952
3953
3954
3955
3956
3957
3958
3959
3960
3961
3962
3963
3964

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
3965
3966
3967
3968
3969
3970
3971
3972
3973
3974
3975
3976
3977
3978
3979
3980
3981
3982
3983
3984
3985
3986
3987
3988

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());
}

void VehicleClockFactGroup::_updateAllValues(void)
{
    _currentTimeFact.setRawValue(QTime::currentTime().toString());
    _currentDateFact.setRawValue(QDateTime::currentDateTime().toString(QLocale::system().dateFormat(QLocale::ShortFormat)));

    FactGroup::_updateAllValues();
}
DonLakeFlyer's avatar
DonLakeFlyer committed
3989
3990
3991
3992
3993
3994
3995
3996
3997
3998
3999
4000
4001
4002
4003
4004
4005
4006
4007
4008
4009
4010
4011
4012
4013
4014
4015
4016
4017
4018
4019
4020

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());
}
4021
4022

const char* VehicleDistanceSensorFactGroup::_rotationNoneFactName =     "rotationNone";
4023
const char* VehicleDistanceSensorFactGroup::_rotationYaw45FactName =    "rotationYaw45";
4024
const char* VehicleDistanceSensorFactGroup::_rotationYaw90FactName =    "rotationYaw90";
4025
const char* VehicleDistanceSensorFactGroup::_rotationYaw135FactName =   "rotationYaw135";
4026
const char* VehicleDistanceSensorFactGroup::_rotationYaw180FactName =   "rotationYaw180";
4027
const char* VehicleDistanceSensorFactGroup::_rotationYaw225FactName =   "rotationYaw225";
4028
const char* VehicleDistanceSensorFactGroup::_rotationYaw270FactName =   "rotationYaw270";
4029
4030
4031
const char* VehicleDistanceSensorFactGroup::_rotationYaw315FactName =   "rotationYaw315";
const char* VehicleDistanceSensorFactGroup::_rotationPitch90FactName =  "rotationPitch90";
const char* VehicleDistanceSensorFactGroup::_rotationPitch270FactName = "rotationPitch270";
4032
4033
4034
4035

VehicleDistanceSensorFactGroup::VehicleDistanceSensorFactGroup(QObject* parent)
    : FactGroup             (1000, ":/json/Vehicle/DistanceSensorFact.json", parent)
    , _rotationNoneFact     (0, _rotationNoneFactName,      FactMetaData::valueTypeDouble)
4036
    , _rotationYaw45Fact    (0, _rotationYaw45FactName,     FactMetaData::valueTypeDouble)
4037
    , _rotationYaw90Fact    (0, _rotationYaw90FactName,     FactMetaData::valueTypeDouble)
4038
    , _rotationYaw135Fact   (0, _rotationYaw135FactName,    FactMetaData::valueTypeDouble)
4039
    , _rotationYaw180Fact   (0, _rotationYaw180FactName,    FactMetaData::valueTypeDouble)
4040
    , _rotationYaw225Fact   (0, _rotationYaw225FactName,    FactMetaData::valueTypeDouble)
4041
    , _rotationYaw270Fact   (0, _rotationYaw270FactName,    FactMetaData::valueTypeDouble)
4042
4043
4044
4045
4046
4047
4048
4049
4050
4051
4052
4053
4054
4055
4056
4057
    , _rotationYaw315Fact   (0, _rotationYaw315FactName,    FactMetaData::valueTypeDouble)
    , _rotationPitch90Fact  (0, _rotationPitch90FactName,   FactMetaData::valueTypeDouble)
    , _rotationPitch270Fact (0, _rotationPitch270FactName,  FactMetaData::valueTypeDouble)
    , _idSet                (false)
    , _id                   (0)
{
    _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);
4058
4059
4060

    // Start out as not available "--.--"
    _rotationNoneFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4061
4062
    _rotationYaw45Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _rotationYaw135Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4063
4064
    _rotationYaw90Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _rotationYaw180Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4065
    _rotationYaw225Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4066
    _rotationYaw270Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4067
4068
    _rotationPitch90Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _rotationPitch270Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4069
}
4070
4071
4072
4073
4074
4075
4076
4077
4078
4079
4080
4081
4082
4083
4084
4085
4086
4087
4088
4089
4090
4091
4092
4093
4094
4095
4096
4097
4098
4099
4100
4101
4102
4103
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

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);
}