Vehicle.cc 171 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"
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"
27
#include "CoordinateVector.h"
28
#include "ParameterManager.h"
29
#include "QGCApplication.h"
dogmaphobic's avatar
dogmaphobic committed
30
#include "QGCImageProvider.h"
31
#include "MissionCommandTree.h"
32
#include "QGroundControlQmlGlobal.h"
33
#include "SettingsManager.h"
34
#include "QGCQGeoCoordinate.h"
35
#include "QGCCorePlugin.h"
36
#include "QGCOptions.h"
37
#include "ADSBVehicle.h"
38
#include "QGCCameraManager.h"
39 40
#include "VideoReceiver.h"
#include "VideoManager.h"
41
#include "VideoSettings.h"
42
#include "PositionManager.h"
Gus Grubba's avatar
Gus Grubba committed
43
#include "VehicleObjectAvoidance.h"
44
#include "TrajectoryPoints.h"
Gus Grubba's avatar
Gus Grubba committed
45

46 47 48 49
#if defined(QGC_AIRMAP_ENABLED)
#include "AirspaceVehicleManager.h"
#endif

50 51
QGC_LOGGING_CATEGORY(VehicleLog, "VehicleLog")

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

56
const QString guided_mode_not_supported_by_vehicle = QObject::tr("Guided mode not supported by Vehicle.");
57

58 59 60
const char* Vehicle::_settingsGroup =               "Vehicle%1";        // %1 replaced with mavlink system id
const char* Vehicle::_joystickModeSettingsKey =     "JoystickMode";
const char* Vehicle::_joystickEnabledSettingsKey =  "JoystickEnabled";
61

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

82 83 84 85 86 87 88 89 90
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
91

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

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

230 231
    connect(_mavlink, &MAVLinkProtocol::messageReceived,        this, &Vehicle::_mavlinkMessageReceived);
    connect(_mavlink, &MAVLinkProtocol::mavlinkMessageStatus,   this, &Vehicle::_mavlinkMessageStatus);
232

233 234
    _addLink(link);

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

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

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

243 244
    connect(_uas, &UAS::imageReady,                     this, &Vehicle::_imageReady);
    connect(this, &Vehicle::remoteControlRSSIChanged,   this, &Vehicle::_remoteControlRSSIChanged);
dogmaphobic's avatar
dogmaphobic committed
245

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

249 250 251 252 253
    // PreArm Error self-destruct timer
    connect(&_prearmErrorTimer, &QTimer::timeout, this, &Vehicle::_prearmErrorTimeout);
    _prearmErrorTimer.setInterval(_prearmErrorTimeoutMSecs);
    _prearmErrorTimer.setSingleShot(true);

254 255
    // Send MAV_CMD ack timer
    _mavCommandAckTimer.setSingleShot(true);
256
    _mavCommandAckTimer.setInterval(_highLatencyLink ? _mavCommandAckTimeoutMSecsHighLatency : _mavCommandAckTimeoutMSecs);
257 258
    connect(&_mavCommandAckTimer, &QTimer::timeout, this, &Vehicle::_sendMavCommandAgain);

259
    _mav = uas();
260

261
    // Listen for system messages
262 263
    connect(_toolbox->uasMessageHandler(), &UASMessageHandler::textMessageCountChanged,  this, &Vehicle::_handleTextMessage);
    connect(_toolbox->uasMessageHandler(), &UASMessageHandler::textMessageReceived,      this, &Vehicle::_handletextMessageReceived);
264

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

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

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

292 293
    connect(&_orbitTelemetryTimer, &QTimer::timeout, this, &Vehicle::_orbitTelemetryTimeout);

294
    // Create camera manager instance
295
    _cameras = _firmwarePlugin->createCameraManager(this);
296
    emit dynamicCamerasChanged();
297

298 299 300
    connect(&_adsbTimer, &QTimer::timeout, this, &Vehicle::_adsbTimerTimeout);
    _adsbTimer.setSingleShot(false);
    _adsbTimer.start(1000);
301 302 303 304

    // Start csv logger
    connect(&_csvLogTimer, &QTimer::timeout, this, &Vehicle::_writeCsvLine);
    _csvLogTimer.start(1000);
305 306
}

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

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

434
    _firmwarePlugin->initializeVehicle(this);
435 436 437 438 439
}

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

441 442
    connect(_firmwarePlugin, &FirmwarePlugin::toolbarIndicatorsChanged, this, &Vehicle::toolBarIndicatorsChanged);

443
    connect(this, &Vehicle::coordinateChanged,      this, &Vehicle::_updateDistanceHeadingToHome);
444
    connect(this, &Vehicle::coordinateChanged,      this, &Vehicle::_updateDistanceToGCS);
445
    connect(this, &Vehicle::homePositionChanged,    this, &Vehicle::_updateDistanceHeadingToHome);
446
    connect(this, &Vehicle::hobbsMeterChanged,      this, &Vehicle::_updateHobbsMeter);
447

448 449
    connect(_toolbox->qgcPositionManager(), &QGCPositionManager::gcsPositionChanged, this, &Vehicle::_updateDistanceToGCS);

450
    _missionManager = new MissionManager(this);
451
    connect(_missionManager, &MissionManager::error,                    this, &Vehicle::_missionManagerError);
452
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_missionLoadComplete);
453 454
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_clearCameraTriggerPoints);
    connect(_missionManager, &MissionManager::sendComplete,             this, &Vehicle::_clearCameraTriggerPoints);
455
    connect(_missionManager, &MissionManager::currentIndexChanged,      this, &Vehicle::_updateHeadingToNextWP);
456

457 458 459
    connect(_missionManager, &MissionManager::sendComplete,             _trajectoryPoints, &TrajectoryPoints::clear);
    connect(_missionManager, &MissionManager::newMissionItemsAvailable, _trajectoryPoints, &TrajectoryPoints::clear);

460
    _parameterManager = new ParameterManager(this);
Don Gagne's avatar
Don Gagne committed
461
    connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
462

Gus Grubba's avatar
Gus Grubba committed
463 464
    _objectAvoidance = new VehicleObjectAvoidance(this, this);

465
    // GeoFenceManager needs to access ParameterManager so make sure to create after
466
    _geoFenceManager = new GeoFenceManager(this);
467
    connect(_geoFenceManager, &GeoFenceManager::error,          this, &Vehicle::_geoFenceManagerError);
468
    connect(_geoFenceManager, &GeoFenceManager::loadComplete,   this, &Vehicle::_geoFenceLoadComplete);
469

470
    _rallyPointManager = new RallyPointManager(this);
471 472
    connect(_rallyPointManager, &RallyPointManager::error,          this, &Vehicle::_rallyPointManagerError);
    connect(_rallyPointManager, &RallyPointManager::loadComplete,   this, &Vehicle::_rallyPointLoadComplete);
473

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

477 478 479 480 481
    // Build FactGroup object model

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

    _hobbsFact.setRawValue(QVariant(QString("0000:00:00")));
499
    _addFact(&_hobbsFact,               _hobbsFactName);
500

501
    _addFactGroup(&_gpsFactGroup,               _gpsFactGroupName);
DonLakeFlyer's avatar
DonLakeFlyer committed
502 503
    _addFactGroup(&_battery1FactGroup,          _battery1FactGroupName);
    _addFactGroup(&_battery2FactGroup,          _battery2FactGroupName);
504 505 506 507 508
    _addFactGroup(&_windFactGroup,              _windFactGroupName);
    _addFactGroup(&_vibrationFactGroup,         _vibrationFactGroupName);
    _addFactGroup(&_temperatureFactGroup,       _temperatureFactGroupName);
    _addFactGroup(&_clockFactGroup,             _clockFactGroupName);
    _addFactGroup(&_distanceSensorFactGroup,    _distanceSensorFactGroupName);
509
    _addFactGroup(&_estimatorStatusFactGroup,   _estimatorStatusFactGroupName);
510

Jacob Walser's avatar
Jacob Walser committed
511
    // Add firmware-specific fact groups, if provided
512 513 514 515 516 517 518
    QMap<QString, FactGroup*>* fwFactGroups = _firmwarePlugin->factGroups();
    if (fwFactGroups) {
        QMapIterator<QString, FactGroup*> i(*fwFactGroups);
        while(i.hasNext()) {
            i.next();
            _addFactGroup(i.value(), i.key());
        }
519 520
    }

521
    _flightDistanceFact.setRawValue(0);
522
    _flightTimeFact.setRawValue(0);
DonLakeFlyer's avatar
DonLakeFlyer committed
523 524 525
    _flightTimeUpdater.setInterval(1000);
    _flightTimeUpdater.setSingleShot(false);
    connect(&_flightTimeUpdater, &QTimer::timeout, this, &Vehicle::_updateFlightTime);
526

527
    // Set video stream to udp if running ArduSub and Video is disabled
528
    if (sub() && _settingsManager->videoSettings()->videoSource()->rawValue() == VideoSettings::videoDisabled) {
Gus Grubba's avatar
Gus Grubba committed
529
        _settingsManager->videoSettings()->videoSource()->setRawValue(VideoSettings::videoSourceUDPH264);
530 531
    }

532 533 534 535 536 537 538 539 540 541
    //-- 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
542 543

    _pidTuningMessages << MAVLINK_MSG_ID_ATTITUDE << MAVLINK_MSG_ID_ATTITUDE_TARGET;
544 545
}

546 547
Vehicle::~Vehicle()
{
Don Gagne's avatar
Don Gagne committed
548 549
    qCDebug(VehicleLog) << "~Vehicle" << this;

550
    delete _missionManager;
551
    _missionManager = nullptr;
552

553
    delete _autopilotPlugin;
554
    _autopilotPlugin = nullptr;
555

556
    delete _mav;
557
    _mav = nullptr;
dogmaphobic's avatar
dogmaphobic committed
558

559
#if defined(QGC_AIRMAP_ENABLED)
560 561
    if (_airspaceVehicleManager) {
        delete _airspaceVehicleManager;
562
    }
563
#endif
564 565
}

566 567 568
void Vehicle::prepareDelete()
{
    if(_cameras) {
569 570 571
        // because of _cameras QML bindings check for nullptr won't work in the binding pipeline
        // the dangling pointer access will cause a runtime fault
        auto tmpCameras = _cameras;
572
        _cameras = nullptr;
573
        delete tmpCameras;
574 575 576 577 578
        emit dynamicCamerasChanged();
        qApp->processEvents();
    }
}

579 580 581
void Vehicle::_offlineFirmwareTypeSettingChanged(QVariant value)
{
    _firmwareType = static_cast<MAV_AUTOPILOT>(value.toInt());
582
    _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
583 584 585 586 587 588 589 590 591 592 593
    emit firmwareTypeChanged();
}

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

void Vehicle::_offlineCruiseSpeedSettingChanged(QVariant value)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
594 595
    _defaultCruiseSpeed = value.toDouble();
    emit defaultCruiseSpeedChanged(_defaultCruiseSpeed);
596 597 598 599
}

void Vehicle::_offlineHoverSpeedSettingChanged(QVariant value)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
600 601
    _defaultHoverSpeed = value.toDouble();
    emit defaultHoverSpeedChanged(_defaultHoverSpeed);
602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632
}

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()
633 634 635 636 637 638 639 640
{
    _messagesReceived   = 0;
    _messagesSent       = 0;
    _messagesLost       = 0;
    _messageSeq         = 0;
    _heardFrom          = false;
}

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

Don Gagne's avatar
Don Gagne committed
650
    if (message.sysid != _id && message.sysid != 0) {
651 652 653 654
        // 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;
        }
655
    }
656

657 658 659
    if (!_containsLink(link)) {
        _addLink(link);
    }
dogmaphobic's avatar
dogmaphobic committed
660

661 662 663 664 665 666 667 668 669 670 671
    //-- Check link status
    _messagesReceived++;
    emit messagesReceivedChanged();
    if(!_heardFrom) {
        if(message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
            _heardFrom = true;
            _compID = message.compid;
            _messageSeq = message.seq + 1;
        }
    } else {
        if(_compID == message.compid) {
Gus Grubba's avatar
Gus Grubba committed
672
            uint16_t seq_received = static_cast<uint16_t>(message.seq);
673 674 675 676 677 678 679 680 681 682 683 684 685 686
            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
687
    // Give the plugin a change to adjust the message contents
688 689 690
    if (!_firmwarePlugin->adjustIncomingMavlinkMessage(this, &message)) {
        return;
    }
dogmaphobic's avatar
dogmaphobic committed
691

692 693 694 695 696
    // Give the Core Plugin access to all mavlink traffic
    if (!_toolbox->corePlugin()->mavlinkMessage(this, link, message)) {
        return;
    }

697
    switch (message.msgid) {
698 699 700 701 702 703
    case MAVLINK_MSG_ID_HOME_POSITION:
        _handleHomePosition(message);
        break;
    case MAVLINK_MSG_ID_HEARTBEAT:
        _handleHeartbeat(message);
        break;
704 705 706
    case MAVLINK_MSG_ID_RADIO_STATUS:
        _handleRadioStatus(message);
        break;
707 708 709 710 711 712
    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
713 714 715 716 717 718
    case MAVLINK_MSG_ID_BATTERY_STATUS:
        _handleBatteryStatus(message);
        break;
    case MAVLINK_MSG_ID_SYS_STATUS:
        _handleSysStatus(message);
        break;
719 720 721 722 723 724 725 726 727 728 729 730
    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;
731 732 733
    case MAVLINK_MSG_ID_VIBRATION:
        _handleVibration(message);
        break;
Don Gagne's avatar
Don Gagne committed
734 735 736
    case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
        _handleExtendedSysState(message);
        break;
737 738 739
    case MAVLINK_MSG_ID_COMMAND_ACK:
        _handleCommandAck(message);
        break;
740 741 742
    case MAVLINK_MSG_ID_COMMAND_LONG:
        _handleCommandLong(message);
        break;
743
    case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
744
        _handleAutopilotVersion(link, message);
745
        break;
746 747 748
    case MAVLINK_MSG_ID_PROTOCOL_VERSION:
        _handleProtocolVersion(link, message);
        break;
749 750 751
    case MAVLINK_MSG_ID_WIND_COV:
        _handleWindCov(message);
        break;
752 753 754
    case MAVLINK_MSG_ID_HIL_ACTUATOR_CONTROLS:
        _handleHilActuatorControls(message);
        break;
755 756 757 758 759 760
    case MAVLINK_MSG_ID_LOGGING_DATA:
        _handleMavlinkLoggingData(message);
        break;
    case MAVLINK_MSG_ID_LOGGING_DATA_ACKED:
        _handleMavlinkLoggingDataAcked(message);
        break;
761 762 763 764 765 766 767 768 769 770 771 772
    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;
773 774 775 776 777 778 779 780
    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);
781
        break;
782 783
    case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED:
        _handleCameraImageCaptured(message);
784
        break;
785 786 787
    case MAVLINK_MSG_ID_ADSB_VEHICLE:
        _handleADSBVehicle(message);
        break;
788 789 790
    case MAVLINK_MSG_ID_HIGH_LATENCY2:
        _handleHighLatency2(message);
        break;
791 792 793
    case MAVLINK_MSG_ID_ATTITUDE:
        _handleAttitude(message);
        break;
794 795
    case MAVLINK_MSG_ID_ATTITUDE_QUATERNION:
        _handleAttitudeQuaternion(message);
DonLakeFlyer's avatar
DonLakeFlyer committed
796 797 798 799
        break;
    case MAVLINK_MSG_ID_ATTITUDE_TARGET:
        _handleAttitudeTarget(message);
        break;
800 801 802
    case MAVLINK_MSG_ID_DISTANCE_SENSOR:
        _handleDistanceSensor(message);
        break;
803 804 805
    case MAVLINK_MSG_ID_ESTIMATOR_STATUS:
        _handleEstimatorStatus(message);
        break;
806
    case MAVLINK_MSG_ID_STATUSTEXT:
Don Gagne's avatar
Don Gagne committed
807 808 809 810
        _handleStatusText(message, false /* longVersion */);
        break;
    case MAVLINK_MSG_ID_STATUSTEXT_LONG:
        _handleStatusText(message, true /* longVersion */);
811
        break;
812 813 814
    case MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS:
        _handleOrbitExecutionStatus(message);
        break;
815 816 817
    case MAVLINK_MSG_ID_MESSAGE_INTERVAL:
        _handleMessageInterval(message);
        break;
DonLakeFlyer's avatar
DonLakeFlyer committed
818 819 820
    case MAVLINK_MSG_ID_PING:
        _handlePing(link, message);
        break;
Gus Grubba's avatar
Gus Grubba committed
821 822 823
    case MAVLINK_MSG_ID_MOUNT_ORIENTATION:
        _handleGimbalOrientation(message);
        break;
Gus Grubba's avatar
Gus Grubba committed
824 825 826
    case MAVLINK_MSG_ID_OBSTACLE_DISTANCE:
        _handleObstacleDistance(message);
        break;
827

828 829 830 831 832 833 834
    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;
835

836
        // Following are ArduPilot dialect messages
837 838 839 840
#if !defined(NO_ARDUPILOT_DIALECT)
    case MAVLINK_MSG_ID_CAMERA_FEEDBACK:
        _handleCameraFeedback(message);
        break;
841 842 843
    case MAVLINK_MSG_ID_WIND:
        _handleWind(message);
        break;
844
#endif
845
    }
dogmaphobic's avatar
dogmaphobic committed
846

847 848
    // 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
849
    emit mavlinkMessageReceived(message);
dogmaphobic's avatar
dogmaphobic committed
850

851 852 853
    _uas->receiveMessage(message);
}

854
#if !defined(NO_ARDUPILOT_DIALECT)
855 856 857 858 859 860 861 862 863 864
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));
}
865
#endif
866

867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902
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);
}

903 904 905 906 907 908 909 910 911 912 913 914 915
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
916
void Vehicle::_handleStatusText(mavlink_message_t& message, bool longVersion)
917
{
Don Gagne's avatar
Don Gagne committed
918 919 920 921 922 923
    QByteArray  b;
    QString     messageText;
    int         severity;

    if (longVersion) {
        b.resize(MAVLINK_MSG_STATUSTEXT_LONG_FIELD_TEXT_LEN+1);
924 925 926 927
        mavlink_statustext_long_t statustextLong;
        mavlink_msg_statustext_long_decode(&message, &statustextLong);
        strncpy(b.data(), statustextLong.text, MAVLINK_MSG_STATUSTEXT_LONG_FIELD_TEXT_LEN);
        severity = statustextLong.severity;
Don Gagne's avatar
Don Gagne committed
928 929
    } else {
        b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
930 931 932 933
        mavlink_statustext_t statustext;
        mavlink_msg_statustext_decode(&message, &statustext);
        strncpy(b.data(), statustext.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN);
        severity = statustext.severity;
Don Gagne's avatar
Don Gagne committed
934
    }
935
    b[b.length()-1] = '\0';
Don Gagne's avatar
Don Gagne committed
936
    messageText = QString(b);
937 938

    bool skipSpoken = false;
Don Gagne's avatar
Don Gagne committed
939
    bool ardupilotPrearm = messageText.startsWith(QStringLiteral("PreArm"));
Don Gagne's avatar
Don Gagne committed
940
    bool px4Prearm = messageText.startsWith(QStringLiteral("preflight"), Qt::CaseInsensitive) && severity >= MAV_SEVERITY_CRITICAL;
Don Gagne's avatar
Don Gagne committed
941
    if (ardupilotPrearm || px4Prearm) {
942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962
        // 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);
}

963 964 965 966 967 968 969 970
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);
971
    _throttlePctFact.setRawValue(static_cast<int16_t>(vfrHud.throttle));
972 973
}

974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026
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.*/
1027 1028
        } mavlink_estimator_status_t;
    };
1029 1030 1031
#endif
}

1032 1033 1034 1035
void Vehicle::_handleDistanceSensor(mavlink_message_t& message)
{
    mavlink_distance_sensor_t distanceSensor;

1036 1037 1038 1039
    mavlink_msg_distance_sensor_decode(&message, &distanceSensor);\

    if (!_distanceSensorFactGroup.idSet()) {
        _distanceSensorFactGroup.setIdSet(true);
1040
        _distanceSensorFactGroup.setId(distanceSensor.id);
1041 1042
    }

1043
    if (_distanceSensorFactGroup.id() != distanceSensor.id) {
1044 1045 1046
        // We can only handle a single sensor reporting
        return;
    }
1047 1048 1049 1050 1051 1052 1053 1054

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

    orientation2Fact_s rgOrientation2Fact[] =
    {
1055 1056 1057 1058 1059 1060 1061 1062 1063 1064
        { 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() },
1065 1066 1067 1068 1069
    };

    for (size_t i=0; i<sizeof(rgOrientation2Fact)/sizeof(rgOrientation2Fact[0]); i++) {
        const orientation2Fact_s& orientation2Fact = rgOrientation2Fact[i];
        if (orientation2Fact.orientation == distanceSensor.orientation) {
1070
            orientation2Fact.fact->setRawValue(distanceSensor.current_distance / 100.0); // cm to meters
1071 1072 1073 1074
        }
    }
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1075 1076 1077 1078 1079 1080 1081 1082 1083
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
1084 1085 1086
    _setpointFactGroup.roll()->setRawValue(qRadiansToDegrees(roll));
    _setpointFactGroup.pitch()->setRawValue(qRadiansToDegrees(pitch));
    _setpointFactGroup.yaw()->setRawValue(qRadiansToDegrees(yaw));
DonLakeFlyer's avatar
DonLakeFlyer committed
1087 1088 1089 1090 1091 1092

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

1093
void Vehicle::_handleAttitudeWorker(double rollRadians, double pitchRadians, double yawRadians)
DonLakeFlyer's avatar
DonLakeFlyer committed
1094
{
1095
    double roll, pitch, yaw;
1096

1097 1098 1099
    roll = QGC::limitAngleToPMPIf(rollRadians);
    pitch = QGC::limitAngleToPMPIf(pitchRadians);
    yaw = QGC::limitAngleToPMPIf(yawRadians);
1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110 1111 1112 1113

    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);
1114 1115 1116 1117 1118 1119 1120 1121 1122 1123 1124 1125 1126 1127 1128 1129 1130 1131 1132 1133 1134 1135 1136 1137 1138 1139
}

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);
1140 1141 1142 1143

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

1146 1147 1148 1149 1150
void Vehicle::_handleGpsRawInt(mavlink_message_t& message)
{
    mavlink_gps_raw_int_t gpsRawInt;
    mavlink_msg_gps_raw_int_decode(&message, &gpsRawInt);

1151 1152
    _gpsRawIntMessageAvailable = true;

1153
    if (gpsRawInt.fix_type >= GPS_FIX_TYPE_3D_FIX) {
1154
        if (!_globalPositionIntMessageAvailable) {
1155 1156 1157 1158 1159
            QGeoCoordinate newPosition(gpsRawInt.lat  / (double)1E7, gpsRawInt.lon / (double)1E7, gpsRawInt.alt  / 1000.0);
            if (newPosition != _coordinate) {
                _coordinate = newPosition;
                emit coordinateChanged(_coordinate);
            }
1160
            _altitudeAMSLFact.setRawValue(gpsRawInt.alt / 1000.0);
1161 1162 1163
        }
    }

1164 1165
    _gpsFactGroup.lat()->setRawValue(gpsRawInt.lat * 1e-7);
    _gpsFactGroup.lon()->setRawValue(gpsRawInt.lon * 1e-7);
1166
    _gpsFactGroup.count()->setRawValue(gpsRawInt.satellites_visible == 255 ? 0 : gpsRawInt.satellites_visible);
1167 1168 1169
    _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);
1170 1171 1172 1173 1174 1175 1176 1177
    _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);

1178 1179 1180 1181 1182
    _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.
1183
    if (globalPositionInt.lat == 0 && globalPositionInt.lon == 0) {
1184 1185 1186
        return;
    }

1187
    _globalPositionIntMessageAvailable = true;
1188 1189 1190 1191 1192
    QGeoCoordinate newPosition(globalPositionInt.lat  / (double)1E7, globalPositionInt.lon / (double)1E7, globalPositionInt.alt  / 1000.0);
    if (newPosition != _coordinate) {
        _coordinate = newPosition;
        emit coordinateChanged(_coordinate);
    }
1193 1194
}

1195 1196 1197 1198 1199
void Vehicle::_handleHighLatency2(mavlink_message_t& message)
{
    mavlink_high_latency2_t highLatency2;
    mavlink_msg_high_latency2_decode(&message, &highLatency2);

1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217
    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);
    }

1218 1219 1220 1221 1222 1223 1224 1225 1226
    _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);
1227 1228
    _altitudeRelativeFact.setRawValue(std::numeric_limits<double>::quiet_NaN());
    _altitudeAMSLFact.setRawValue(highLatency2.altitude);
1229 1230 1231 1232

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

DonLakeFlyer's avatar
DonLakeFlyer committed
1233
    _battery1FactGroup.percentRemaining()->setRawValue(highLatency2.battery);
1234 1235 1236 1237 1238 1239 1240 1241

    _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);
1242 1243

    struct failure2Sensor_s {
1244
        HL_FAILURE_FLAG         failureBit;
1245 1246 1247 1248
        MAV_SYS_STATUS_SENSOR   sensorBit;
    };

    static const failure2Sensor_s rgFailure2Sensor[] = {
1249 1250 1251 1252 1253 1254
        { 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 },
1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271
    };

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

1274 1275 1276 1277 1278
void Vehicle::_handleAltitude(mavlink_message_t& message)
{
    mavlink_altitude_t altitude;
    mavlink_msg_altitude_decode(&message, &altitude);

1279 1280 1281 1282 1283 1284 1285
    // 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);
        }
    }
1286 1287
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1288 1289
void Vehicle::_setCapabilities(uint64_t capabilityBits)
{
1290
    _capabilityBits = capabilityBits;
DonLakeFlyer's avatar
DonLakeFlyer committed
1291
    _vehicleCapabilitiesKnown = true;
1292
    emit capabilitiesKnownChanged(true);
1293
    emit capabilityBitsChanged(_capabilityBits);
DonLakeFlyer's avatar
DonLakeFlyer committed
1294

1295 1296 1297 1298 1299
    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);
1300
    qCDebug(VehicleLog) << QString("Vehicle %1 MISSION_COMMAND_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_COMMAND_INT ? supports : doesNotSupport);
1301 1302
    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
1303 1304
}

1305
void Vehicle::_handleAutopilotVersion(LinkInterface *link, mavlink_message_t& message)
1306
{
1307 1308
    Q_UNUSED(link);

1309 1310 1311
    mavlink_autopilot_version_t autopilotVersion;
    mavlink_msg_autopilot_version_decode(&message, &autopilotVersion);

Gus Grubba's avatar
Gus Grubba committed
1312 1313 1314
    _uid = (quint64)autopilotVersion.uid;
    emit vehicleUIDChanged();

1315 1316 1317 1318 1319 1320 1321 1322
    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
1323
        setFirmwareVersion(majorVersion, minorVersion, patchVersion, versionType);
1324
    }
1325

Don Gagne's avatar
Don Gagne committed
1326 1327 1328 1329 1330 1331 1332 1333
    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);

1334
        // 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
1335 1336 1337
        _gitHash = "";
        for (int i = 7; i >= 0; i--) {
            _gitHash.append(QString("%1").arg(autopilotVersion.flight_custom_version[i], 2, 16, QChar('0')));
1338
        }
Don Gagne's avatar
Don Gagne committed
1339 1340
    } else {
        // APM Firmware stores the first 8 characters of the git hash as an ASCII character string
1341 1342 1343 1344
        char nullStr[9];
        strncpy(nullStr, (char*)autopilotVersion.flight_custom_version, 8);
        nullStr[8] = 0;
        _gitHash = nullStr;
1345
    }
1346 1347 1348
    if (_toolbox->corePlugin()->options()->checkFirmwareVersion()) {
        _firmwarePlugin->checkIfIsLatestStable(this);
    }
Don Gagne's avatar
Don Gagne committed
1349
    emit gitHashChanged(_gitHash);
1350

DonLakeFlyer's avatar
DonLakeFlyer committed
1351 1352
    _setCapabilities(autopilotVersion.capabilities);
    _startPlanRequest();
1353 1354
}

1355 1356 1357 1358 1359 1360 1361
void Vehicle::_handleProtocolVersion(LinkInterface *link, mavlink_message_t& message)
{
    Q_UNUSED(link);

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

1362 1363 1364
    qCDebug(VehicleLog) << "_handleProtocolVersion" << protoVersion.max_version;

    _mavlinkProtocolRequestComplete = true;
1365
    _setMaxProtoVersion(protoVersion.max_version);
1366
    _startPlanRequest();
1367 1368 1369
}

void Vehicle::_setMaxProtoVersion(unsigned version) {
1370 1371 1372

    // Set only once or if we need to reduce the max version
    if (_maxProtoVersion == 0 || version < _maxProtoVersion) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1373
        qCDebug(VehicleLog) << "_setMaxProtoVersion before:after" << _maxProtoVersion << version;
1374 1375 1376
        _maxProtoVersion = version;
        emit requestProtocolVersion(_maxProtoVersion);
    }
1377 1378
}

Gus Grubba's avatar
Gus Grubba committed
1379 1380 1381 1382 1383
QString Vehicle::vehicleUIDStr()
{
    QString uid;
    uint8_t* pUid = (uint8_t*)(void*)&_uid;
    uid.sprintf("%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X",
1384 1385 1386 1387 1388 1389 1390 1391
                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
1392 1393 1394
    return uid;
}

1395 1396 1397 1398 1399 1400
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],
1401 1402 1403 1404 1405 1406 1407 1408 1409 1410 1411 1412 1413 1414 1415 1416
            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);
1417 1418
}

1419 1420
void Vehicle::_handleCommandLong(mavlink_message_t& message)
{
1421 1422
#ifdef NO_SERIAL_LINK
    // If not using serial link, bail out.
DonLakeFlyer's avatar
DonLakeFlyer committed
1423 1424
    Q_UNUSED(message)
#else
1425 1426 1427 1428
    mavlink_command_long_t cmd;
    mavlink_msg_command_long_decode(&message, &cmd);

    switch (cmd.command) {
1429 1430 1431 1432 1433 1434 1435 1436 1437 1438
    // 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));
1439
                    emit linksChanged();
1440 1441
                }
            }
1442
        }
1443 1444
        break;
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1445
#endif
1446 1447
}

Don Gagne's avatar
Don Gagne committed
1448 1449 1450 1451 1452 1453 1454
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:
1455 1456
        _setFlying(false);
        _setLanding(false);
Don Gagne's avatar
Don Gagne committed
1457
        break;
1458
    case MAV_LANDED_STATE_TAKEOFF:
Don Gagne's avatar
Don Gagne committed
1459
    case MAV_LANDED_STATE_IN_AIR:
1460 1461 1462 1463 1464 1465 1466 1467 1468
        _setFlying(true);
        _setLanding(false);
        break;
    case MAV_LANDED_STATE_LANDING:
        _setFlying(true);
        _setLanding(true);
        break;
    default:
        break;
Don Gagne's avatar
Don Gagne committed
1469
    }
1470 1471

    if (vtol()) {
1472 1473 1474 1475 1476
        bool vtolInFwdFlight = extendedState.vtol_state == MAV_VTOL_STATE_FW;
        if (vtolInFwdFlight != _vtolInFwdFlight) {
            _vtolInFwdFlight = vtolInFwdFlight;
            emit vtolInFwdFlightChanged(vtolInFwdFlight);
        }
1477
    }
Don Gagne's avatar
Don Gagne committed
1478 1479
}

1480 1481 1482 1483 1484 1485 1486 1487 1488 1489 1490 1491 1492
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);
}

1493 1494 1495 1496 1497 1498 1499 1500
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));

1501 1502 1503 1504
    if (direction < 0) {
        direction += 360;
    }

1505 1506 1507 1508 1509
    _windFactGroup.direction()->setRawValue(direction);
    _windFactGroup.speed()->setRawValue(speed);
    _windFactGroup.verticalSpeed()->setRawValue(0);
}

1510
#if !defined(NO_ARDUPILOT_DIALECT)
1511 1512 1513 1514 1515
void Vehicle::_handleWind(mavlink_message_t& message)
{
    mavlink_wind_t wind;
    mavlink_msg_wind_decode(&message, &wind);

1516 1517 1518 1519 1520 1521
    // We don't want negative wind angles
    float direction = wind.direction;
    if (direction < 0) {
        direction += 360;
    }
    _windFactGroup.direction()->setRawValue(direction);
1522 1523 1524
    _windFactGroup.speed()->setRawValue(wind.speed);
    _windFactGroup.verticalSpeed()->setRawValue(wind.speed_z);
}
1525
#endif
1526

DonLakeFlyer's avatar
DonLakeFlyer committed
1527 1528 1529 1530 1531 1532 1533
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
1534 1535 1536 1537 1538 1539
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
DonLakeFlyer committed
1540
        _battery1FactGroup.current()->setRawValue(VehicleBatteryFactGroup::_currentUnavailable);
Don Gagne's avatar
Don Gagne committed
1541
    } else {
1542
        // Current is in Amps, current_battery is 10 * milliamperes (1 = 10 milliampere)
DonLakeFlyer's avatar
DonLakeFlyer committed
1543
        _battery1FactGroup.current()->setRawValue((float)sysStatus.current_battery / 100.0f);
Don Gagne's avatar
Don Gagne committed
1544 1545
    }
    if (sysStatus.voltage_battery == UINT16_MAX) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1546
        _battery1FactGroup.voltage()->setRawValue(VehicleBatteryFactGroup::_voltageUnavailable);
Don Gagne's avatar
Don Gagne committed
1547
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1548
        _battery1FactGroup.voltage()->setRawValue((double)sysStatus.voltage_battery / 1000.0);
1549
        // current_battery is 10 mA and voltage_battery is 1mV. (10/1e3 times 1/1e3 = 1/1e5)
DonLakeFlyer's avatar
DonLakeFlyer committed
1550
        _battery1FactGroup.instantPower()->setRawValue((float)(sysStatus.current_battery*sysStatus.voltage_battery)/(100000.0));
Don Gagne's avatar
Don Gagne committed
1551
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1552
    _battery1FactGroup.percentRemaining()->setRawValue(sysStatus.battery_remaining);
1553

1554 1555 1556
    if (sysStatus.battery_remaining > 0) {
        if (sysStatus.battery_remaining < _settingsManager->appSettings()->batteryPercentRemainingAnnounce()->rawValue().toInt() &&
                sysStatus.battery_remaining < _lastAnnouncedLowBatteryPercent) {
1557
            _say(tr("%1 low battery: %2 percent remaining").arg(_vehicleIdSpeech()).arg(sysStatus.battery_remaining));
1558
        }
1559
        _lastAnnouncedLowBatteryPercent = sysStatus.battery_remaining;
1560
    }
1561

1562 1563 1564 1565 1566 1567 1568 1569 1570 1571 1572 1573
    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);
    }
1574

DonLakeFlyer's avatar
DonLakeFlyer committed
1575 1576 1577 1578 1579 1580
    // 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);
    }
1581 1582 1583 1584 1585

    uint32_t newSensorsUnhealthy = _onboardControlSensorsEnabled & ~_onboardControlSensorsHealth;
    if (newSensorsUnhealthy != _onboardControlSensorsUnhealthy) {
        _onboardControlSensorsUnhealthy = newSensorsUnhealthy;
        emit unhealthySensorsChanged();
1586
        emit sensorsUnhealthyBitsChanged(_onboardControlSensorsUnhealthy);
1587
    }
Don Gagne's avatar
Don Gagne committed
1588 1589 1590 1591 1592 1593 1594
}

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
1595 1596
    VehicleBatteryFactGroup& batteryFactGroup = bat_status.id == 0 ? _battery1FactGroup : _battery2FactGroup;

Don Gagne's avatar
Don Gagne committed
1597
    if (bat_status.temperature == INT16_MAX) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1598
        batteryFactGroup.temperature()->setRawValue(VehicleBatteryFactGroup::_temperatureUnavailable);
Don Gagne's avatar
Don Gagne committed
1599
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1600
        batteryFactGroup.temperature()->setRawValue((double)bat_status.temperature / 100.0);
Don Gagne's avatar
Don Gagne committed
1601 1602
    }
    if (bat_status.current_consumed == -1) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1603
        batteryFactGroup.mahConsumed()->setRawValue(VehicleBatteryFactGroup::_mahConsumedUnavailable);
Don Gagne's avatar
Don Gagne committed
1604
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1605
        batteryFactGroup.mahConsumed()->setRawValue(bat_status.current_consumed);
Don Gagne's avatar
Don Gagne committed
1606 1607 1608 1609 1610 1611 1612 1613 1614 1615 1616 1617
    }

    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
1618
    batteryFactGroup.cellCount()->setRawValue(cellCount);
1619 1620

    //-- Time remaining in seconds (0 means not supported)
DonLakeFlyer's avatar
DonLakeFlyer committed
1621
    batteryFactGroup.timeRemaining()->setRawValue(bat_status.time_remaining);
1622 1623
    //-- Battery charge state (0 means not supported)
    if(bat_status.charge_state <= MAV_BATTERY_CHARGE_STATE_UNHEALTHY) {
DonLakeFlyer's avatar
DonLakeFlyer committed
1624
        batteryFactGroup.chargeState()->setRawValue(bat_status.charge_state);
1625
    } else {
DonLakeFlyer's avatar
DonLakeFlyer committed
1626
        batteryFactGroup.chargeState()->setRawValue(0);
1627 1628 1629 1630 1631 1632
    }
    //-- 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
1633 1634
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1635 1636 1637 1638 1639 1640 1641 1642
void Vehicle::_setHomePosition(QGeoCoordinate& homeCoord)
{
    if (homeCoord != _homePosition) {
        _homePosition = homeCoord;
        emit homePositionChanged(_homePosition);
    }
}

1643 1644 1645
void Vehicle::_handleHomePosition(mavlink_message_t& message)
{
    mavlink_home_position_t homePos;
dogmaphobic's avatar
dogmaphobic committed
1646

1647
    mavlink_msg_home_position_decode(&message, &homePos);
Don Gagne's avatar
Don Gagne committed
1648 1649 1650 1651

    QGeoCoordinate newHomePosition (homePos.latitude / 10000000.0,
                                    homePos.longitude / 10000000.0,
                                    homePos.altitude / 1000.0);
DonLakeFlyer's avatar
DonLakeFlyer committed
1652
    _setHomePosition(newHomePosition);
1653 1654
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1655
void Vehicle::_updateArmed(bool armed)
1656
{
DonLakeFlyer's avatar
DonLakeFlyer committed
1657 1658
    if (_armed != armed) {
        _armed = armed;
1659
        emit armedChanged(_armed);
dogmaphobic's avatar
dogmaphobic committed
1660

1661 1662
        // We are transitioning to the armed state, begin tracking trajectory points for the map
        if (_armed) {
1663 1664
            _trajectoryPoints->start();
            _flightTimerStart();
1665
            _clearCameraTriggerPoints();
1666
        } else {
1667
            _trajectoryPoints->stop();
DonLakeFlyer's avatar
DonLakeFlyer committed
1668
            _flightTimerStop();
1669
            // Also handle Video Streaming
1670 1671 1672 1673 1674
            if(qgcApp()->toolbox()->videoManager()->videoReceiver()) {
                if(_settingsManager->videoSettings()->disableWhenDisarmed()->rawValue().toBool()) {
                    _settingsManager->videoSettings()->streamEnabled()->setRawValue(false);
                    qgcApp()->toolbox()->videoManager()->videoReceiver()->stop();
                }
1675
            }
1676
        }
1677
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
1678 1679
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1680 1681 1682 1683 1684 1685
void Vehicle::_handlePing(LinkInterface* link, mavlink_message_t& message)
{
    mavlink_ping_t      ping;
    mavlink_message_t   msg;

    mavlink_msg_ping_decode(&message, &ping);
1686 1687
    mavlink_msg_ping_pack_chan(static_cast<uint8_t>(_mavlink->getSystemId()),
                               static_cast<uint8_t>(_mavlink->getComponentId()),
DonLakeFlyer's avatar
DonLakeFlyer committed
1688 1689 1690 1691 1692 1693 1694 1695 1696
                               priorityLink()->mavlinkChannel(),
                               &msg,
                               ping.time_usec,
                               ping.seq,
                               message.sysid,
                               message.compid);
    sendMessageOnLink(link, msg);
}

DonLakeFlyer's avatar
DonLakeFlyer committed
1697 1698 1699 1700 1701 1702 1703 1704 1705 1706 1707 1708 1709 1710 1711 1712 1713 1714 1715 1716 1717 1718 1719 1720
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);
    }
1721 1722

    if (heartbeat.base_mode != _base_mode || heartbeat.custom_mode != _custom_mode) {
1723 1724 1725 1726 1727 1728
        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();
        }
1729 1730
        _base_mode = heartbeat.base_mode;
        _custom_mode = heartbeat.custom_mode;
1731 1732 1733
        if (previousFlightMode != flightMode()) {
            emit flightModeChanged(flightMode());
        }
1734 1735 1736
    }
}

1737 1738
void Vehicle::_handleRadioStatus(mavlink_message_t& message)
{
1739

1740 1741 1742
    //-- Process telemetry status message
    mavlink_radio_status_t rstatus;
    mavlink_msg_radio_status_decode(&message, &rstatus);
1743

1744 1745
    int rssi    = rstatus.rssi;
    int remrssi = rstatus.remrssi;
1746 1747
    int lnoise = (int)(int8_t)rstatus.noise;
    int rnoise = (int)(int8_t)rstatus.remnoise;
1748 1749 1750 1751 1752 1753 1754 1755 1756 1757 1758 1759 1760 1761
    //-- 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);
1762 1763 1764
    } else {
        rssi    = (int)(int8_t)rstatus.rssi;
        remrssi = (int)(int8_t)rstatus.remrssi;
1765 1766 1767 1768 1769 1770 1771 1772 1773 1774 1775 1776 1777 1778 1779 1780 1781 1782 1783 1784 1785 1786
    }
    //-- 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);
    }
1787 1788
    if(_telemetryLNoise != lnoise) {
        _telemetryLNoise = lnoise;
1789 1790
        emit telemetryLNoiseChanged(_telemetryLNoise);
    }
1791 1792
    if(_telemetryRNoise != rnoise) {
        _telemetryRNoise = rnoise;
1793 1794 1795 1796
        emit telemetryRNoiseChanged(_telemetryRNoise);
    }
}

1797 1798 1799 1800 1801 1802 1803 1804 1805 1806 1807 1808 1809 1810 1811 1812 1813 1814 1815 1816 1817 1818 1819 1820 1821 1822 1823 1824 1825 1826 1827 1828 1829 1830 1831 1832 1833 1834 1835 1836 1837 1838 1839 1840 1841 1842 1843 1844 1845 1846 1847 1848 1849 1850 1851 1852 1853 1854 1855 1856 1857 1858 1859 1860 1861
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
1862 1863 1864 1865
    for (int i=0; i<cMaxRcChannels; i++) {
        pwmValues[i] = -1;
    }

1866 1867 1868 1869 1870 1871
    for (int i=0; i<8; i++) {
        uint16_t channelValue = *_rgChannelvalues[i];

        if (channelValue == UINT16_MAX) {
            pwmValues[i] = -1;
        } else {
1872
            channelCount = i + 1;
1873 1874 1875 1876 1877 1878 1879 1880 1881 1882 1883
            pwmValues[i] = channelValue;
        }
    }
    for (int i=9; i<18; i++) {
        pwmValues[i] = -1;
    }

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

1884 1885 1886 1887 1888 1889 1890 1891 1892 1893 1894 1895 1896 1897 1898 1899 1900 1901
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);
}

1902 1903
bool Vehicle::_containsLink(LinkInterface* link)
{
Don Gagne's avatar
Don Gagne committed
1904
    return _links.contains(link);
1905 1906 1907 1908 1909 1910
}

void Vehicle::_addLink(LinkInterface* link)
{
    if (!_containsLink(link)) {
        qCDebug(VehicleLog) << "_addLink:" << QString("%1").arg((ulong)link, 0, 16);
1911
        _links += link;
1912
        if (_links.count() <= 1) {
acfloria's avatar
acfloria committed
1913
            _updatePriorityLink(true /* updateActive */, false /* sendCommand */);
1914
        } else {
acfloria's avatar
acfloria committed
1915
            _updatePriorityLink(true /* updateActive */, true /* sendCommand */);
1916 1917
        }

1918 1919
        connect(_toolbox->linkManager(), &LinkManager::linkInactive, this, &Vehicle::_linkInactiveOrDeleted);
        connect(_toolbox->linkManager(), &LinkManager::linkDeleted, this, &Vehicle::_linkInactiveOrDeleted);
1920
        connect(link, &LinkInterface::highLatencyChanged, this, &Vehicle::_updateHighLatencyLink);
1921
        connect(link, &LinkInterface::activeChanged, this, &Vehicle::_linkActiveChanged);
1922 1923 1924
    }
}

Don Gagne's avatar
Don Gagne committed
1925
void Vehicle::_linkInactiveOrDeleted(LinkInterface* link)
1926
{
Don Gagne's avatar
Don Gagne committed
1927
    qCDebug(VehicleLog) << "_linkInactiveOrDeleted linkCount" << _links.count();
dogmaphobic's avatar
dogmaphobic committed
1928

Don Gagne's avatar
Don Gagne committed
1929
    _links.removeOne(link);
1930

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

Don Gagne's avatar
Don Gagne committed
1933
    if (_links.count() == 0 && !_allLinksInactiveSent) {
Don Gagne's avatar
Don Gagne committed
1934
        qCDebug(VehicleLog) << "All links inactive";
Don Gagne's avatar
Don Gagne committed
1935 1936 1937
        // Make sure to not send this more than one time
        _allLinksInactiveSent = true;
        emit allLinksInactive(this);
1938 1939 1940
    }
}

1941 1942 1943 1944 1945 1946 1947 1948 1949 1950 1951 1952 1953
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)
{
1954 1955 1956 1957 1958
    // Make sure this is still a good link
    if (!link || !_links.contains(link) || !link->isConnected()) {
        return;
    }

1959 1960 1961 1962 1963 1964
#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

1965
    // Give the plugin a chance to adjust
1966
    _firmwarePlugin->adjustOutgoingMavlinkMessage(this, link, &message);
1967 1968 1969 1970 1971 1972

    // 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);
1973 1974
    _messagesSent++;
    emit messagesSentChanged();
1975 1976
}

1977
void Vehicle::_updatePriorityLink(bool updateActive, bool sendCommand)
1978
{
1979
    emit linksPropertiesChanged();
1980 1981 1982

    // if the priority link is commanded and still active don't change anything
    if (_priorityLinkCommanded) {
1983
        if (_priorityLink.data()->link_active(_id)) {
1984 1985 1986 1987 1988 1989
            return;
        } else {
            _priorityLinkCommanded = false;
        }
    }

1990
    LinkInterface* newPriorityLink = nullptr;
1991

1992
    // This routine specifically does not clear _priorityLink when there are no links remaining.
1993
    // By doing this we hold a reference on the last link as the Vehicle shuts down. Thus preventing shutdown
1994
    // ordering nullptr pointer crashes where priorityLink() is still called during shutdown sequence.
1995 1996 1997 1998 1999 2000 2001
    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]) {
2002
            if (!_priorityLink.data()->highLatency() && _priorityLink->link_active(_id)) {
2003 2004 2005 2006
                // 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;
            }
2007 2008 2009 2010
        }
    }

    // The previous priority link is no longer valid. We must no find the best link available in this priority order:
2011 2012 2013
    //      First active direct USB connection
    //      Any active non high latency link
    //      An active high latency link
2014 2015 2016
    //      Any link

#ifndef NO_SERIAL_LINK
2017
    // Search for an active direct usb connection
2018 2019
    for (int i=0; i<_links.count(); i++) {
        LinkInterface* link = _links[i];
2020 2021 2022 2023 2024 2025
        SerialLink* pSerialLink = qobject_cast<SerialLink*>(link);
        if (pSerialLink) {
            LinkConfiguration* config = pSerialLink->getLinkConfiguration();
            if (config) {
                SerialConfiguration* pSerialConfig = qobject_cast<SerialConfiguration*>(config);
                if (pSerialConfig && pSerialConfig->usbDirect()) {
2026
                    if (_priorityLink.data() != link && link->link_active(_id)) {
2027 2028
                        newPriorityLink = link;
                        break;
2029 2030 2031
                    }
                }
            }
2032 2033
        }
    }
2034
#endif
2035

2036
    if (!newPriorityLink) {
2037
        // Search for an active non-high latency link
2038 2039
        for (int i=0; i<_links.count(); i++) {
            LinkInterface* link = _links[i];
2040
            if (!link->highLatency() && link->link_active(_id)) {
2041 2042 2043 2044 2045 2046 2047 2048
                newPriorityLink = link;
                break;
            }
        }
    }

    if (!newPriorityLink) {
        // Search for an active high latency link
2049 2050
        for (int i=0; i<_links.count(); i++) {
            LinkInterface* link = _links[i];
2051
            if (link->highLatency() && link->link_active(_id)) {
2052 2053 2054 2055
                newPriorityLink = link;
                break;
            }
        }
2056 2057
    }

2058 2059 2060
    if (!newPriorityLink) {
        // Use any link
        newPriorityLink = _links[0];
2061
    }
2062

2063
    if (_priorityLink.data() != newPriorityLink) {
2064 2065 2066
        if (_priorityLink) {
            qgcApp()->showMessage((tr("switch to %2 as priority link")).arg(newPriorityLink->getName()));
        }
2067
        _priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink);
2068

2069
        _updateHighLatencyLink(sendCommand);
2070

2071 2072
        emit priorityLinkNameChanged(_priorityLink->getName());
        if (updateActive) {
2073
            _linkActiveChanged(_priorityLink.data(), _priorityLink->link_active(_id), _id);
2074 2075
        }
    }
2076 2077
}

2078 2079 2080 2081 2082 2083 2084 2085 2086 2087 2088 2089 2090 2091 2092 2093
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;
2094 2095 2096 2097 2098 2099 2100 2101 2102 2103 2104 2105 2106 2107 2108 2109 2110 2111 2112 2113 2114 2115 2116 2117 2118 2119 2120 2121 2122 2123 2124 2125 2126 2127 2128 2129 2130 2131 2132 2133 2134
    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;
        }
    }

2135 2136 2137 2138 2139 2140 2141 2142 2143 2144 2145 2146 2147 2148 2149
    default:
        return -1;
    }
}

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

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

2150 2151 2152
QString Vehicle::formatedMessages()
{
    QString messages;
2153
    for(UASMessage* message: _toolbox->uasMessageHandler()->messages()) {
2154 2155 2156 2157 2158
        messages += message->getFormatedText();
    }
    return messages;
}

dogmaphobic's avatar
dogmaphobic committed
2159 2160
void Vehicle::clearMessages()
{
2161
    _toolbox->uasMessageHandler()->clearMessages();
dogmaphobic's avatar
dogmaphobic committed
2162 2163
}

2164 2165 2166 2167 2168 2169 2170 2171 2172
void Vehicle::_handletextMessageReceived(UASMessage* message)
{
    if(message)
    {
        _formatedMessage = message->getFormatedText();
        emit formatedMessageChanged();
    }
}

2173 2174 2175 2176 2177 2178 2179 2180 2181 2182 2183 2184 2185 2186 2187
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
2188

2189
    UASMessageHandler* pMh = _toolbox->uasMessageHandler();
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 2216 2217 2218 2219 2220 2221 2222 2223 2224 2225 2226 2227 2228 2229 2230 2231 2232 2233 2234 2235 2236 2237 2238 2239 2240 2241 2242 2243 2244 2245 2246 2247 2248 2249 2250 2251 2252 2253 2254
    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();
    }
}
2255 2256 2257

void Vehicle::_loadSettings(void)
{
2258 2259 2260
    if (!_active) {
        return;
    }
2261 2262 2263
    QSettings settings;
    settings.beginGroup(QString(_settingsGroup).arg(_id));
    bool convertOk;
Gus Grubba's avatar
Gus Grubba committed
2264
    _joystickMode = static_cast<JoystickMode_t>(settings.value(_joystickModeSettingsKey, JoystickModeRC).toInt(&convertOk));
2265 2266 2267
    if (!convertOk) {
        _joystickMode = JoystickModeRC;
    }
2268
    // Joystick enabled is a global setting so first make sure there are any joysticks connected
2269
    if (_toolbox->joystickManager()->joysticks().count()) {
2270
        setJoystickEnabled(settings.value(_joystickEnabledSettingsKey, false).toBool());
2271
        _startJoystick(true);
2272
    }
2273 2274 2275 2276 2277
}

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

2279
    settings.beginGroup(QString(_settingsGroup).arg(_id));
dogmaphobic's avatar
dogmaphobic committed
2280

2281
    settings.setValue(_joystickModeSettingsKey, _joystickMode);
2282 2283 2284

    // The joystick enabled setting should only be changed if a joystick is present
    // since the checkbox can only be clicked if one is present
2285
    if (_toolbox->joystickManager()->joysticks().count()) {
2286 2287
        settings.setValue(_joystickEnabledSettingsKey, _joystickEnabled);
    }
2288 2289 2290 2291 2292 2293 2294 2295 2296 2297 2298 2299 2300
}

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
2301

2302 2303 2304 2305 2306 2307 2308 2309
    _joystickMode = (JoystickMode_t)mode;
    _saveSettings();
    emit joystickModeChanged(mode);
}

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

2311
    list << "Normal" << "Attitude" << "Position" << "Force" << "Velocity";
dogmaphobic's avatar
dogmaphobic committed
2312

2313 2314
    return list;
}
2315 2316 2317 2318 2319 2320 2321 2322

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

void Vehicle::setJoystickEnabled(bool enabled)
{
2323
    _joystickEnabled = enabled;
2324
    _startJoystick(_joystickEnabled);
2325
    _saveSettings();
2326
    emit joystickEnabledChanged(_joystickEnabled);
2327 2328 2329 2330
}

void Vehicle::_startJoystick(bool start)
{
2331
    Joystick* joystick = _joystickManager->activeJoystick();
2332 2333
    if (joystick) {
        if (start) {
2334
            joystick->startPolling(this);
2335 2336 2337 2338 2339 2340 2341 2342 2343 2344 2345 2346 2347
        } else {
            joystick->stopPolling();
        }
    }
}

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

void Vehicle::setActive(bool active)
{
2348 2349
    if (_active != active) {
        _active = active;
2350
        _startJoystick(false);
2351 2352
        emit activeChanged(_active);
    }
2353
}
2354

2355 2356 2357 2358
QGeoCoordinate Vehicle::homePosition(void)
{
    return _homePosition;
}
2359 2360 2361 2362

void Vehicle::setArmed(bool armed)
{
    // We specifically use COMMAND_LONG:MAV_CMD_COMPONENT_ARM_DISARM since it is supported by more flight stacks.
2363
    sendMavCommand(_defaultComponentId,
2364 2365 2366
                   MAV_CMD_COMPONENT_ARM_DISARM,
                   true,    // show error if fails
                   armed ? 1.0f : 0.0f);
2367 2368 2369 2370
}

bool Vehicle::flightModeSetAvailable(void)
{
2371
    return _firmwarePlugin->isCapable(this, FirmwarePlugin::SetFlightModeCapability);
2372 2373 2374 2375
}

QStringList Vehicle::flightModes(void)
{
2376
    return _firmwarePlugin->flightModes(this);
2377 2378
}

Don Gagne's avatar
Don Gagne committed
2379
QString Vehicle::flightMode(void) const
2380 2381 2382 2383 2384 2385 2386 2387 2388 2389 2390 2391 2392 2393 2394 2395
{
    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;
2396 2397 2398 2399 2400 2401 2402 2403
        mavlink_msg_set_mode_pack_chan(_mavlink->getSystemId(),
                                       _mavlink->getComponentId(),
                                       priorityLink()->mavlinkChannel(),
                                       &msg,
                                       id(),
                                       newBaseMode,
                                       custom_mode);
        sendMessageOnLink(priorityLink(), msg);
2404
    } else {
Don Gagne's avatar
Don Gagne committed
2405
        qWarning() << "FirmwarePlugin::setFlightMode failed, flightMode:" << flightMode;
2406 2407 2408
    }
}

2409 2410
QString Vehicle::priorityLinkName(void) const
{
2411
    if (_priorityLink) {
2412
        return _priorityLink->getName();
2413 2414 2415
    }

    return "none";
2416 2417
}

2418 2419 2420
QVariantList Vehicle::links(void) const {
    QVariantList ret;

2421
    for( const auto &item: _links )
2422 2423 2424 2425 2426
        ret << QVariant::fromValue(item);

    return ret;
}

2427 2428
void Vehicle::setPriorityLinkByName(const QString& priorityLinkName)
{
2429 2430 2431 2432
    if (!_priorityLink) {
        return;
    }

2433 2434 2435 2436 2437
    if (priorityLinkName == _priorityLink->getName()) {
        // The link did not change
        return;
    }

2438
    LinkInterface* newPriorityLink = nullptr;
2439 2440 2441 2442 2443 2444 2445 2446 2447


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

    if (newPriorityLink) {
2448
        _priorityLinkCommanded = true;
2449
        _priorityLink = _toolbox->linkManager()->sharedLinkInterfacePointerForLink(newPriorityLink);
2450
        _updateHighLatencyLink(true);
2451
        emit priorityLinkNameChanged(_priorityLink->getName());
2452
        _linkActiveChanged(_priorityLink.data(), _priorityLink->link_active(_id), _id);
2453 2454 2455
    }
}

2456 2457 2458 2459 2460 2461 2462 2463 2464 2465 2466 2467 2468 2469
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;
    }

2470 2471 2472 2473 2474 2475 2476 2477
    mavlink_msg_set_mode_pack_chan(_mavlink->getSystemId(),
                                   _mavlink->getComponentId(),
                                   priorityLink()->mavlinkChannel(),
                                   &msg,
                                   id(),
                                   newBaseMode,
                                   _custom_mode);
    sendMessageOnLink(priorityLink(), msg);
2478
}
2479

2480
void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple)
2481 2482 2483
{
    mavlink_message_t               msg;
    mavlink_request_data_stream_t   dataStream;
dogmaphobic's avatar
dogmaphobic committed
2484

Don Gagne's avatar
Don Gagne committed
2485 2486
    memset(&dataStream, 0, sizeof(dataStream));

2487 2488 2489 2490
    dataStream.req_stream_id = stream;
    dataStream.req_message_rate = rate;
    dataStream.start_stop = 1;  // start
    dataStream.target_system = id();
2491
    dataStream.target_component = _defaultComponentId;
dogmaphobic's avatar
dogmaphobic committed
2492

2493 2494 2495 2496 2497
    mavlink_msg_request_data_stream_encode_chan(_mavlink->getSystemId(),
                                                _mavlink->getComponentId(),
                                                priorityLink()->mavlinkChannel(),
                                                &msg,
                                                &dataStream);
2498

2499 2500 2501 2502
    if (sendMultiple) {
        // We use sendMessageMultiple since we really want these to make it to the vehicle
        sendMessageMultiple(msg);
    } else {
2503
        sendMessageOnLink(priorityLink(), msg);
2504
    }
2505 2506 2507 2508 2509 2510
}

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

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

2514 2515 2516 2517 2518 2519
        if (--_sendMessageMultipleList[_nextSendMessageMultipleIndex].retryCount <= 0) {
            _sendMessageMultipleList.removeAt(_nextSendMessageMultipleIndex);
        } else {
            _nextSendMessageMultipleIndex++;
        }
    }
dogmaphobic's avatar
dogmaphobic committed
2520

2521 2522 2523 2524 2525 2526 2527 2528
    if (_nextSendMessageMultipleIndex >= _sendMessageMultipleList.count()) {
        _nextSendMessageMultipleIndex = 0;
    }
}

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

2530 2531
    info.message =      message;
    info.retryCount =   _sendMessageMultipleRetries;
dogmaphobic's avatar
dogmaphobic committed
2532

2533 2534
    _sendMessageMultipleList.append(info);
}
2535 2536 2537 2538

void Vehicle::_missionManagerError(int errorCode, const QString& errorMsg)
{
    Q_UNUSED(errorCode);
2539
    qgcApp()->showMessage(tr("Mission transfer failed. Retry transfer. Error: %1").arg(errorMsg));
2540
}
2541

2542 2543 2544
void Vehicle::_geoFenceManagerError(int errorCode, const QString& errorMsg)
{
    Q_UNUSED(errorCode);
2545
    qgcApp()->showMessage(tr("GeoFence transfer failed. Retry transfer. Error: %1").arg(errorMsg));
2546 2547 2548 2549 2550
}

void Vehicle::_rallyPointManagerError(int errorCode, const QString& errorMsg)
{
    Q_UNUSED(errorCode);
2551
    qgcApp()->showMessage(tr("Rally Point transfer failed. Retry transfer. Error: %1").arg(errorMsg));
2552 2553
}

2554 2555 2556
void Vehicle::_clearCameraTriggerPoints(void)
{
    _cameraTriggerPoints.clearAndDeleteContents();
2557 2558
}

2559
void Vehicle::_flightTimerStart(void)
2560
{
2561
    _flightTimer.start();
DonLakeFlyer's avatar
DonLakeFlyer committed
2562
    _flightTimeUpdater.start();
2563
    _flightDistanceFact.setRawValue(0);
2564
    _flightTimeFact.setRawValue(0);
2565 2566
}

DonLakeFlyer's avatar
DonLakeFlyer committed
2567 2568 2569 2570 2571 2572 2573 2574 2575 2576
void Vehicle::_flightTimerStop(void)
{
    _flightTimeUpdater.stop();
}

void Vehicle::_updateFlightTime(void)
{
    _flightTimeFact.setRawValue((double)_flightTimer.elapsed() / 1000.0);
}

2577
void Vehicle::_startPlanRequest(void)
2578
{
DonLakeFlyer's avatar
DonLakeFlyer committed
2579
    if (_missionManagerInitialRequestSent) {
2580
        // We have already started (or possibly completed) the sequence of requesting the plan for the first time
DonLakeFlyer's avatar
DonLakeFlyer committed
2581 2582 2583
        return;
    }

2584 2585 2586 2587 2588
    // We don't start the Plan request until the following things are satisfied:
    //  - Parameter download is complete
    //  - We know the vehicle capabilities
    //  - We know the max mavlink protocol version
    if (_parameterManager->parametersReady() && _vehicleCapabilitiesKnown && _mavlinkProtocolRequestComplete) {
2589
        qCDebug(VehicleLog) << "_startPlanRequest";
2590
        _missionManagerInitialRequestSent = true;
2591 2592 2593 2594
        if (_settingsManager->appSettings()->autoLoadMissions()->rawValue().toBool()) {
            QString missionAutoLoadDirPath = _settingsManager->appSettings()->missionSavePath();
            if (!missionAutoLoadDirPath.isEmpty()) {
                QDir missionAutoLoadDir(missionAutoLoadDirPath);
2595 2596
                QString autoloadFilename = missionAutoLoadDir.absoluteFilePath(tr("AutoLoad%1.%2").arg(_id).arg(AppSettings::planFileExtension));
                if (QFile(autoloadFilename).exists()) {
2597
                    _initialPlanRequestComplete = true; // We aren't going to load from the vehicle, so we are done
2598
                    PlanMasterController::sendPlanToVehicle(this, autoloadFilename);
2599 2600
                    return;
                }
Don Gagne's avatar
Don Gagne committed
2601 2602
            }
        }
2603
        _missionManager->loadFromVehicle();
2604 2605
    } else {
        if (!_parameterManager->parametersReady()) {
2606
            qCDebug(VehicleLog) << "Delaying _startPlanRequest due to parameters not ready";
2607
        } else if (!_vehicleCapabilitiesKnown) {
DonLakeFlyer's avatar
DonLakeFlyer committed
2608
            qCDebug(VehicleLog) << "Delaying _startPlanRequest due to vehicle capabilities not known";
2609 2610
        } else if (!_mavlinkProtocolRequestComplete) {
            qCDebug(VehicleLog) << "Delaying _startPlanRequest due to mavlink protocol request not complete";
2611 2612 2613 2614
        }
    }
}

2615 2616 2617 2618 2619
void Vehicle::_missionLoadComplete(void)
{
    // After the initial mission request completes we ask for the geofence
    if (!_geoFenceManagerInitialRequestSent) {
        _geoFenceManagerInitialRequestSent = true;
2620 2621 2622 2623 2624 2625 2626
        if (_geoFenceManager->supported()) {
            qCDebug(VehicleLog) << "_missionLoadComplete requesting GeoFence";
            _geoFenceManager->loadFromVehicle();
        } else {
            qCDebug(VehicleLog) << "_missionLoadComplete GeoFence not supported skipping";
            _geoFenceLoadComplete();
        }
2627 2628 2629 2630 2631 2632 2633 2634
    }
}

void Vehicle::_geoFenceLoadComplete(void)
{
    // After geofence request completes we ask for the rally points
    if (!_rallyPointManagerInitialRequestSent) {
        _rallyPointManagerInitialRequestSent = true;
2635 2636 2637 2638 2639 2640 2641
        if (_rallyPointManager->supported()) {
            qCDebug(VehicleLog) << "_missionLoadComplete requesting Rally Points";
            _rallyPointManager->loadFromVehicle();
        } else {
            qCDebug(VehicleLog) << "_missionLoadComplete Rally Points not supported skipping";
            _rallyPointLoadComplete();
        }
2642 2643 2644 2645 2646
    }
}

void Vehicle::_rallyPointLoadComplete(void)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
2647
    qCDebug(VehicleLog) << "_missionLoadComplete _initialPlanRequestComplete = true";
2648 2649
    if (!_initialPlanRequestComplete) {
        _initialPlanRequestComplete = true;
Don Gagne's avatar
Don Gagne committed
2650
        emit initialPlanRequestCompleteChanged(true);
2651
    }
2652 2653
}

2654 2655
void Vehicle::_parametersReady(bool parametersReady)
{
2656
    qDebug() << "_parametersReady" << parametersReady;
2657 2658 2659 2660
    // 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();
2661
    if (parametersReady) {
2662
        _setupAutoDisarmSignalling();
2663
        _startPlanRequest();
Lorenz Meier's avatar
Lorenz Meier committed
2664
    }
2665
}
2666

2667 2668 2669 2670 2671 2672 2673 2674 2675 2676
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(),
2677 2678 2679 2680
                                        _mavlink->getComponentId(),
                                        priorityLink()->mavlinkChannel(),
                                        &msg,
                                        &cmd);
2681 2682 2683 2684

    sendMessageOnLink(priorityLink(), msg);
}

Don Gagne's avatar
Don Gagne committed
2685
void Vehicle::disconnectInactiveVehicle(void)
2686
{
Don Gagne's avatar
Don Gagne committed
2687
    // Vehicle is no longer communicating with us, disconnect all links
2688

2689
    LinkManager* linkMgr = _toolbox->linkManager();
2690
    for (int i=0; i<_links.count(); i++) {
2691 2692
        // 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.
2693
        if (!_toolbox->multiVehicleManager()->linkInUse(_links[i], this)) {
2694 2695
            linkMgr->disconnectLink(_links[i]);
        }
2696
    }
2697
    emit linksChanged();
2698
}
2699

dogmaphobic's avatar
dogmaphobic committed
2700 2701 2702 2703 2704
void Vehicle::_imageReady(UASInterface*)
{
    if(_uas)
    {
        QImage img = _uas->getImage();
2705
        _toolbox->imageProvider()->setImage(&img, _id);
dogmaphobic's avatar
dogmaphobic committed
2706 2707 2708 2709
        _flowImageIndex++;
        emit flowImageIndexChanged();
    }
}
Don Gagne's avatar
Don Gagne committed
2710 2711 2712

void Vehicle::_remoteControlRSSIChanged(uint8_t rssi)
{
2713 2714 2715 2716 2717 2718 2719 2720 2721 2722 2723
    //-- 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;
2724
    }
Don Gagne's avatar
Don Gagne committed
2725 2726 2727 2728 2729 2730 2731 2732 2733 2734 2735
    // 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
2736

Gus Grubba's avatar
Gus Grubba committed
2737
void Vehicle::virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust)
Don Gagne's avatar
Don Gagne committed
2738
{
2739
    // The following if statement prevents the virtualTabletJoystick from sending values if the standard joystick is enabled
2740
    if ( !_joystickEnabled && !_highLatencyLink) {
Gus Grubba's avatar
Gus Grubba committed
2741 2742 2743 2744 2745 2746
        _uas->setExternalControlSetpoint(
            static_cast<float>(roll),
            static_cast<float>(pitch),
            static_cast<float>(yaw),
            static_cast<float>(thrust),
            0, JoystickModeRC);
2747
    }
Don Gagne's avatar
Don Gagne committed
2748
}
2749 2750 2751 2752 2753 2754 2755 2756 2757

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

2758
void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID)
2759
{
2760 2761
    // only continue if the vehicle id is correct
    if (vehicleID != _id) {
2762 2763 2764
        return;
    }

2765
    emit linksPropertiesChanged();
2766

2767 2768 2769
    bool communicationLost = false;
    bool communicationRegained = false;

2770 2771 2772 2773
    if (link == _priorityLink) {
        if (active && _connectionLost) {
            // communication to priority link regained
            _connectionLost = false;
2774
            communicationRegained = true;
2775
            emit connectionLostChanged(false);
2776

2777 2778 2779 2780 2781 2782 2783 2784
            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
2785
            }
2786
        } else if (!active && !_connectionLost) {
2787
            _updatePriorityLink(false /* updateActive */, false /* sendCommand */);
2788

2789
            if (link == _priorityLink) {
2790
                // No other link to switch to was found, notify user of comm lossf
2791 2792 2793 2794 2795 2796 2797 2798 2799
                _connectionLost = true;
                communicationLost = true;
                _heardFrom = false;
                emit connectionLostChanged(true);

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

                    disconnectInactiveVehicle();
2803 2804 2805 2806
                }
            }
        }
    } else {
2807
        qgcApp()->showMessage((tr("%1 communication to auxiliary link %2 %3")).arg(_vehicleIdSpeech()).arg(link->getName()).arg(active ? "regained" : "lost"));
acfloria's avatar
acfloria committed
2808
        _updatePriorityLink(false /* updateActive */, true /* sendCommand */);
2809
    }
2810 2811 2812 2813 2814 2815 2816 2817 2818 2819 2820 2821 2822 2823 2824 2825 2826 2827 2828 2829 2830 2831 2832 2833 2834

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

2837
void Vehicle::_say(const QString& text)
2838
{
2839
    _toolbox->audioOutput()->say(text.toLower());
2840
}
2841 2842 2843

bool Vehicle::fixedWing(void) const
{
2844
    return QGCMAVLink::isFixedWing(vehicleType());
2845 2846
}

Don Gagne's avatar
Don Gagne committed
2847 2848
bool Vehicle::rover(void) const
{
2849
    return QGCMAVLink::isRover(vehicleType());
Don Gagne's avatar
Don Gagne committed
2850 2851
}

2852 2853
bool Vehicle::sub(void) const
{
2854
    return QGCMAVLink::isSub(vehicleType());
2855 2856
}

2857 2858
bool Vehicle::multiRotor(void) const
{
2859
    return QGCMAVLink::isMultiRotor(vehicleType());
2860
}
Don Gagne's avatar
Don Gagne committed
2861

Don Gagne's avatar
Don Gagne committed
2862 2863
bool Vehicle::vtol(void) const
{
2864
    return _firmwarePlugin->isVtol(this);
Don Gagne's avatar
Don Gagne committed
2865 2866
}

2867 2868 2869 2870 2871
bool Vehicle::supportsThrottleModeCenterZero(void) const
{
    return _firmwarePlugin->supportsThrottleModeCenterZero();
}

2872
bool Vehicle::supportsNegativeThrust(void)
2873
{
2874
    return _firmwarePlugin->supportsNegativeThrust(this);
2875 2876
}

2877 2878 2879 2880 2881
bool Vehicle::supportsRadio(void) const
{
    return _firmwarePlugin->supportsRadio();
}

2882 2883 2884 2885 2886
bool Vehicle::supportsJSButton(void) const
{
    return _firmwarePlugin->supportsJSButton();
}

2887 2888 2889 2890 2891
bool Vehicle::supportsMotorInterference(void) const
{
    return _firmwarePlugin->supportsMotorInterference();
}

2892 2893 2894 2895 2896
bool Vehicle::supportsTerrainFrame(void) const
{
    return _firmwarePlugin->supportsTerrainFrame();
}

2897 2898 2899 2900 2901 2902 2903 2904 2905 2906 2907 2908 2909 2910 2911 2912 2913 2914 2915 2916 2917 2918 2919 2920 2921 2922 2923 2924 2925 2926 2927 2928 2929 2930
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];
}

2931 2932 2933
/// Returns the string to speak to identify the vehicle
QString Vehicle::_vehicleIdSpeech(void)
{
2934
    if (_toolbox->multiVehicleManager()->vehicles()->count() > 1) {
2935
        return tr("vehicle %1").arg(id());
2936
    } else {
2937
        return QString();
2938 2939 2940
    }
}

Don Gagne's avatar
Don Gagne committed
2941
void Vehicle::_handleFlightModeChanged(const QString& flightMode)
2942
{
2943
    _say(tr("%1 %2 flight mode").arg(_vehicleIdSpeech()).arg(flightMode));
Don Gagne's avatar
Don Gagne committed
2944
    emit guidedModeChanged(_firmwarePlugin->isGuidedMode(this));
2945 2946 2947 2948
}

void Vehicle::_announceArmedChanged(bool armed)
{
2949
    _say(QString("%1 %2").arg(_vehicleIdSpeech()).arg(armed ? tr("armed") : tr("disarmed")));
2950 2951
}

2952
void Vehicle::_setFlying(bool flying)
Don Gagne's avatar
Don Gagne committed
2953
{
2954
    if (_flying != flying) {
Don Gagne's avatar
Don Gagne committed
2955 2956 2957 2958 2959
        _flying = flying;
        emit flyingChanged(flying);
    }
}

2960 2961 2962 2963 2964 2965 2966 2967
void Vehicle::_setLanding(bool landing)
{
    if (armed() && _landing != landing) {
        _landing = landing;
        emit landingChanged(landing);
    }
}

Don Gagne's avatar
Don Gagne committed
2968 2969
bool Vehicle::guidedModeSupported(void) const
{
2970
    return _firmwarePlugin->isCapable(this, FirmwarePlugin::GuidedModeCapability);
Don Gagne's avatar
Don Gagne committed
2971 2972 2973 2974
}

bool Vehicle::pauseVehicleSupported(void) const
{
2975 2976 2977 2978 2979 2980
    return _firmwarePlugin->isCapable(this, FirmwarePlugin::PauseVehicleCapability);
}

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

2983 2984 2985 2986 2987
bool Vehicle::takeoffVehicleSupported() const
{
    return _firmwarePlugin->isCapable(this, FirmwarePlugin::TakeoffVehicleCapability);
}

2988 2989 2990 2991 2992
QString Vehicle::gotoFlightMode() const
{
    return _firmwarePlugin->gotoFlightMode();
}

DonLakeFlyer's avatar
DonLakeFlyer committed
2993
void Vehicle::guidedModeRTL(bool smartRTL)
Don Gagne's avatar
Don Gagne committed
2994 2995
{
    if (!guidedModeSupported()) {
2996
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
2997 2998
        return;
    }
DonLakeFlyer's avatar
DonLakeFlyer committed
2999
    _firmwarePlugin->guidedModeRTL(this, smartRTL);
Don Gagne's avatar
Don Gagne committed
3000 3001 3002 3003 3004
}

void Vehicle::guidedModeLand(void)
{
    if (!guidedModeSupported()) {
3005
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
3006 3007 3008 3009 3010
        return;
    }
    _firmwarePlugin->guidedModeLand(this);
}

3011
void Vehicle::guidedModeTakeoff(double altitudeRelative)
Don Gagne's avatar
Don Gagne committed
3012 3013
{
    if (!guidedModeSupported()) {
3014
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
3015 3016
        return;
    }
3017
    _firmwarePlugin->guidedModeTakeoff(this, altitudeRelative);
3018 3019
}

3020 3021 3022 3023 3024
double Vehicle::minimumTakeoffAltitude(void)
{
    return _firmwarePlugin->minimumTakeoffAltitude(this);
}

3025 3026 3027
void Vehicle::startMission(void)
{
    _firmwarePlugin->startMission(this);
Don Gagne's avatar
Don Gagne committed
3028 3029 3030 3031 3032
}

void Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord)
{
    if (!guidedModeSupported()) {
3033
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
3034 3035
        return;
    }
3036 3037 3038
    if (!coordinate().isValid()) {
        return;
    }
3039
    double maxDistance = _settingsManager->flyViewSettings()->maxGoToLocationDistance()->rawValue().toDouble();
3040
    if (coordinate().distanceTo(gotoCoord) > maxDistance) {
3041
        qgcApp()->showMessage(QString("New location is too far. Must be less than %1 %2.").arg(qRound(FactMetaData::metersToAppSettingsDistanceUnits(maxDistance).toDouble())).arg(FactMetaData::appSettingsDistanceUnitsString()));
3042 3043
        return;
    }
Don Gagne's avatar
Don Gagne committed
3044 3045 3046
    _firmwarePlugin->guidedModeGotoLocation(this, gotoCoord);
}

3047
void Vehicle::guidedModeChangeAltitude(double altitudeChange)
Don Gagne's avatar
Don Gagne committed
3048 3049
{
    if (!guidedModeSupported()) {
3050
        qgcApp()->showMessage(guided_mode_not_supported_by_vehicle);
Don Gagne's avatar
Don Gagne committed
3051 3052
        return;
    }
3053
    _firmwarePlugin->guidedModeChangeAltitude(this, altitudeChange);
Don Gagne's avatar
Don Gagne committed
3054 3055
}

DonLakeFlyer's avatar
DonLakeFlyer committed
3056
void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude)
3057
{
3058 3059
    if (!orbitModeSupported()) {
        qgcApp()->showMessage(QStringLiteral("Orbit mode not supported by Vehicle."));
3060 3061
        return;
    }
Don Gagne's avatar
Don Gagne committed
3062
    if (capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
Gus Grubba's avatar
Gus Grubba committed
3063 3064 3065 3066 3067 3068 3069 3070 3071 3072
        sendMavCommandInt(
            defaultComponentId(),
            MAV_CMD_DO_ORBIT,
            MAV_FRAME_GLOBAL,
            true,                           // show error if fails
            static_cast<float>(radius),
            static_cast<float>(qQNaN()),    // Use default velocity
            0,                              // Vehicle points to center
            static_cast<float>(qQNaN()),    // reserved
            centerCoord.latitude(), centerCoord.longitude(), static_cast<float>(amslAltitude));
3073
    } else {
Gus Grubba's avatar
Gus Grubba committed
3074 3075 3076 3077 3078 3079 3080 3081 3082 3083 3084
        sendMavCommand(
            defaultComponentId(),
            MAV_CMD_DO_ORBIT,
            true,                           // show error if fails
            static_cast<float>(radius),
            static_cast<float>(qQNaN()),    // Use default velocity
            0,                              // Vehicle points to center
            static_cast<float>(qQNaN()),    // reserved
            static_cast<float>(centerCoord.latitude()),
            static_cast<float>(centerCoord.longitude()),
            static_cast<float>(amslAltitude));
3085
    }
3086 3087
}

Don Gagne's avatar
Don Gagne committed
3088 3089 3090 3091 3092 3093 3094 3095 3096
void Vehicle::pauseVehicle(void)
{
    if (!pauseVehicleSupported()) {
        qgcApp()->showMessage(QStringLiteral("Pause not supported by vehicle."));
        return;
    }
    _firmwarePlugin->pauseVehicle(this);
}

3097
void Vehicle::abortLanding(double climbOutAltitude)
3098
{
Gus Grubba's avatar
Gus Grubba committed
3099 3100 3101 3102 3103
    sendMavCommand(
        defaultComponentId(),
        MAV_CMD_DO_GO_AROUND,
        true,        // show error if fails
        static_cast<float>(climbOutAltitude));
3104 3105
}

Don Gagne's avatar
Don Gagne committed
3106 3107 3108 3109 3110 3111 3112 3113 3114 3115 3116 3117
bool Vehicle::guidedMode(void) const
{
    return _firmwarePlugin->isGuidedMode(this);
}

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

void Vehicle::emergencyStop(void)
{
Gus Grubba's avatar
Gus Grubba committed
3118 3119 3120 3121 3122 3123
    sendMavCommand(
        _defaultComponentId,
        MAV_CMD_COMPONENT_ARM_DISARM,
        true,        // show error if fails
        0.0f,
        21196.0f);  // Magic number for emergency stop
Don Gagne's avatar
Don Gagne committed
3124 3125
}

3126 3127 3128 3129 3130 3131
void Vehicle::setCurrentMissionSequence(int seq)
{
    if (!_firmwarePlugin->sendHomePositionToVehicle()) {
        seq--;
    }
    mavlink_message_t msg;
Gus Grubba's avatar
Gus Grubba committed
3132 3133 3134 3135 3136 3137 3138 3139
    mavlink_msg_mission_set_current_pack_chan(
        static_cast<uint8_t>(_mavlink->getSystemId()),
        static_cast<uint8_t>(_mavlink->getComponentId()),
        priorityLink()->mavlinkChannel(),
        &msg,
        static_cast<uint8_t>(id()),
        _compID,
        static_cast<uint8_t>(seq));
3140
    sendMessageOnLink(priorityLink(), msg);
3141 3142
}

3143
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
3144
{
3145 3146
    MavCommandQueueEntry_t entry;

3147
    entry.commandInt = false;
3148 3149 3150
    entry.component = component;
    entry.command = command;
    entry.showError = showError;
Gus Grubba's avatar
Gus Grubba committed
3151 3152 3153 3154 3155 3156 3157
    entry.rgParam[0] = static_cast<double>(param1);
    entry.rgParam[1] = static_cast<double>(param2);
    entry.rgParam[2] = static_cast<double>(param3);
    entry.rgParam[3] = static_cast<double>(param4);
    entry.rgParam[4] = static_cast<double>(param5);
    entry.rgParam[5] = static_cast<double>(param6);
    entry.rgParam[6] = static_cast<double>(param7);
3158 3159 3160 3161 3162 3163 3164 3165 3166

    _mavCommandQueue.append(entry);

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

3167 3168 3169 3170 3171
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;
3172 3173
    entry.component = component;
    entry.command = command;
3174
    entry.frame = frame;
3175
    entry.showError = showError;
Gus Grubba's avatar
Gus Grubba committed
3176 3177 3178 3179
    entry.rgParam[0] = static_cast<double>(param1);
    entry.rgParam[1] = static_cast<double>(param2);
    entry.rgParam[2] = static_cast<double>(param3);
    entry.rgParam[3] = static_cast<double>(param4);
3180 3181
    entry.rgParam[4] = param5;
    entry.rgParam[5] = param6;
Gus Grubba's avatar
Gus Grubba committed
3182
    entry.rgParam[6] = static_cast<double>(param7);
3183 3184 3185 3186 3187 3188 3189 3190 3191 3192 3193

    _mavCommandQueue.append(entry);

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

void Vehicle::_sendMavCommandAgain(void)
{
3194 3195 3196 3197 3198 3199
    if(!_mavCommandQueue.size()) {
        qWarning() << "Command resend with no commands in queue";
        _mavCommandAckTimer.stop();
        return;
    }

3200 3201 3202
    MavCommandQueueEntry_t& queuedCommand = _mavCommandQueue[0];

    if (_mavCommandRetryCount++ > _mavCommandMaxRetryCount) {
3203
        if (queuedCommand.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) {
3204 3205
            qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES.";
            _handleUnsupportedRequestAutopilotCapabilities();
3206 3207
        }

3208
        if (queuedCommand.command == MAV_CMD_REQUEST_PROTOCOL_VERSION) {
3209 3210
            qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_PROTOCOL_VERSION.";
            _handleUnsupportedRequestProtocolVersion();
3211 3212
        }

3213 3214
        emit mavCommandResult(_id, queuedCommand.component, queuedCommand.command, MAV_RESULT_FAILED, true /* noResponsefromVehicle */);
        if (queuedCommand.showError) {
3215
            qgcApp()->showMessage(tr("Vehicle did not respond to command: %1").arg(_toolbox->missionCommandTree()->friendlyName(queuedCommand.command)));
3216 3217 3218 3219 3220 3221
        }
        _mavCommandQueue.removeFirst();
        _sendNextQueuedMavCommand();
        return;
    }

3222
    if (_mavCommandRetryCount > 1) {
3223 3224 3225 3226
        if (!px4Firmware() && queuedCommand.command == MAV_CMD_START_RX_PAIR) {
            // The implementation of this command comes from the IO layer and is shared across stacks. So for other firmwares
            // we aren't really sure whether they are correct or not.
            return;
3227
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
3228
        qCDebug(VehicleLog) << "Vehicle::_sendMavCommandAgain retrying command:_mavCommandRetryCount" << queuedCommand.command << _mavCommandRetryCount;
3229 3230
    }

3231 3232
    _mavCommandAckTimer.start();

Don Gagne's avatar
Don Gagne committed
3233
    mavlink_message_t       msg;
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 3270 3271 3272 3273 3274
    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
3275

3276
    sendMessageOnLink(priorityLink(), msg);
Don Gagne's avatar
Don Gagne committed
3277
}
3278

3279 3280 3281 3282 3283 3284 3285 3286
void Vehicle::_sendNextQueuedMavCommand(void)
{
    if (_mavCommandQueue.count()) {
        _mavCommandRetryCount = 0;
        _sendMavCommandAgain();
    }
}

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
void Vehicle::_handleUnsupportedRequestProtocolVersion(void)
{
    // We end up here if either the vehicle does not support the MAV_CMD_REQUEST_PROTOCOL_VERSION command or if
    // we never received an Ack back for the command.

    // If the link isn't already running Mavlink V2 fall back to the capability bits to determine whether to use Mavlink V2 or not.
    if (_maxProtoVersion == 0) {
        if (capabilitiesKnown()) {
            unsigned vehicleMaxProtoVersion = capabilityBits() & MAV_PROTOCOL_CAPABILITY_MAVLINK2 ? 200 : 100;
            qCDebug(VehicleLog) << QStringLiteral("Setting _maxProtoVersion to %1 based on capabilitity bits since not yet set.").arg(vehicleMaxProtoVersion);
            _setMaxProtoVersion(vehicleMaxProtoVersion);
        } else {
            qCDebug(VehicleLog) << "Waiting for capabilities to be known to set _maxProtoVersion";
        }
    } else {
        qCDebug(VehicleLog) << "Leaving _maxProtoVersion at current value" << _maxProtoVersion;
    }
    _mavlinkProtocolRequestComplete = true;

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

void Vehicle::_protocolVersionTimeOut(void)
{
    // The PROTOCOL_VERSION message didn't make it through the pipe from Vehicle->QGC.
3313
    // This means although the vehicle may support mavlink 2, the pipe does not.
3314 3315 3316 3317 3318 3319 3320 3321 3322 3323 3324 3325 3326 3327 3328 3329
    qCDebug(VehicleLog) << QStringLiteral("Setting _maxProtoVersion to 100 due to timeout on receiving PROTOCOL_VERSION message.");
    _setMaxProtoVersion(100);
    _mavlinkProtocolRequestComplete = true;
    _startPlanRequest();
}

void Vehicle::_handleUnsupportedRequestAutopilotCapabilities(void)
{
    // We end up here if either the vehicle does not support the MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES command or if
    // we never received an Ack back for the command.

    _setCapabilities(0);

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

DonLakeFlyer's avatar
DonLakeFlyer committed
3331 3332 3333 3334 3335 3336 3337 3338
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) {
3339 3340
        qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error(%1). Setting no capabilities.").arg(ack.result);
        _handleUnsupportedRequestAutopilotCapabilities();
DonLakeFlyer's avatar
DonLakeFlyer committed
3341 3342
    }

3343 3344 3345 3346 3347 3348 3349
    if (ack.command == MAV_CMD_REQUEST_PROTOCOL_VERSION) {
        if (ack.result == MAV_RESULT_ACCEPTED) {
            // The vehicle should be sending a PROTOCOL_VERSION message in a mavlink 2 packet. This may or may not make it through the pipe.
            // So we wait for it to come and timeout if it doesn't.
            if (!_mavlinkProtocolRequestComplete) {
                QTimer::singleShot(1000, this, &Vehicle::_protocolVersionTimeOut);
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
3350
        } else {
3351 3352
            qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_PROTOCOL_VERSION with error(%1).").arg(ack.result);
            _handleUnsupportedRequestProtocolVersion();
DonLakeFlyer's avatar
DonLakeFlyer committed
3353 3354 3355
        }
    }

3356
#if !defined(NO_ARDUPILOT_DIALECT)
3357 3358 3359
    if (ack.command == MAV_CMD_FLASH_BOOTLOADER && ack.result == MAV_RESULT_ACCEPTED) {
        qgcApp()->showMessage(tr("Bootloader flash succeeded"));
    }
3360
#endif
3361

DonLakeFlyer's avatar
DonLakeFlyer committed
3362 3363 3364 3365 3366 3367 3368 3369 3370
    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) {
Gus Grubba's avatar
Gus Grubba committed
3371
        QString commandName = _toolbox->missionCommandTree()->friendlyName(static_cast<MAV_CMD>(ack.command));
DonLakeFlyer's avatar
DonLakeFlyer committed
3372 3373 3374 3375 3376 3377 3378 3379 3380 3381 3382 3383 3384 3385 3386 3387 3388 3389 3390 3391 3392 3393
        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();
}

3394 3395 3396 3397 3398 3399 3400 3401 3402 3403 3404 3405 3406
void Vehicle::setPrearmError(const QString& prearmError)
{
    _prearmError = prearmError;
    emit prearmErrorChanged(_prearmError);
    if (!_prearmError.isEmpty()) {
        _prearmErrorTimer.start();
    }
}

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

3408
void Vehicle::setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType)
3409 3410 3411 3412
{
    _firmwareMajorVersion = majorVersion;
    _firmwareMinorVersion = minorVersion;
    _firmwarePatchVersion = patchVersion;
3413
    _firmwareVersionType = versionType;
3414 3415 3416 3417 3418 3419 3420 3421 3422
    emit firmwareVersionChanged();
}

void Vehicle::setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion)
{
    _firmwareCustomMajorVersion = majorVersion;
    _firmwareCustomMinorVersion = minorVersion;
    _firmwareCustomPatchVersion = patchVersion;
    emit firmwareCustomVersionChanged();
3423 3424 3425 3426 3427 3428 3429 3430 3431 3432 3433 3434 3435 3436 3437 3438 3439
}

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

3442 3443
void Vehicle::rebootVehicle()
{
3444
    _autoDisconnect = true;
3445 3446 3447 3448 3449 3450 3451 3452 3453 3454 3455 3456 3457 3458 3459 3460 3461

    mavlink_message_t       msg;
    mavlink_command_long_t  cmd;

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

3464 3465 3466 3467 3468 3469 3470 3471
void Vehicle::setSoloFirmware(bool soloFirmware)
{
    if (soloFirmware != _soloFirmware) {
        _soloFirmware = soloFirmware;
        emit soloFirmwareChanged(soloFirmware);
    }
}

3472
void Vehicle::motorTest(int motor, int percent, int timeoutSecs)
3473
{
3474
    sendMavCommand(_defaultComponentId, MAV_CMD_DO_MOTOR_TEST, true, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, timeoutSecs, 0, MOTOR_TEST_ORDER_BOARD);
3475 3476
}

3477
QString Vehicle::brandImageIndoor(void) const
3478
{
3479 3480 3481 3482 3483 3484
    return _firmwarePlugin->brandImageIndoor(this);
}

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

3487 3488 3489 3490 3491 3492 3493 3494 3495 3496 3497 3498 3499 3500 3501 3502 3503 3504 3505 3506 3507 3508 3509 3510 3511 3512 3513 3514 3515 3516 3517 3518 3519 3520 3521
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" },
3522
        { MAV_SYS_STATUS_SENSOR_BATTERY,                "Battery" },
3523 3524 3525 3526 3527 3528 3529 3530 3531 3532 3533 3534
    };

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

3535 3536 3537 3538 3539 3540 3541 3542
void Vehicle::setOfflineEditingDefaultComponentId(int defaultComponentId)
{
    if (_offlineEditingVehicle) {
        _defaultComponentId = defaultComponentId;
    } else {
        qWarning() << "Call to Vehicle::setOfflineEditingDefaultComponentId on vehicle which is not offline";
    }
}
3543

Don Gagne's avatar
Don Gagne committed
3544 3545
void Vehicle::triggerCamera(void)
{
3546
    sendMavCommand(_defaultComponentId,
Don Gagne's avatar
Don Gagne committed
3547 3548 3549
                   MAV_CMD_DO_DIGICAM_CONTROL,
                   true,                            // show errors
                   0.0, 0.0, 0.0, 0.0,              // param 1-4 unused
3550 3551 3552
                   1.0,                             // trigger camera
                   0.0,                             // param 6 unused
                   1.0);                            // test shot flag
Don Gagne's avatar
Don Gagne committed
3553 3554
}

3555 3556 3557
void Vehicle::setVtolInFwdFlight(bool vtolInFwdFlight)
{
    if (_vtolInFwdFlight != vtolInFwdFlight) {
3558 3559 3560 3561 3562
        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
3563 3564 3565
    }
}

3566 3567
const char* VehicleGPSFactGroup::_latFactName =                 "lat";
const char* VehicleGPSFactGroup::_lonFactName =                 "lon";
3568 3569 3570 3571 3572
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
3573 3574 3575

VehicleGPSFactGroup::VehicleGPSFactGroup(QObject* parent)
    : FactGroup(1000, ":/json/Vehicle/GPSFact.json", parent)
3576 3577
    , _latFact              (0, _latFactName,               FactMetaData::valueTypeDouble)
    , _lonFact              (0, _lonFactName,               FactMetaData::valueTypeDouble)
Don Gagne's avatar
Don Gagne committed
3578 3579 3580 3581 3582 3583
    , _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)
{
3584 3585
    _addFact(&_latFact,                 _latFactName);
    _addFact(&_lonFact,                 _lonFactName);
Don Gagne's avatar
Don Gagne committed
3586 3587 3588 3589 3590
    _addFact(&_hdopFact,                _hdopFactName);
    _addFact(&_vdopFact,                _vdopFactName);
    _addFact(&_courseOverGroundFact,    _courseOverGroundFactName);
    _addFact(&_lockFact,                _lockFactName);
    _addFact(&_countFact,               _countFactName);
3591

3592 3593
    _latFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _lonFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
3594 3595 3596
    _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
3597 3598
}

3599
void Vehicle::startMavlinkLog()
3600
{
3601
    sendMavCommand(_defaultComponentId, MAV_CMD_LOGGING_START, false /* showError */);
3602 3603
}

3604
void Vehicle::stopMavlinkLog()
3605
{
3606
    sendMavCommand(_defaultComponentId, MAV_CMD_LOGGING_STOP, false /* showError */);
3607 3608
}

3609
void Vehicle::_ackMavlinkLogData(uint16_t sequence)
3610 3611 3612
{
    mavlink_message_t msg;
    mavlink_logging_ack_t ack;
Don Gagne's avatar
Don Gagne committed
3613
    memset(&ack, 0, sizeof(ack));
3614
    ack.sequence = sequence;
3615
    ack.target_component = _defaultComponentId;
3616 3617
    ack.target_system = id();
    mavlink_msg_logging_ack_encode_chan(
3618 3619 3620 3621 3622
                _mavlink->getSystemId(),
                _mavlink->getComponentId(),
                priorityLink()->mavlinkChannel(),
                &msg,
                &ack);
3623 3624 3625
    sendMessageOnLink(priorityLink(), msg);
}

3626
void Vehicle::_handleMavlinkLoggingData(mavlink_message_t& message)
3627 3628 3629
{
    mavlink_logging_data_t log;
    mavlink_msg_logging_data_decode(&message, &log);
Gus Grubba's avatar
Gus Grubba committed
3630
    emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence,
3631
                        log.first_message_offset, QByteArray((const char*)log.data, log.length), false);
3632 3633
}

3634
void Vehicle::_handleMavlinkLoggingDataAcked(mavlink_message_t& message)
3635
{
3636 3637
    mavlink_logging_data_acked_t log;
    mavlink_msg_logging_data_acked_decode(&message, &log);
3638
    _ackMavlinkLogData(log.sequence);
Gus Grubba's avatar
Gus Grubba committed
3639
    emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence,
3640
                        log.first_message_offset, QByteArray((const char*)log.data, log.length), true);
3641 3642
}

3643 3644 3645 3646 3647 3648
void Vehicle::setFirmwarePluginInstanceData(QObject* firmwarePluginInstanceData)
{
    firmwarePluginInstanceData->setParent(this);
    _firmwarePluginInstanceData = firmwarePluginInstanceData;
}

3649 3650 3651 3652 3653
QString Vehicle::missionFlightMode(void) const
{
    return _firmwarePlugin->missionFlightMode();
}

3654 3655 3656 3657 3658
QString Vehicle::pauseFlightMode(void) const
{
    return _firmwarePlugin->pauseFlightMode();
}

3659 3660 3661 3662 3663
QString Vehicle::rtlFlightMode(void) const
{
    return _firmwarePlugin->rtlFlightMode();
}

DonLakeFlyer's avatar
DonLakeFlyer committed
3664 3665 3666 3667 3668 3669 3670 3671 3672 3673
QString Vehicle::smartRTLFlightMode(void) const
{
    return _firmwarePlugin->smartRTLFlightMode();
}

bool Vehicle::supportsSmartRTL(void) const
{
    return _firmwarePlugin->supportsSmartRTL();
}

3674 3675 3676 3677 3678
QString Vehicle::landFlightMode(void) const
{
    return _firmwarePlugin->landFlightMode();
}

3679 3680 3681 3682 3683
QString Vehicle::takeControlFlightMode(void) const
{
    return _firmwarePlugin->takeControlFlightMode();
}

3684 3685 3686 3687 3688
QString Vehicle::followFlightMode(void) const
{
    return _firmwarePlugin->followFlightMode();
}

3689 3690 3691 3692 3693 3694 3695 3696 3697 3698 3699 3700 3701 3702 3703 3704 3705 3706 3707 3708 3709 3710 3711 3712
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();
}

3713
const QVariantList& Vehicle::toolBarIndicators()
3714 3715 3716 3717 3718 3719 3720 3721
{
    if(_firmwarePlugin) {
        return _firmwarePlugin->toolBarIndicators(this);
    }
    static QVariantList emptyList;
    return emptyList;
}

3722
const QVariantList& Vehicle::staticCameraList(void) const
3723 3724 3725 3726 3727 3728 3729 3730
{
    if (_firmwarePlugin) {
        return _firmwarePlugin->cameraList(this);
    }
    static QVariantList emptyList;
    return emptyList;
}

3731 3732 3733 3734
bool Vehicle::vehicleYawsToNextWaypointInMission(void) const
{
    return _firmwarePlugin->vehicleYawsToNextWaypointInMission(this);
}
3735

3736 3737 3738 3739 3740 3741 3742 3743 3744 3745 3746 3747 3748 3749 3750 3751 3752 3753 3754 3755 3756 3757 3758
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;
}

3759 3760 3761
void Vehicle::_handleADSBVehicle(const mavlink_message_t& message)
{
    mavlink_adsb_vehicle_t adsbVehicle;
Don Gagne's avatar
Don Gagne committed
3762
    static const int maxTimeSinceLastSeen = 15;
3763 3764 3765 3766

    mavlink_msg_adsb_vehicle_decode(&message, &adsbVehicle);
    if (adsbVehicle.flags | ADSB_FLAGS_VALID_COORDS) {
        if (_adsbICAOMap.contains(adsbVehicle.ICAO_address)) {
Don Gagne's avatar
Don Gagne committed
3767
            if (adsbVehicle.tslc <= maxTimeSinceLastSeen) {
Don Gagne's avatar
Don Gagne committed
3768
                _adsbICAOMap[adsbVehicle.ICAO_address]->update(adsbVehicle);
3769
            }
Don Gagne's avatar
Don Gagne committed
3770
        } else if (adsbVehicle.tslc <= maxTimeSinceLastSeen) {
3771 3772 3773 3774 3775 3776 3777
            ADSBVehicle* vehicle = new ADSBVehicle(adsbVehicle, this);
            _adsbICAOMap[adsbVehicle.ICAO_address] = vehicle;
            _adsbVehicles.append(vehicle);
        }
    }
}

3778
void Vehicle::_updateDistanceHeadingToHome(void)
3779 3780 3781
{
    if (coordinate().isValid() && homePosition().isValid()) {
        _distanceToHomeFact.setRawValue(coordinate().distanceTo(homePosition()));
3782 3783 3784 3785 3786
        if (_distanceToHomeFact.rawValue().toDouble() > 1.0) {
            _headingToHomeFact.setRawValue(coordinate().azimuthTo(homePosition()));
        } else {
            _headingToHomeFact.setRawValue(qQNaN());
        }
3787 3788
    } else {
        _distanceToHomeFact.setRawValue(qQNaN());
3789
        _headingToHomeFact.setRawValue(qQNaN());
3790 3791 3792
    }
}

3793 3794 3795 3796 3797 3798 3799 3800 3801 3802 3803 3804 3805 3806 3807 3808 3809
void Vehicle::_updateHeadingToNextWP(void)
{
    const int _currentIndex = _missionManager->currentIndex();
    MissionItem _currentItem;
    QList<MissionItem*> llist = _missionManager->missionItems();

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

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

3810 3811 3812 3813 3814 3815 3816 3817 3818 3819
void Vehicle::_updateDistanceToGCS(void)
{
    QGeoCoordinate gcsPosition = _toolbox->qgcPositionManager()->gcsPosition();
    if (coordinate().isValid() && gcsPosition.isValid()) {
        _distanceToGCSFact.setRawValue(coordinate().distanceTo(gcsPosition));
    } else {
        _distanceToGCSFact.setRawValue(qQNaN());
    }
}

3820 3821 3822 3823 3824
void Vehicle::_updateHobbsMeter(void)
{
    _hobbsFact.setRawValue(hobbsMeter());
}

Don Gagne's avatar
Don Gagne committed
3825 3826 3827 3828 3829 3830 3831 3832 3833 3834 3835
void Vehicle::forceInitialPlanRequestComplete(void)
{
    _initialPlanRequestComplete = true;
    emit initialPlanRequestCompleteChanged(true);
}

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

3836 3837 3838 3839 3840 3841
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) &&
3842
            _parameterManager->parameterExists(FactSystem::defaultComponentId, HOOBS_LO)) {
3843 3844
        Fact* factHi = _parameterManager->getParameter(FactSystem::defaultComponentId, HOOBS_HI);
        Fact* factLo = _parameterManager->getParameter(FactSystem::defaultComponentId, HOOBS_LO);
3845
        uint64_t hobbsTimeSeconds = ((uint64_t)factHi->rawValue().toUInt() << 32 | (uint64_t)factLo->rawValue().toUInt()) / 1000000;
3846 3847 3848 3849 3850
        int hours   = hobbsTimeSeconds / 3600;
        int minutes = (hobbsTimeSeconds % 3600) / 60;
        int seconds = hobbsTimeSeconds % 60;
        QString timeStr;
        timeStr.sprintf("%04d:%02d:%02d", hours, minutes, seconds);
3851
        qCDebug(VehicleLog) << "Hobbs Meter:" << timeStr << "(" << factHi->rawValue().toUInt() << factLo->rawValue().toUInt() << ")";
3852 3853 3854 3855
        return timeStr;
    }
    return QString("0000:00:00");
}
Don Gagne's avatar
Don Gagne committed
3856

3857 3858 3859 3860 3861 3862 3863 3864 3865
void Vehicle::_vehicleParamLoaded(bool ready)
{
    //-- TODO: This seems silly but can you think of a better
    //   way to update this?
    if(ready) {
        emit hobbsMeterChanged();
    }
}

3866
void Vehicle::_updateHighLatencyLink(bool sendCommand)
3867
{
3868 3869 3870 3871
    if (!_priorityLink) {
        return;
    }

3872 3873
    if (_priorityLink->highLatency() != _highLatencyLink) {
        _highLatencyLink = _priorityLink->highLatency();
3874
        _mavCommandAckTimer.setInterval(_highLatencyLink ? _mavCommandAckTimeoutMSecsHighLatency : _mavCommandAckTimeoutMSecs);
3875
        emit highLatencyLinkChanged(_highLatencyLink);
3876 3877

        if (sendCommand) {
acfloria's avatar
acfloria committed
3878 3879 3880 3881
            sendMavCommand(defaultComponentId(),
                           MAV_CMD_CONTROL_HIGH_LATENCY,
                           true,
                           _highLatencyLink ? 1.0f : 0.0f); // request start/stop transmitting over high latency telemetry
3882
        }
3883 3884 3885
    }
}

Gus Grubba's avatar
Gus Grubba committed
3886
void Vehicle::_trafficUpdate(bool alert, QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading)
3887
{
3888
    Q_UNUSED(vehicle_id);
3889 3890 3891
    // 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
3892
        _trafficVehicleMap[traffic_id]->update(alert, location, heading);
3893
    } else {
Gus Grubba's avatar
Gus Grubba committed
3894
        ADSBVehicle* vehicle = new ADSBVehicle(location, heading, alert, this);
3895 3896 3897 3898 3899
        _trafficVehicleMap[traffic_id] = vehicle;
        _adsbVehicles.append(vehicle);
    }

}
3900 3901
void Vehicle::_adsbTimerTimeout()
{
Don Gagne's avatar
Don Gagne committed
3902 3903 3904 3905 3906 3907 3908
    // Remove all expired ADSB vehicle whether from AirMap or ADSB Mavlink
    for (int i=_adsbVehicles.count()-1; i>=0; i--) {
        ADSBVehicle* adsbVehicle = _adsbVehicles.value<ADSBVehicle*>(i);
        if (adsbVehicle->expired()) {
            qDebug() << "ADSB expired";
            _adsbVehicles.removeAt(i);
            adsbVehicle->deleteLater();
3909 3910 3911
        }
    }
}
3912

3913 3914 3915 3916 3917 3918 3919 3920 3921 3922 3923
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();
    }
}

3924 3925 3926 3927 3928 3929 3930 3931 3932 3933
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);
}

3934
void Vehicle::_handleMessageInterval(const mavlink_message_t& message)
Don Gagne's avatar
Don Gagne committed
3935
{
3936 3937 3938 3939 3940 3941 3942 3943 3944
    if (_pidTuningWaitingForRates) {
        mavlink_message_interval_t messageInterval;

        mavlink_msg_message_interval_decode(&message, &messageInterval);

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

3946 3947 3948 3949 3950 3951 3952 3953 3954 3955
        if (_pidTuningMessageRatesUsecs.count() == _pidTuningMessages.count()) {
            // We have back all the rates we requested
            _pidTuningWaitingForRates = false;
            _pidTuningAdjustRates(true);
        }
    }
}

void Vehicle::setPIDTuningTelemetryMode(bool pidTuning)
{
Don Gagne's avatar
Don Gagne committed
3956
    if (pidTuning) {
3957 3958 3959 3960 3961 3962 3963 3964 3965 3966 3967 3968 3969 3970 3971 3972 3973 3974 3975 3976 3977 3978 3979 3980 3981 3982 3983 3984 3985 3986 3987 3988
        if (!_pidTuningTelemetryMode) {
            // First step is to get the current message rates before we adjust them
            _pidTuningTelemetryMode = true;
            _pidTuningWaitingForRates = true;
            _pidTuningMessageRatesUsecs.clear();
            for (int telemetry: _pidTuningMessages) {
                sendMavCommand(defaultComponentId(),
                               MAV_CMD_GET_MESSAGE_INTERVAL,
                               true,                        // show error
                               telemetry);
            }
        }
    } else {
        if (_pidTuningTelemetryMode) {
            _pidTuningTelemetryMode = false;
            if (_pidTuningWaitingForRates) {
                // We never finished waiting for previous rates
                _pidTuningWaitingForRates = false;
            } else {
                _pidTuningAdjustRates(false);
            }
        }
    }
}

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

    for (int telemetry: _pidTuningMessages) {

        if (requestedRate < _pidTuningMessageRatesUsecs[telemetry]) {
Don Gagne's avatar
Don Gagne committed
3989 3990 3991 3992
            sendMavCommand(defaultComponentId(),
                           MAV_CMD_SET_MESSAGE_INTERVAL,
                           true,                        // show error
                           telemetry,
3993
                           setRatesForTuning ? requestedRate : _pidTuningMessageRatesUsecs[telemetry]);
Don Gagne's avatar
Don Gagne committed
3994 3995 3996
        }
    }

3997 3998
    setLiveUpdates(setRatesForTuning);
    _setpointFactGroup.setLiveUpdates(setRatesForTuning);
Don Gagne's avatar
Don Gagne committed
3999 4000
}

4001 4002
void Vehicle::_initializeCsv()
{
4003 4004 4005
    if(!_toolbox->settingsManager()->appSettings()->saveCsvTelemetry()->rawValue().toBool()){
        return;
    }
4006 4007 4008 4009 4010 4011 4012 4013 4014 4015 4016 4017 4018 4019 4020 4021 4022 4023 4024 4025 4026 4027 4028 4029
    QString now = QDateTime::currentDateTime().toString("yyyy-MM-dd hh-mm-ss");
    QString fileName = QString("%1 vehicle%2.csv").arg(now).arg(_id);
    QDir saveDir(_toolbox->settingsManager()->appSettings()->telemetrySavePath());
    _csvLogFile.setFileName(saveDir.absoluteFilePath(fileName));

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

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

void Vehicle::_writeCsvLine()
{
4030 4031 4032 4033 4034 4035 4036 4037 4038 4039
    // Only save the logs after the the vehicle gets armed, unless "Save logs even if vehicle was not armed" is checked
    if(!_csvLogFile.isOpen() &&
           (_armed || _toolbox->settingsManager()->appSettings()->telemetrySaveNotArmed()->rawValue().toBool())){
        _initializeCsv();
    }

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

4040 4041 4042 4043 4044 4045 4046 4047 4048 4049 4050 4051 4052 4053 4054 4055 4056 4057
    QStringList allFactValues;
    QTextStream stream(&_csvLogFile);

    // Write timestamp to csv file
    allFactValues << QDateTime::currentDateTime().toString();
    // Write Vehicle's own facts
    for (const QString& factName : factNames()) {
        allFactValues << getFact(factName)->cookedValueString();
    }
    // write facts from Vehicle's FactGroups
    for (const QString& groupName: factGroupNames()) {
        for (const QString& factName : getFactGroup(groupName)->factNames()) {
            allFactValues << getFactGroup(groupName)->getFact(factName)->cookedValueString();
        }
    }

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

4059 4060 4061 4062 4063 4064 4065 4066 4067 4068 4069 4070
#if !defined(NO_ARDUPILOT_DIALECT)
void Vehicle::flashBootloader(void)
{
    sendMavCommand(defaultComponentId(),
                   MAV_CMD_FLASH_BOOTLOADER,
                   true,        // show error
                   0, 0, 0, 0,  // param 1-4 not used
                   290876);     // magic number

}
#endif

4071 4072
void Vehicle::gimbalControlValue(double pitch, double yaw)
{
Gus Grubba's avatar
Gus Grubba committed
4073
    //qDebug() << "Gimbal:" << pitch << yaw;
4074 4075 4076 4077 4078 4079 4080 4081 4082 4083 4084 4085
    sendMavCommand(
        _defaultComponentId,
        MAV_CMD_DO_MOUNT_CONTROL,
        false,                               // show errors
        static_cast<float>(pitch),           // Pitch 0 - 90
        0,                                   // Roll (not used)
        static_cast<float>(yaw),             // Yaw -180 - 180
        0,                                   // Altitude (not used)
        0,                                   // Latitude (not used)
        0,                                   // Longitude (not used)
        MAV_MOUNT_MODE_MAVLINK_TARGETING);   // MAVLink Roll,Pitch,Yaw
}
4086

Gus Grubba's avatar
Gus Grubba committed
4087 4088
void Vehicle::gimbalPitchStep(int direction)
{
Gus Grubba's avatar
Gus Grubba committed
4089 4090
    if(_haveGimbalData) {
        //qDebug() << "Pitch:" << _curGimbalPitch << direction << (_curGimbalPitch + direction);
Gus Grubba's avatar
Gus Grubba committed
4091 4092 4093 4094 4095 4096 4097
        double p = static_cast<double>(_curGimbalPitch + direction);
        gimbalControlValue(p, static_cast<double>(_curGinmbalYaw));
    }
}

void Vehicle::gimbalYawStep(int direction)
{
Gus Grubba's avatar
Gus Grubba committed
4098 4099
    if(_haveGimbalData) {
        //qDebug() << "Yaw:" << _curGinmbalYaw << direction << (_curGinmbalYaw + direction);
Gus Grubba's avatar
Gus Grubba committed
4100
        double y = static_cast<double>(_curGinmbalYaw + direction);
Gus Grubba's avatar
Gus Grubba committed
4101
        gimbalControlValue(static_cast<double>(_curGimbalPitch), y);
Gus Grubba's avatar
Gus Grubba committed
4102 4103 4104 4105 4106
    }
}

void Vehicle::centerGimbal()
{
Gus Grubba's avatar
Gus Grubba committed
4107
    if(_haveGimbalData) {
Gus Grubba's avatar
Gus Grubba committed
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
        gimbalControlValue(0.0, 0.0);
    }
}

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

Gus Grubba's avatar
Gus Grubba committed
4134 4135 4136 4137 4138 4139 4140
void Vehicle::_handleObstacleDistance(const mavlink_message_t& message)
{
    mavlink_obstacle_distance_t o;
    mavlink_msg_obstacle_distance_decode(&message, &o);
    _objectAvoidance->update(&o);
}

4141 4142 4143
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------

4144 4145 4146 4147 4148 4149
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";
4150
const char* VehicleBatteryFactGroup::_instantPowerFactName =                "instantPower";
4151 4152
const char* VehicleBatteryFactGroup::_timeRemainingFactName =               "timeRemaining";
const char* VehicleBatteryFactGroup::_chargeStateFactName =                 "chargeState";
4153 4154 4155 4156 4157 4158 4159 4160 4161

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;
4162
const double VehicleBatteryFactGroup::_instantPowerUnavailable =      -1.0;
4163

Don Gagne's avatar
Don Gagne committed
4164 4165
VehicleBatteryFactGroup::VehicleBatteryFactGroup(QObject* parent)
    : FactGroup(1000, ":/json/Vehicle/BatteryFact.json", parent)
4166 4167 4168
    , _voltageFact                  (0, _voltageFactName,                   FactMetaData::valueTypeDouble)
    , _percentRemainingFact         (0, _percentRemainingFactName,          FactMetaData::valueTypeInt32)
    , _mahConsumedFact              (0, _mahConsumedFactName,               FactMetaData::valueTypeInt32)
Don Gagne's avatar
Don Gagne committed
4169
    , _currentFact                  (0, _currentFactName,                   FactMetaData::valueTypeFloat)
4170 4171
    , _temperatureFact              (0, _temperatureFactName,               FactMetaData::valueTypeDouble)
    , _cellCountFact                (0, _cellCountFactName,                 FactMetaData::valueTypeInt32)
4172
    , _instantPowerFact             (0, _instantPowerFactName,              FactMetaData::valueTypeFloat)
4173 4174
    , _timeRemainingFact            (0, _timeRemainingFactName,             FactMetaData::valueTypeInt32)
    , _chargeStateFact              (0, _chargeStateFactName,               FactMetaData::valueTypeUint8)
4175
{
4176 4177 4178 4179 4180 4181
    _addFact(&_voltageFact,                 _voltageFactName);
    _addFact(&_percentRemainingFact,        _percentRemainingFactName);
    _addFact(&_mahConsumedFact,             _mahConsumedFactName);
    _addFact(&_currentFact,                 _currentFactName);
    _addFact(&_temperatureFact,             _temperatureFactName);
    _addFact(&_cellCountFact,               _cellCountFactName);
4182
    _addFact(&_instantPowerFact,            _instantPowerFactName);
4183 4184
    _addFact(&_timeRemainingFact,           _timeRemainingFactName);
    _addFact(&_chargeStateFact,             _chargeStateFactName);
Don Gagne's avatar
Don Gagne committed
4185 4186 4187 4188 4189 4190 4191 4192

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

4196 4197 4198 4199
const char* VehicleWindFactGroup::_directionFactName =      "direction";
const char* VehicleWindFactGroup::_speedFactName =          "speed";
const char* VehicleWindFactGroup::_verticalSpeedFactName =  "verticalSpeed";

4200 4201 4202 4203 4204 4205 4206 4207 4208 4209 4210 4211 4212 4213 4214 4215
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());
}

4216 4217 4218 4219 4220 4221 4222
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";

4223 4224 4225 4226 4227 4228 4229 4230 4231 4232 4233 4234 4235 4236 4237 4238 4239 4240 4241 4242 4243
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());
}
4244 4245 4246 4247 4248 4249 4250 4251 4252 4253 4254 4255 4256 4257 4258 4259 4260 4261 4262 4263

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
4264 4265 4266 4267 4268 4269 4270 4271 4272 4273 4274 4275 4276 4277 4278 4279 4280 4281 4282 4283 4284 4285 4286 4287

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
4288 4289 4290 4291 4292 4293 4294 4295 4296 4297 4298 4299 4300 4301 4302 4303 4304 4305 4306 4307 4308 4309 4310 4311 4312 4313 4314 4315 4316 4317 4318 4319

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

const char* VehicleDistanceSensorFactGroup::_rotationNoneFactName =     "rotationNone";
4322
const char* VehicleDistanceSensorFactGroup::_rotationYaw45FactName =    "rotationYaw45";
4323
const char* VehicleDistanceSensorFactGroup::_rotationYaw90FactName =    "rotationYaw90";
4324
const char* VehicleDistanceSensorFactGroup::_rotationYaw135FactName =   "rotationYaw135";
4325
const char* VehicleDistanceSensorFactGroup::_rotationYaw180FactName =   "rotationYaw180";
4326
const char* VehicleDistanceSensorFactGroup::_rotationYaw225FactName =   "rotationYaw225";
4327
const char* VehicleDistanceSensorFactGroup::_rotationYaw270FactName =   "rotationYaw270";
4328 4329 4330
const char* VehicleDistanceSensorFactGroup::_rotationYaw315FactName =   "rotationYaw315";
const char* VehicleDistanceSensorFactGroup::_rotationPitch90FactName =  "rotationPitch90";
const char* VehicleDistanceSensorFactGroup::_rotationPitch270FactName = "rotationPitch270";
4331 4332 4333 4334

VehicleDistanceSensorFactGroup::VehicleDistanceSensorFactGroup(QObject* parent)
    : FactGroup             (1000, ":/json/Vehicle/DistanceSensorFact.json", parent)
    , _rotationNoneFact     (0, _rotationNoneFactName,      FactMetaData::valueTypeDouble)
4335
    , _rotationYaw45Fact    (0, _rotationYaw45FactName,     FactMetaData::valueTypeDouble)
4336
    , _rotationYaw90Fact    (0, _rotationYaw90FactName,     FactMetaData::valueTypeDouble)
4337
    , _rotationYaw135Fact   (0, _rotationYaw135FactName,    FactMetaData::valueTypeDouble)
4338
    , _rotationYaw180Fact   (0, _rotationYaw180FactName,    FactMetaData::valueTypeDouble)
4339
    , _rotationYaw225Fact   (0, _rotationYaw225FactName,    FactMetaData::valueTypeDouble)
4340
    , _rotationYaw270Fact   (0, _rotationYaw270FactName,    FactMetaData::valueTypeDouble)
4341 4342 4343 4344 4345 4346 4347 4348 4349 4350 4351 4352 4353 4354 4355 4356
    , _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);
4357 4358 4359

    // Start out as not available "--.--"
    _rotationNoneFact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4360 4361
    _rotationYaw45Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _rotationYaw135Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4362 4363
    _rotationYaw90Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _rotationYaw180Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4364
    _rotationYaw225Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4365
    _rotationYaw270Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4366 4367
    _rotationPitch90Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
    _rotationPitch270Fact.setRawValue(std::numeric_limits<float>::quiet_NaN());
4368
}
4369 4370 4371 4372 4373 4374 4375 4376 4377 4378 4379 4380 4381 4382 4383 4384 4385 4386 4387 4388 4389 4390 4391 4392 4393 4394 4395 4396 4397 4398 4399 4400 4401 4402 4403 4404 4405 4406 4407 4408 4409 4410 4411 4412 4413 4414 4415 4416 4417 4418 4419 4420 4421 4422 4423 4424 4425 4426 4427 4428 4429 4430 4431 4432 4433 4434

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