QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
Vehicle.cc
Go to the documentation of this file.
1#include "Vehicle.h"
2#include "Actuators.h"
6#include "TerrainFactGroup.h"
13#include "VehicleGPSFactGroup.h"
18#include "VehicleRPMFactGroup.h"
23#include "VehicleSupports.h"
24#include "ADSBVehicleManager.h"
25#include "AudioOutput.h"
26#include "AutoPilotPlugin.h"
28#include "MAVLinkEventManager.h"
29#include "FirmwarePlugin.h"
31#include "FTPManager.h"
32#include "GeoFenceManager.h"
35#include "Joystick.h"
36#include "JoystickManager.h"
37#include "LinkManager.h"
38#include "MavCommandQueue.h"
41#include "MAVLinkLogManager.h"
42#include "MAVLinkProtocol.h"
43#include "MissionCommandTree.h"
44#include "MissionManager.h"
45#include "MultiVehicleManager.h"
46#include "ParameterManager.h"
48#include "PositionManager.h"
49#include "AppMessages.h"
50#include "QGCMath.h"
51#include "QGCApplication.h"
52#include "QGCCameraManager.h"
53#include "QGCCorePlugin.h"
54#include "QGCImageProvider.h"
55#include "QGCLoggingCategory.h"
56#include "QGCQGeoCoordinate.h"
57#include "RallyPointManager.h"
58#include "RemoteIDManager.h"
60#include "SettingsManager.h"
61#include "AppSettings.h"
62#include "FlyViewSettings.h"
63#include "StandardModes.h"
65#include "TerrainQuery.h"
66#include "TrajectoryPoints.h"
67#include "VehicleLinkManager.h"
68#include "MAVLinkStreamConfig.h"
69#include "QGCMapCircle.h"
70#include "QmlObjectListModel.h"
71#include "SysStatusSensorInfo.h"
73#include "VideoManager.h"
74#include "VideoSettings.h"
75#include "QGCSensors.h"
76#include "StatusTextHandler.h"
78#include "GimbalController.h"
79#include "MavlinkSettings.h"
80#include "APM.h"
81
82#ifdef QT_DEBUG
83#include "MockLink.h"
84#endif
85
86#include <QtCore/QDateTime>
87
88QGC_LOGGING_CATEGORY(VehicleLog, "Vehicle.Vehicle")
89
90#define UPDATE_TIMER 50
91#define DEFAULT_LAT 38.965767f
92#define DEFAULT_LON -120.083923f
93
94// After a second GCS has requested control and we have given it permission to takeover, we will remove takeover permission automatically after this timeout
95// If the second GCS didn't get control
96#define REQUEST_OPERATOR_CONTROL_ALLOW_TAKEOVER_TIMEOUT_MSECS 10000
97
98const QString guided_mode_not_supported_by_vehicle = QObject::tr("Guided mode not supported by Vehicle.");
99
100// Standard connected vehicle
102 int vehicleId,
103 int defaultComponentId,
104 MAV_AUTOPILOT firmwareType,
105 MAV_TYPE vehicleType,
106 QObject* parent)
107 : VehicleFactGroup (parent)
108 , _systemID (vehicleId)
109 , _defaultComponentId (defaultComponentId)
110 , _firmwareType (firmwareType)
111 , _vehicleType (vehicleType)
112 , _defaultCruiseSpeed (SettingsManager::instance()->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
113 , _defaultHoverSpeed (SettingsManager::instance()->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
114 , _sysStatusSensorInfo (std::make_unique<SysStatusSensorInfo>(this))
115 , _trajectoryPoints (new TrajectoryPoints(this, this))
116 , _cameraTriggerPoints (std::make_unique<QmlObjectListModel>(this))
117 , _orbitMapCircle (std::make_unique<QGCMapCircle>(this))
118 , _mavlinkStreamConfig (std::make_unique<MAVLinkStreamConfig>(std::bind(&Vehicle::_setMessageInterval, this, std::placeholders::_1, std::placeholders::_2)))
119 , _vehicleFactGroup (this)
120{
121 connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &Vehicle::_activeVehicleChanged);
122
123 connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived);
124 connect(MAVLinkProtocol::instance(), &MAVLinkProtocol::mavlinkMessageStatus, this, &Vehicle::_mavlinkMessageStatus);
125
126 connect(this, &Vehicle::flightModeChanged, this, &Vehicle::_handleFlightModeChanged);
127 connect(this, &Vehicle::armedChanged, this, &Vehicle::_announceArmedChanged);
128 connect(this, &Vehicle::flyingChanged, this, [this](bool flying){
129 if (flying) {
132 }
133 });
134
136
137 _commonInit(link);
138
139 // Set video stream to udp if running ArduSub and Video is disabled
140 if (sub() && SettingsManager::instance()->videoSettings()->videoSource()->rawValue() == VideoSettings::videoDisabled) {
142 SettingsManager::instance()->videoSettings()->lowLatencyMode()->setRawValue(true);
143 }
144
145 _autopilotPlugin = _firmwarePlugin->autopilotPlugin(this);
146 _autopilotPlugin->setParent(this);
147
148 // PreArm Error self-destruct timer
149 connect(&_prearmErrorTimer, &QTimer::timeout, this, &Vehicle::_prearmErrorTimeout);
150 _prearmErrorTimer.setInterval(_prearmErrorTimeoutMSecs);
151 _prearmErrorTimer.setSingleShot(true);
152
153 // Command queue timer is managed by MavCommandQueue itself.
154
155 // MAV_TYPE_GENERIC is used by unit test for creating a vehicle which doesn't do the connect sequence. This
156 // way we can test the methods that are used within the connect sequence.
157 if (!QGC::runningUnitTests() || _vehicleType != MAV_TYPE_GENERIC) {
159 }
160
161 _firmwarePlugin->initializeVehicle(this);
162 for(auto& factName: factNames()) {
163 _firmwarePlugin->adjustMetaData(vehicleType, getFact(factName)->metaData());
164 }
165
166 _sendMultipleTimer.start(_sendMessageMultipleIntraMessageDelay);
167 connect(&_sendMultipleTimer, &QTimer::timeout, this, &Vehicle::_sendMessageMultipleNext);
168
169 connect(&_orbitTelemetryTimer, &QTimer::timeout, this, &Vehicle::_orbitTelemetryTimeout);
170
171 // Start csv logger
172 connect(&_csvLogTimer, &QTimer::timeout, this, &Vehicle::_writeCsvLine);
173 _csvLogTimer.start(1000);
174
175}
176
177// Disconnected Vehicle for offline editing
178Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
179 MAV_TYPE vehicleType,
180 QObject* parent)
181 : VehicleFactGroup (parent)
182 , _systemID (0)
183 , _defaultComponentId (MAV_COMP_ID_ALL)
184 , _offlineEditingVehicle (true)
185 , _firmwareType (firmwareType)
186 , _vehicleType (vehicleType)
187 , _defaultCruiseSpeed (SettingsManager::instance()->appSettings()->offlineEditingCruiseSpeed()->rawValue().toDouble())
188 , _defaultHoverSpeed (SettingsManager::instance()->appSettings()->offlineEditingHoverSpeed()->rawValue().toDouble())
189 , _capabilityBitsKnown (true)
190 , _capabilityBits (MAV_PROTOCOL_CAPABILITY_MISSION_FENCE | MAV_PROTOCOL_CAPABILITY_MISSION_RALLY)
191 , _sysStatusSensorInfo (std::make_unique<SysStatusSensorInfo>(this))
192 , _trajectoryPoints (new TrajectoryPoints(this, this))
193 , _cameraTriggerPoints (std::make_unique<QmlObjectListModel>(this))
194 , _orbitMapCircle (std::make_unique<QGCMapCircle>(this))
195 , _mavlinkStreamConfig (std::make_unique<MAVLinkStreamConfig>(std::bind(&Vehicle::_setMessageInterval, this, std::placeholders::_1, std::placeholders::_2)))
196 , _vehicleFactGroup (this)
197{
198 // This will also set the settings based firmware/vehicle types. So it needs to happen first.
199 if (_firmwareType == MAV_AUTOPILOT_TRACK) {
201 }
202
203 _commonInit(nullptr /* link */);
204
205 connect(SettingsManager::instance()->appSettings()->offlineEditingCruiseSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineCruiseSpeedSettingChanged);
206 connect(SettingsManager::instance()->appSettings()->offlineEditingHoverSpeed(), &Fact::rawValueChanged, this, &Vehicle::_offlineHoverSpeedSettingChanged);
207
208 _offlineFirmwareTypeSettingChanged(_firmwareType); // This adds correct terrain capability bit
209 _firmwarePlugin->initializeVehicle(this);
210}
211
213{
214 connect(SettingsManager::instance()->appSettings()->offlineEditingFirmwareClass(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged);
215 connect(SettingsManager::instance()->appSettings()->offlineEditingVehicleClass(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged);
216
217 _offlineFirmwareTypeSettingChanged(SettingsManager::instance()->appSettings()->offlineEditingFirmwareClass()->rawValue());
218 _offlineVehicleTypeSettingChanged(SettingsManager::instance()->appSettings()->offlineEditingVehicleClass()->rawValue());
219}
220
222{
223 disconnect(SettingsManager::instance()->appSettings()->offlineEditingFirmwareClass(), &Fact::rawValueChanged, this, &Vehicle::_offlineFirmwareTypeSettingChanged);
224 disconnect(SettingsManager::instance()->appSettings()->offlineEditingVehicleClass(), &Fact::rawValueChanged, this, &Vehicle::_offlineVehicleTypeSettingChanged);
225}
226
227void Vehicle::_commonInit(LinkInterface* link)
228{
229 _firmwarePlugin = FirmwarePluginManager::instance()->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
230
232
233 connect(this, &Vehicle::coordinateChanged, this, &Vehicle::_updateDistanceHeadingHome);
234 connect(this, &Vehicle::coordinateChanged, this, &Vehicle::_updateDistanceHeadingGCS);
235 connect(this, &Vehicle::homePositionChanged, this, &Vehicle::_updateDistanceHeadingHome);
236 connect(this, &Vehicle::hobbsMeterChanged, this, &Vehicle::_updateHobbsMeter);
239
240 connect(QGCPositionManager::instance(), &QGCPositionManager::gcsPositionChanged, this, &Vehicle::_updateDistanceHeadingGCS);
241 connect(QGCPositionManager::instance(), &QGCPositionManager::gcsPositionChanged, this, &Vehicle::_updateHomepoint);
242
244 connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError);
245 connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_firstMissionLoadComplete);
246 connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_clearCameraTriggerPoints);
247 connect(_missionManager, &MissionManager::sendComplete, this, &Vehicle::_clearCameraTriggerPoints);
248 connect(_missionManager, &MissionManager::currentIndexChanged, this, &Vehicle::_updateHeadingToNextWP);
249 connect(_missionManager, &MissionManager::currentIndexChanged, this, &Vehicle::_updateMissionItemIndex);
250
253
254 _standardModes = new StandardModes (this, this);
255 _componentInformationManager = new ComponentInformationManager (this, this);
257 _ftpManager = new FTPManager (this);
258
259 // Command send/ack queue and request-message coordinator must exist before any
260 // manager that may call Vehicle::sendMavCommand / requestMessage during construction
261 // (e.g. VehicleLinkManager::_addLink() → _updatePrimaryLink → sendMavCommand).
262 _mavCmdQueue = new MavCommandQueue(this);
263 connect(_mavCmdQueue, &MavCommandQueue::commandResult, this, &Vehicle::mavCommandResult);
264 _reqMsgCoord = new RequestMessageCoordinator(this, _mavCmdQueue);
265 _messageIntervalManager = new MessageIntervalManager(this, _mavCmdQueue, _reqMsgCoord);
266 connect(_messageIntervalManager, &MessageIntervalManager::mavlinkMsgIntervalsChanged,
270
272 if (link) {
273 _vehicleLinkManager->_addLink(link);
274 }
275
277 // Re-emit flightModeChanged after available modes mapping updates so UI refreshes
278 // the human-readable mode name even if HEARTBEAT arrived earlier.
279 connect(_standardModes, &StandardModes::modesUpdated, this, [this]() {
281 });
282
283 _parameterManager = new ParameterManager(this);
284 connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
285 connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, [this](bool) {
286 emit hasGripperChanged();
287 });
289 this, &Vehicle::_gotProgressUpdate);
290 connect(_parameterManager, &ParameterManager::loadProgressChanged, this, &Vehicle::_gotProgressUpdate);
291
292 _objectAvoidance = new VehicleObjectAvoidance(this, this);
293
294 _autotune = _firmwarePlugin->createAutotune(this);
295
296 // GeoFenceManager needs to access ParameterManager so make sure to create after
298 connect(_geoFenceManager, &GeoFenceManager::error, this, &Vehicle::_geoFenceManagerError);
299 connect(_geoFenceManager, &GeoFenceManager::loadComplete, this, &Vehicle::_firstGeoFenceLoadComplete);
300
302 connect(_rallyPointManager, &RallyPointManager::error, this, &Vehicle::_rallyPointManagerError);
303 connect(_rallyPointManager, &RallyPointManager::loadComplete, this, &Vehicle::_firstRallyPointLoadComplete);
304
305 // Remote ID manager might want to acces parameters so make sure to create it after
307
308 // Flight modes can differ based on advanced mode
310
331
332 if (!_offlineEditingVehicle) {
334 }
335
337
338 _createImageProtocolManager();
339 _createStatusTextHandler();
340 _createMAVLinkLogManager();
341 _createSigningController();
342 _createMAVLinkEventManager();
343
344 // _addFactGroup(_vehicleFactGroup, _vehicleFactGroupName);
363
364 // Add firmware-specific fact groups, if provided
365 QMap<QString, FactGroup*>* fwFactGroups = _firmwarePlugin->factGroups();
366 if (fwFactGroups) {
367 for (auto it = fwFactGroups->keyValueBegin(); it != fwFactGroups->keyValueEnd(); ++it) {
368 _addFactGroup(it->second, it->first);
369 }
370 }
371
372 _flightTimeUpdater.setInterval(1000);
373 _flightTimeUpdater.setSingleShot(false);
374 connect(&_flightTimeUpdater, &QTimer::timeout, this, &Vehicle::_updateFlightTime);
375
376 // Set video stream to udp if running ArduSub and Video is disabled
377 if (sub() && SettingsManager::instance()->videoSettings()->videoSource()->rawValue() == VideoSettings::videoDisabled) {
379 SettingsManager::instance()->videoSettings()->lowLatencyMode()->setRawValue(true);
380 }
381
382 _gimbalController = new GimbalController(this);
383 _vehicleSupports = new VehicleSupports(this);
384
385 _createCameraManager();
386}
387
389{
390 qCDebug(VehicleLog) << "~Vehicle" << this;
391
392 // Stop all timers and disconnect their signals to prevent any callbacks during destruction.
393 // Even though _stopCommandProcessing() should have been called earlier via VehicleLinkManager,
394 // we do it again here defensively in case the vehicle is destroyed without going through
395 // the normal link removal path (e.g., in unit tests).
396 if (_mavCmdQueue) {
397 _mavCmdQueue->stop();
398 }
399 _sendMultipleTimer.stop();
400 _sendMultipleTimer.disconnect();
401 _prearmErrorTimer.stop();
402 _prearmErrorTimer.disconnect();
403
404 delete _missionManager;
405 _missionManager = nullptr;
406
407 delete _autopilotPlugin;
408 _autopilotPlugin = nullptr;
409}
410
429
432
433QObject* Vehicle::sysStatusSensorInfo() { return _sysStatusSensorInfo.get(); }
434QmlObjectListModel* Vehicle::cameraTriggerPoints() { return _cameraTriggerPoints.get(); }
436
437void Vehicle::_deleteCameraManager()
438{
439 if(_cameraManager) {
440 // Disconnect all signals to prevent any callbacks during or after deletion
441 _cameraManager->disconnect();
442 delete _cameraManager;
443 _cameraManager = nullptr;
444 }
445}
446
447void Vehicle::_deleteGimbalController()
448{
449 if (_gimbalController) {
450 // Disconnect all signals to prevent any callbacks during or after deletion
451 _gimbalController->disconnect();
452 delete _gimbalController;
453 _gimbalController = nullptr;
454 }
455}
456
457void Vehicle::_stopCommandProcessing()
458{
459 qCDebug(VehicleLog) << "_stopCommandProcessing - stopping timers and clearing pending commands";
460
461 // Stop timers AND disconnect their signals to prevent any pending callbacks
462 // from being delivered after this point. This is critical during vehicle destruction
463 // where a queued callback could access a partially-destroyed vehicle.
464 if (_mavCmdQueue) {
465 _mavCmdQueue->stop();
466 }
467 if (_reqMsgCoord) {
468 _reqMsgCoord->stop();
469 }
470 _sendMultipleTimer.stop();
471 _sendMultipleTimer.disconnect();
472}
473
475{
476 _firmwareType = static_cast<MAV_AUTOPILOT>(varFirmwareType.toInt());
477 _firmwarePlugin = FirmwarePluginManager::instance()->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
478 if (_firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA) {
479 _capabilityBits |= MAV_PROTOCOL_CAPABILITY_TERRAIN;
480 } else {
481 _capabilityBits &= ~MAV_PROTOCOL_CAPABILITY_TERRAIN;
482 }
483 emit firmwareTypeChanged();
484 emit capabilityBitsChanged(_capabilityBits);
485}
486
488{
489 _vehicleType = static_cast<MAV_TYPE>(varVehicleType.toInt());
490 emit vehicleTypeChanged();
491}
492
493void Vehicle::_offlineCruiseSpeedSettingChanged(QVariant value)
494{
495 _defaultCruiseSpeed = value.toDouble();
496 emit defaultCruiseSpeedChanged(_defaultCruiseSpeed);
497}
498
499void Vehicle::_offlineHoverSpeedSettingChanged(QVariant value)
500{
501 _defaultHoverSpeed = value.toDouble();
502 emit defaultHoverSpeedChanged(_defaultHoverSpeed);
503}
504
506{
507 return QGCMAVLink::firmwareClassToString(_firmwareType);
508}
509
511{
512 _messagesReceived = 0;
513 _messagesSent = 0;
514 _messagesLost = 0;
515 _messageSeq = 0;
516 _heardFrom = false;
517}
518
519void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message)
520{
521 if (message.sysid != _systemID && message.sysid != 0) {
522 // We allow RADIO_STATUS messages which come from a link the vehicle is using to pass through and be handled
523 if (!(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS && _vehicleLinkManager->containsLink(link))) {
524 return;
525 }
526 }
527
528 // We give the link manager first whack since it it reponsible for adding new links
530
531 //-- Check link status
532 _messagesReceived++;
534 if(!_heardFrom) {
535 if(message.msgid == MAVLINK_MSG_ID_HEARTBEAT) {
536 _heardFrom = true;
537 _compID = message.compid;
538 _messageSeq = message.seq + 1;
539 }
540 } else {
541 if(_compID == message.compid) {
542 uint16_t seq_received = static_cast<uint16_t>(message.seq);
543 uint16_t packet_lost_count = 0;
544 //-- Account for overflow during packet loss
545 if(seq_received < _messageSeq) {
546 packet_lost_count = (seq_received + 255) - _messageSeq;
547 } else {
548 packet_lost_count = seq_received - _messageSeq;
549 }
550 _messageSeq = message.seq + 1;
551 _messagesLost += packet_lost_count;
552 if(packet_lost_count)
553 emit messagesLostChanged();
554 }
555 }
556
557 // Give the plugin a change to adjust the message contents
558 if (!_firmwarePlugin->adjustIncomingMavlinkMessage(this, &message)) {
559 return;
560 }
561
562 // Give the Core Plugin access to all mavlink traffic
563 if (!QGCCorePlugin::instance()->mavlinkMessage(this, link, message)) {
564 return;
565 }
566
568 return;
569 }
570 _ftpManager->_mavlinkMessageReceived(message);
571 _parameterManager->mavlinkMessageReceived(message);
572 (void) QMetaObject::invokeMethod(_imageProtocolManager, "mavlinkMessageReceived", Qt::AutoConnection, message);
574
575 _reqMsgCoord->handleReceivedMessage(message);
576
577 // Handle creation of dynamic fact group lists
580
581 // Let the fact groups take a whack at the mavlink traffic
582 for (FactGroup* factGroup : factGroups()) {
583 factGroup->handleMessage(this, message);
584 }
585
586 this->handleMessage(this, message);
587
588 switch (message.msgid) {
589 case MAVLINK_MSG_ID_HOME_POSITION:
590 _handleHomePosition(message);
591 break;
592 case MAVLINK_MSG_ID_HEARTBEAT:
593 _handleHeartbeat(message);
594 break;
595 case MAVLINK_MSG_ID_RC_CHANNELS:
596 _handleRCChannels(message);
597 break;
598 case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
599 {
600 mavlink_servo_output_raw_t servoOutputRaw;
601 mavlink_msg_servo_output_raw_decode(&message, &servoOutputRaw);
602
603 // ArduPilot commonly publishes servo1_raw..servo16_raw in a single packet (port may remain 0).
604 const uint16_t rawValues[16] = {
605 servoOutputRaw.servo1_raw,
606 servoOutputRaw.servo2_raw,
607 servoOutputRaw.servo3_raw,
608 servoOutputRaw.servo4_raw,
609 servoOutputRaw.servo5_raw,
610 servoOutputRaw.servo6_raw,
611 servoOutputRaw.servo7_raw,
612 servoOutputRaw.servo8_raw,
613 servoOutputRaw.servo9_raw,
614 servoOutputRaw.servo10_raw,
615 servoOutputRaw.servo11_raw,
616 servoOutputRaw.servo12_raw,
617 servoOutputRaw.servo13_raw,
618 servoOutputRaw.servo14_raw,
619 servoOutputRaw.servo15_raw,
620 servoOutputRaw.servo16_raw
621 };
622
623 for (int servoIndex = 0; servoIndex < _servoOutputRawValues.size() && servoIndex < 16; servoIndex++) {
624 _servoOutputRawValues[servoIndex] = (rawValues[servoIndex] == UINT16_MAX) ? -1 : static_cast<int>(rawValues[servoIndex]);
625 }
626
628 }
629 break;
630 case MAVLINK_MSG_ID_BATTERY_STATUS:
631 _handleBatteryStatus(message);
632 break;
633 case MAVLINK_MSG_ID_SYS_STATUS:
634 _handleSysStatus(message);
635 break;
636 case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
637 _handleExtendedSysState(message);
638 break;
639 case MAVLINK_MSG_ID_COMMAND_ACK:
640 _handleCommandAck(message);
641 break;
642 case MAVLINK_MSG_ID_LOGGING_DATA:
643 _handleMavlinkLoggingData(message);
644 break;
645 case MAVLINK_MSG_ID_LOGGING_DATA_ACKED:
646 _handleMavlinkLoggingDataAcked(message);
647 break;
648 case MAVLINK_MSG_ID_GPS_RAW_INT:
649 _handleGpsRawInt(message);
650 break;
651 case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
652 _handleGlobalPositionInt(message);
653 break;
654 case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED:
655 _handleCameraImageCaptured(message);
656 break;
657 case MAVLINK_MSG_ID_ADSB_VEHICLE:
659 break;
660 case MAVLINK_MSG_ID_HIGH_LATENCY:
661 _handleHighLatency(message);
662 break;
663 case MAVLINK_MSG_ID_HIGH_LATENCY2:
664 _handleHighLatency2(message);
665 break;
666 case MAVLINK_MSG_ID_STATUSTEXT:
667 m_statusTextHandler->mavlinkMessageReceived(message);
668 break;
669 case MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS:
670 _handleOrbitExecutionStatus(message);
671 break;
672 case MAVLINK_MSG_ID_PING:
673 _handlePing(link, message);
674 break;
675 case MAVLINK_MSG_ID_OBSTACLE_DISTANCE:
676 _handleObstacleDistance(message);
677 break;
678 case MAVLINK_MSG_ID_FENCE_STATUS:
679 _handleFenceStatus(message);
680 break;
681
682 case MAVLINK_MSG_ID_EVENT:
683 case MAVLINK_MSG_ID_CURRENT_EVENT_SEQUENCE:
684 case MAVLINK_MSG_ID_RESPONSE_EVENT_ERROR:
685 _handleEventMessage(message);
686 break;
687
688 case MAVLINK_MSG_ID_SERIAL_CONTROL:
689 {
690 mavlink_serial_control_t ser;
691 mavlink_msg_serial_control_decode(&message, &ser);
692 if (static_cast<size_t>(ser.count) > sizeof(ser.data)) {
693 qCWarning(VehicleLog) << "Invalid count for SERIAL_CONTROL, discarding." << ser.count;
694 } else {
695 emit mavlinkSerialControl(ser.device, ser.flags, ser.timeout, ser.baudrate,
696 QByteArray(reinterpret_cast<const char*>(ser.data), ser.count));
697 }
698 }
699 break;
700 case MAVLINK_MSG_ID_AVAILABLE_MODES_MONITOR:
701 {
702 // Avoid duplicate requests during initial connection setup
704 mavlink_available_modes_monitor_t availableModesMonitor;
705 mavlink_msg_available_modes_monitor_decode(&message, &availableModesMonitor);
706 _standardModes->availableModesMonitorReceived(availableModesMonitor.seq);
707 }
708 break;
709 }
710 case MAVLINK_MSG_ID_CURRENT_MODE:
711 _handleCurrentMode(message);
712 break;
713
714 // Following are ArduPilot dialect messages
715#if !defined(QGC_NO_ARDUPILOT_DIALECT)
716 case MAVLINK_MSG_ID_CAMERA_FEEDBACK:
717 _handleCameraFeedback(message);
718 break;
719#endif
720 case MAVLINK_MSG_ID_LOG_ENTRY:
721 {
722 mavlink_log_entry_t log{};
723 mavlink_msg_log_entry_decode(&message, &log);
724 emit logEntry(log.time_utc, log.size, log.id, log.num_logs, log.last_log_num);
725 break;
726 }
727 case MAVLINK_MSG_ID_LOG_DATA:
728 {
729 mavlink_log_data_t log{};
730 mavlink_msg_log_data_decode(&message, &log);
731 if (static_cast<size_t>(log.count) > sizeof(log.data)) {
732 qCWarning(VehicleLog) << "Invalid count for LOG_DATA, discarding." << log.count;
733 } else {
734 emit logData(log.ofs, log.id, log.count, log.data);
735 }
736 break;
737 }
738 case MAVLINK_MSG_ID_MESSAGE_INTERVAL:
739 {
740 _messageIntervalManager->handleMessageInterval(message);
741 break;
742 }
743 case MAVLINK_MSG_ID_CONTROL_STATUS:
744 _handleControlStatus(message);
745 break;
746 case MAVLINK_MSG_ID_COMMAND_LONG:
747 _handleCommandLong(message);
748 break;
749 }
750
751 // This must be emitted after the vehicle processes the message. This way the vehicle state is up to date when anyone else
752 // does processing.
753 emit mavlinkMessageReceived(message);
754}
755
756#if !defined(QGC_NO_ARDUPILOT_DIALECT)
757void Vehicle::_handleCameraFeedback(const mavlink_message_t& message)
758{
759 // If CAMERA_IMAGE_CAPTURED is supported, then CAMERA_FEEDBACK is redundant and should be ignored
760 // to avoid duplicate points.
761 if (_cameraImageCapturedMessageAvailable) {
762 return;
763 }
764
765 mavlink_camera_feedback_t feedback;
766
767 mavlink_msg_camera_feedback_decode(&message, &feedback);
768
769 QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lng / qPow(10.0, 7.0), feedback.alt_msl);
770 qCDebug(VehicleLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.img_idx;
771 _cameraTriggerPoints->append(new QGCQGeoCoordinate(imageCoordinate, this));
772}
773#endif
774
775void Vehicle::_handleOrbitExecutionStatus(const mavlink_message_t& message)
776{
777 mavlink_orbit_execution_status_t orbitStatus;
778
779 mavlink_msg_orbit_execution_status_decode(&message, &orbitStatus);
780
781 double newRadius = qAbs(static_cast<double>(orbitStatus.radius));
782 if (!QGC::fuzzyCompare(_orbitMapCircle->radius()->rawValue().toDouble(), newRadius)) {
783 _orbitMapCircle->radius()->setRawValue(newRadius);
784 }
785
786 bool newOrbitClockwise = orbitStatus.radius > 0 ? true : false;
787 if (_orbitMapCircle->clockwiseRotation() != newOrbitClockwise) {
788 _orbitMapCircle->setClockwiseRotation(newOrbitClockwise);
789 }
790
791 QGeoCoordinate newCenter(static_cast<double>(orbitStatus.x) / qPow(10.0, 7.0), static_cast<double>(orbitStatus.y) / qPow(10.0, 7.0));
792 if (_orbitMapCircle->center() != newCenter) {
793 _orbitMapCircle->setCenter(newCenter);
794 }
795
796 if (!_orbitActive) {
797 _orbitActive = true;
798 _orbitMapCircle->setShowRotation(true);
799 emit orbitActiveChanged(true);
800 }
801
802 _orbitTelemetryTimer.start(_orbitTelemetryTimeoutMsecs);
803}
804
805void Vehicle::_orbitTelemetryTimeout()
806{
807 _orbitActive = false;
808 emit orbitActiveChanged(false);
809}
810
811void Vehicle::_handleCameraImageCaptured(const mavlink_message_t& message)
812{
813 mavlink_camera_image_captured_t feedback;
814
815 mavlink_msg_camera_image_captured_decode(&message, &feedback);
816
817 if (!_cameraImageCapturedMessageAvailable) {
818 _cameraImageCapturedMessageAvailable = true;
819 // Avoid initial duplicatation in case where first photo has CAMERA_FEEDBACK processed first.
820 if (_cameraTriggerPoints->count() > 0) {
821 return;
822 }
823 }
824
825 QGeoCoordinate imageCoordinate((double)feedback.lat / qPow(10.0, 7.0), (double)feedback.lon / qPow(10.0, 7.0), feedback.alt);
826 qCDebug(VehicleLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.image_index << feedback.capture_result;
827 if (feedback.capture_result == 1) {
828 _cameraTriggerPoints->append(new QGCQGeoCoordinate(imageCoordinate, this));
829 }
830}
831
832// TODO: VehicleFactGroup
833void Vehicle::_handleGpsRawInt(mavlink_message_t& message)
834{
835 if (message.compid != _defaultComponentId) {
836 return;
837 }
838
839 mavlink_gps_raw_int_t gpsRawInt;
840 mavlink_msg_gps_raw_int_decode(&message, &gpsRawInt);
841
842 _gpsRawIntMessageAvailable = true;
843
844 if (gpsRawInt.fix_type >= GPS_FIX_TYPE_3D_FIX) {
845 if (!_globalPositionIntMessageAvailable) {
846 QGeoCoordinate newPosition(gpsRawInt.lat / (double)1E7, gpsRawInt.lon / (double)1E7, gpsRawInt.alt / 1000.0);
847 if (newPosition != _coordinate) {
848 _coordinate = newPosition;
849 emit coordinateChanged(_coordinate);
850 }
852 _altitudeAMSLFact.setRawValue(gpsRawInt.alt / 1000.0);
853 }
854 }
855 }
856}
857
858// TODO: VehicleFactGroup
859void Vehicle::_handleGlobalPositionInt(mavlink_message_t& message)
860{
861 if (message.compid != _defaultComponentId) {
862 return;
863 }
864
865 mavlink_global_position_int_t globalPositionInt;
866 mavlink_msg_global_position_int_decode(&message, &globalPositionInt);
867
869 _altitudeRelativeFact.setRawValue(globalPositionInt.relative_alt / 1000.0);
870 _altitudeAMSLFact.setRawValue(globalPositionInt.alt / 1000.0);
871 }
872
873 // ArduPilot sends bogus GLOBAL_POSITION_INT messages with lat/lat 0/0 even when it has no gps signal
874 // Apparently, this is in order to transport relative altitude information.
875 if (globalPositionInt.lat == 0 && globalPositionInt.lon == 0) {
876 return;
877 }
878
879 _globalPositionIntMessageAvailable = true;
880 QGeoCoordinate newPosition(globalPositionInt.lat / (double)1E7, globalPositionInt.lon / (double)1E7, globalPositionInt.alt / 1000.0);
881 if (newPosition != _coordinate) {
882 _coordinate = newPosition;
883 emit coordinateChanged(_coordinate);
884 }
885}
886
887// TODO: VehicleFactGroup
888void Vehicle::_handleHighLatency(mavlink_message_t& message)
889{
890 mavlink_high_latency_t highLatency;
891 mavlink_msg_high_latency_decode(&message, &highLatency);
892
893 QString previousFlightMode;
894 if (_base_mode != 0 || _custom_mode != 0){
895 // Vehicle is initialized with _base_mode=0 and _custom_mode=0. Don't pass this to flightMode() since it will complain about
896 // bad modes while unit testing.
897 previousFlightMode = flightMode();
898 }
899 _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
900 _custom_mode = _firmwarePlugin->highLatencyCustomModeTo32Bits(highLatency.custom_mode);
901 if (previousFlightMode != flightMode()) {
903 }
904
905 // Assume armed since we don't know
906 if (_armed != true) {
907 _armed = true;
908 emit armedChanged(_armed);
909 }
910
911 struct {
912 const double latitude;
913 const double longitude;
914 const double altitude;
915 } coordinate {
916 highLatency.latitude / (double)1E7,
917 highLatency.longitude / (double)1E7,
918 static_cast<double>(highLatency.altitude_amsl)
919 };
920
921 _coordinate.setLatitude(coordinate.latitude);
922 _coordinate.setLongitude(coordinate.longitude);
923 _coordinate.setAltitude(coordinate.altitude);
924 emit coordinateChanged(_coordinate);
925
926 _airSpeedFact.setRawValue((double)highLatency.airspeed / 5.0);
927 _groundSpeedFact.setRawValue((double)highLatency.groundspeed / 5.0);
928 _climbRateFact.setRawValue((double)highLatency.climb_rate / 10.0);
929 _headingFact.setRawValue((double)highLatency.heading * 2.0);
932}
933
934// TODO: VehicleFactGroup
935void Vehicle::_handleHighLatency2(mavlink_message_t& message)
936{
937 mavlink_high_latency2_t highLatency2;
938 mavlink_msg_high_latency2_decode(&message, &highLatency2);
939
940 QString previousFlightMode;
941 if (_base_mode != 0 || _custom_mode != 0){
942 // Vehicle is initialized with _base_mode=0 and _custom_mode=0. Don't pass this to flightMode() since it will complain about
943 // bad modes while unit testing.
944 previousFlightMode = flightMode();
945 }
946 // ArduPilot has the basemode in the custom0 field of the high latency message.
947 if (highLatency2.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
948 _base_mode = (uint8_t)highLatency2.custom0;
949 } else {
950 _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
951 }
952 _custom_mode = _firmwarePlugin->highLatencyCustomModeTo32Bits(highLatency2.custom_mode);
953 if (previousFlightMode != flightMode()) {
955 }
956 // ArduPilot has the arming status (basemode) in the custom0 field of the high latency message.
957 if (highLatency2.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA) {
958 if ((uint8_t)highLatency2.custom0 & MAV_MODE_FLAG_SAFETY_ARMED && _armed != true) {
959 _armed = true;
960 emit armedChanged(_armed);
961 } else if (!((uint8_t)highLatency2.custom0 & MAV_MODE_FLAG_SAFETY_ARMED) && _armed != false) {
962 _armed = false;
963 emit armedChanged(_armed);
964 }
965 } else {
966 // Assume armed since we don't know
967 if (_armed != true) {
968 _armed = true;
969 emit armedChanged(_armed);
970 }
971 }
972
973 _coordinate.setLatitude(highLatency2.latitude / (double)1E7);
974 _coordinate.setLongitude(highLatency2.longitude / (double)1E7);
975 _coordinate.setAltitude(highLatency2.altitude);
976 emit coordinateChanged(_coordinate);
977
978 _airSpeedFact.setRawValue((double)highLatency2.airspeed / 5.0);
979 _groundSpeedFact.setRawValue((double)highLatency2.groundspeed / 5.0);
980 _climbRateFact.setRawValue((double)highLatency2.climb_rate / 10.0);
981 _headingFact.setRawValue((double)highLatency2.heading * 2.0);
983 _altitudeAMSLFact.setRawValue(highLatency2.altitude);
984
985 // Map from MAV_FAILURE bits to standard SYS_STATUS message handling
986 const uint32_t newOnboardControlSensorsEnabled = QGCMAVLink::highLatencyFailuresToMavSysStatus(highLatency2);
987 if (newOnboardControlSensorsEnabled != _onboardControlSensorsEnabled) {
988 _onboardControlSensorsEnabled = newOnboardControlSensorsEnabled;
989 _onboardControlSensorsPresent = newOnboardControlSensorsEnabled;
990 _onboardControlSensorsUnhealthy = 0;
991 }
992}
993
994void Vehicle::_setCapabilities(uint64_t capabilityBits)
995{
996 _capabilityBits = capabilityBits;
997 _capabilityBitsKnown = true;
998 emit capabilitiesKnownChanged(true);
999 emit capabilityBitsChanged(_capabilityBits);
1000
1001 QString supports("supports");
1002 QString doesNotSupport("does not support");
1003
1004 qCDebug(VehicleLog) << QString("Vehicle %1 Mavlink 2.0").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MAVLINK2 ? supports : doesNotSupport);
1005 qCDebug(VehicleLog) << QString("Vehicle %1 MISSION_ITEM_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_INT ? supports : doesNotSupport);
1006 qCDebug(VehicleLog) << QString("Vehicle %1 MISSION_COMMAND_INT").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_COMMAND_INT ? supports : doesNotSupport);
1007 qCDebug(VehicleLog) << QString("Vehicle %1 GeoFence").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_FENCE ? supports : doesNotSupport);
1008 qCDebug(VehicleLog) << QString("Vehicle %1 RallyPoints").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_MISSION_RALLY ? supports : doesNotSupport);
1009 qCDebug(VehicleLog) << QString("Vehicle %1 Terrain").arg(_capabilityBits & MAV_PROTOCOL_CAPABILITY_TERRAIN ? supports : doesNotSupport);
1010}
1011
1013{
1014 QString uid;
1015 uint8_t* pUid = (uint8_t*)(void*)&_uid;
1016 uid = uid.asprintf("%02X:%02X:%02X:%02X:%02X:%02X:%02X:%02X",
1017 pUid[0] & 0xff,
1018 pUid[1] & 0xff,
1019 pUid[2] & 0xff,
1020 pUid[3] & 0xff,
1021 pUid[4] & 0xff,
1022 pUid[5] & 0xff,
1023 pUid[6] & 0xff,
1024 pUid[7] & 0xff);
1025 return uid;
1026}
1027
1028void Vehicle::_handleExtendedSysState(mavlink_message_t& message)
1029{
1030 if (message.compid != _defaultComponentId) {
1031 return;
1032 }
1033
1034 mavlink_extended_sys_state_t extendedState;
1035 mavlink_msg_extended_sys_state_decode(&message, &extendedState);
1036
1037 switch (extendedState.landed_state) {
1038 case MAV_LANDED_STATE_ON_GROUND:
1039 _setFlying(false);
1040 _setLanding(false);
1041 break;
1042 case MAV_LANDED_STATE_TAKEOFF:
1043 case MAV_LANDED_STATE_IN_AIR:
1044 _setFlying(true);
1045 _setLanding(false);
1046 break;
1047 case MAV_LANDED_STATE_LANDING:
1048 _setFlying(true);
1049 _setLanding(true);
1050 break;
1051 default:
1052 break;
1053 }
1054
1055 if (vtol()) {
1056 bool vtolInFwdFlight = extendedState.vtol_state == MAV_VTOL_STATE_FW;
1057 if (vtolInFwdFlight != _vtolInFwdFlight) {
1058 _vtolInFwdFlight = vtolInFwdFlight;
1060 }
1061 }
1062}
1063
1064bool Vehicle::_apmArmingNotRequired()
1065{
1066 QString armingRequireParam("ARMING_REQUIRE");
1067 return _parameterManager->parameterExists(ParameterManager::defaultComponentId, armingRequireParam) &&
1068 _parameterManager->getParameter(ParameterManager::defaultComponentId, armingRequireParam)->rawValue().toInt() == 0;
1069}
1070
1071void Vehicle::_handleSysStatus(mavlink_message_t& message)
1072{
1073 if (message.compid != _defaultComponentId) {
1074 return;
1075 }
1076
1077 mavlink_sys_status_t sysStatus;
1078 mavlink_msg_sys_status_decode(&message, &sysStatus);
1079
1080 _sysStatusSensorInfo->update(sysStatus);
1081
1082 if (sysStatus.onboard_control_sensors_enabled & MAV_SYS_STATUS_PREARM_CHECK) {
1083 if (!_readyToFlyAvailable) {
1084 _readyToFlyAvailable = true;
1085 emit readyToFlyAvailableChanged(true);
1086 }
1087
1088 bool newReadyToFly = sysStatus.onboard_control_sensors_health & MAV_SYS_STATUS_PREARM_CHECK;
1089 if (newReadyToFly != _readyToFly) {
1090 _readyToFly = newReadyToFly;
1091 emit readyToFlyChanged(_readyToFly);
1092 }
1093 }
1094
1095 bool newAllSensorsHealthy = (sysStatus.onboard_control_sensors_enabled & sysStatus.onboard_control_sensors_health) == sysStatus.onboard_control_sensors_enabled;
1096 if (newAllSensorsHealthy != _allSensorsHealthy) {
1097 _allSensorsHealthy = newAllSensorsHealthy;
1098 emit allSensorsHealthyChanged(_allSensorsHealthy);
1099 }
1100
1101 if (_onboardControlSensorsPresent != sysStatus.onboard_control_sensors_present) {
1102 _onboardControlSensorsPresent = sysStatus.onboard_control_sensors_present;
1103 emit sensorsPresentBitsChanged(_onboardControlSensorsPresent);
1104 emit requiresGpsFixChanged();
1105 }
1106 if (_onboardControlSensorsEnabled != sysStatus.onboard_control_sensors_enabled) {
1107 _onboardControlSensorsEnabled = sysStatus.onboard_control_sensors_enabled;
1108 emit sensorsEnabledBitsChanged(_onboardControlSensorsEnabled);
1109 }
1110 if (_onboardControlSensorsHealth != sysStatus.onboard_control_sensors_health) {
1111 _onboardControlSensorsHealth = sysStatus.onboard_control_sensors_health;
1112 emit sensorsHealthBitsChanged(_onboardControlSensorsHealth);
1113 }
1114
1115 // ArduPilot firmare has a strange case when ARMING_REQUIRE=0. This means the vehicle is always armed but the motors are not
1116 // really powered up until the safety button is pressed. Because of this we can't depend on the heartbeat to tell us the true
1117 // armed (and dangerous) state. We must instead rely on SYS_STATUS telling us that the motors are enabled.
1118 if (apmFirmware() && _apmArmingNotRequired()) {
1119 _updateArmed(_onboardControlSensorsEnabled & MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS);
1120 }
1121
1122 uint32_t newSensorsUnhealthy = _onboardControlSensorsEnabled & ~_onboardControlSensorsHealth;
1123 if (newSensorsUnhealthy != _onboardControlSensorsUnhealthy) {
1124 _onboardControlSensorsUnhealthy = newSensorsUnhealthy;
1125 emit sensorsUnhealthyBitsChanged(_onboardControlSensorsUnhealthy);
1126 }
1127}
1128
1129void Vehicle::_handleBatteryStatus(mavlink_message_t& message)
1130{
1131 mavlink_battery_status_t batteryStatus;
1132 mavlink_msg_battery_status_decode(&message, &batteryStatus);
1133
1134 if (!_lowestBatteryChargeStateAnnouncedMap.contains(batteryStatus.id)) {
1135 _lowestBatteryChargeStateAnnouncedMap[batteryStatus.id] = batteryStatus.charge_state;
1136 }
1137
1138 QString batteryMessage;
1139
1140 switch (batteryStatus.charge_state) {
1141 case MAV_BATTERY_CHARGE_STATE_OK:
1142 _lowestBatteryChargeStateAnnouncedMap[batteryStatus.id] = batteryStatus.charge_state;
1143 break;
1144 case MAV_BATTERY_CHARGE_STATE_LOW:
1145 if (batteryStatus.charge_state > _lowestBatteryChargeStateAnnouncedMap[batteryStatus.id]) {
1146 _lowestBatteryChargeStateAnnouncedMap[batteryStatus.id] = batteryStatus.charge_state;
1147 batteryMessage = tr("battery %1 level low");
1148 }
1149 break;
1150 case MAV_BATTERY_CHARGE_STATE_CRITICAL:
1151 if (batteryStatus.charge_state > _lowestBatteryChargeStateAnnouncedMap[batteryStatus.id]) {
1152 _lowestBatteryChargeStateAnnouncedMap[batteryStatus.id] = batteryStatus.charge_state;
1153 batteryMessage = tr("battery %1 level is critical");
1154 }
1155 break;
1156 case MAV_BATTERY_CHARGE_STATE_EMERGENCY:
1157 if (batteryStatus.charge_state > _lowestBatteryChargeStateAnnouncedMap[batteryStatus.id]) {
1158 _lowestBatteryChargeStateAnnouncedMap[batteryStatus.id] = batteryStatus.charge_state;
1159 batteryMessage = tr("battery %1 level emergency");
1160 }
1161 break;
1162 case MAV_BATTERY_CHARGE_STATE_FAILED:
1163 if (batteryStatus.charge_state > _lowestBatteryChargeStateAnnouncedMap[batteryStatus.id]) {
1164 _lowestBatteryChargeStateAnnouncedMap[batteryStatus.id] = batteryStatus.charge_state;
1165 batteryMessage = tr("battery %1 failed");
1166 }
1167 break;
1168 case MAV_BATTERY_CHARGE_STATE_UNHEALTHY:
1169 if (batteryStatus.charge_state > _lowestBatteryChargeStateAnnouncedMap[batteryStatus.id]) {
1170 _lowestBatteryChargeStateAnnouncedMap[batteryStatus.id] = batteryStatus.charge_state;
1171 batteryMessage = tr("battery %1 unhealthy");
1172 }
1173 break;
1174 }
1175
1176 if (!batteryMessage.isEmpty()) {
1177 QString batteryIdStr("%1");
1178 if (_batteryFactGroupListModel->count() > 1) {
1179 batteryIdStr = batteryIdStr.arg(batteryStatus.id);
1180 } else {
1181 batteryIdStr = batteryIdStr.arg("");
1182 }
1183 _say(tr("warning"));
1184 _say(QStringLiteral("%1 %2 ").arg(_vehicleIdSpeech()).arg(batteryMessage.arg(batteryIdStr)));
1185 }
1186}
1187
1188void Vehicle::_setHomePosition(QGeoCoordinate& homeCoord)
1189{
1190 if (homeCoord != _homePosition) {
1191 _homePosition = homeCoord;
1192 qCDebug(VehicleLog) << "new home location set at coordinate: " << homeCoord;
1193 emit homePositionChanged(_homePosition);
1194 }
1195}
1196
1197void Vehicle::_handleHomePosition(mavlink_message_t& message)
1198{
1199 if (message.compid != _defaultComponentId) {
1200 return;
1201 }
1202
1203 mavlink_home_position_t homePos;
1204
1205 mavlink_msg_home_position_decode(&message, &homePos);
1206
1207 QGeoCoordinate newHomePosition (homePos.latitude / 10000000.0,
1208 homePos.longitude / 10000000.0,
1209 homePos.altitude / 1000.0);
1210 _setHomePosition(newHomePosition);
1211}
1212
1213void Vehicle::_updateArmed(bool armed)
1214{
1215 if (_armed != armed) {
1216 _armed = armed;
1217 emit armedChanged(_armed);
1218 // We are transitioning to the armed state, begin tracking trajectory points for the map
1219 if (_armed) {
1220 _trajectoryPoints->start();
1221 _flightTimerStart();
1222 _clearCameraTriggerPoints();
1223 // Reset battery warning
1225 } else {
1226 _trajectoryPoints->stop();
1227 _flightTimerStop();
1228 // Also handle Video Streaming
1229 if(SettingsManager::instance()->videoSettings()->disableWhenDisarmed()->rawValue().toBool()) {
1230 SettingsManager::instance()->videoSettings()->streamEnabled()->setRawValue(false);
1232 }
1233 }
1234 }
1235}
1236
1237void Vehicle::_handlePing(LinkInterface* link, mavlink_message_t& message)
1238{
1239 SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock();
1240 if (!sharedLink) {
1241 qCDebug(VehicleLog) << "_handlePing: primary link gone!";
1242 return;
1243 }
1244
1245 mavlink_ping_t ping;
1247
1248 mavlink_msg_ping_decode(&message, &ping);
1249
1250 if ((ping.target_system == 0) && (ping.target_component == 0)) {
1251 // Mavlink defines a ping request as a MSG_ID_PING which contains target_system = 0 and target_component = 0
1252 // So only send a ping response when you receive a valid ping request
1253 mavlink_msg_ping_pack_chan(static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
1254 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
1255 sharedLink->mavlinkChannel(),
1256 &msg,
1257 ping.time_usec,
1258 ping.seq,
1259 message.sysid,
1260 message.compid);
1261 sendMessageOnLinkThreadSafe(link, msg);
1262 }
1263}
1264
1265void Vehicle::setActuatorsMetadata([[maybe_unused]] uint8_t compid,
1266 const QString &metadataJsonFileName)
1267{
1268 if (!_actuators) {
1269 _actuators = new Actuators(this, this);
1270 }
1271 _actuators->load(metadataJsonFileName);
1272}
1273
1274void Vehicle::_handleHeartbeat(mavlink_message_t& message)
1275{
1276 if (message.compid != _defaultComponentId) {
1277 return;
1278 }
1279
1280 mavlink_heartbeat_t heartbeat;
1281
1282 mavlink_msg_heartbeat_decode(&message, &heartbeat);
1283
1284 bool newArmed = heartbeat.base_mode & MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
1285
1286 // ArduPilot firmare has a strange case when ARMING_REQUIRE=0. This means the vehicle is always armed but the motors are not
1287 // really powered up until the safety button is pressed. Because of this we can't depend on the heartbeat to tell us the true
1288 // armed (and dangerous) state. We must instead rely on SYS_STATUS telling us that the motors are enabled.
1289 if (apmFirmware()) {
1290 if (!_apmArmingNotRequired() || !(_onboardControlSensorsPresent & MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS)) {
1291 // If ARMING_REQUIRE!=0 or we haven't seen motor output status yet we use the hearbeat info for armed
1292 _updateArmed(newArmed);
1293 }
1294 } else {
1295 // Non-ArduPilot always updates from armed state in heartbeat
1296 _updateArmed(newArmed);
1297 }
1298
1299 if (heartbeat.base_mode != _base_mode || heartbeat.custom_mode != _custom_mode) {
1300 QString previousFlightMode;
1301 if (_base_mode != 0 || _custom_mode != 0){
1302 // Vehicle is initialized with _base_mode=0 and _custom_mode=0. Don't pass this to flightMode() since it will complain about
1303 // bad modes while unit testing.
1304 previousFlightMode = flightMode();
1305 }
1306 _base_mode = heartbeat.base_mode;
1307 _custom_mode = heartbeat.custom_mode;
1308 if (previousFlightMode != flightMode()) {
1310 }
1311 }
1312}
1313
1314void Vehicle::_handleCurrentMode(mavlink_message_t& message)
1315{
1316 if (message.compid != _defaultComponentId) {
1317 return;
1318 }
1319
1320 mavlink_current_mode_t currentMode;
1321 mavlink_msg_current_mode_decode(&message, &currentMode);
1322 if (currentMode.intended_custom_mode != 0) { // 0 == unknown/not supplied
1323 _has_custom_mode_user_intention = true;
1324 QString previousFlightMode = flightMode();
1325 bool changed = _custom_mode_user_intention != currentMode.intended_custom_mode;
1326 _custom_mode_user_intention = currentMode.intended_custom_mode;
1327 if (changed && previousFlightMode != flightMode()) {
1329 }
1330 }
1331}
1332
1333void Vehicle::_handleRCChannels(mavlink_message_t& message)
1334{
1335 mavlink_rc_channels_t channels;
1336
1337 mavlink_msg_rc_channels_decode(&message, &channels);
1338
1339 QVector<uint16_t> rawChannelValues({
1340 channels.chan1_raw,
1341 channels.chan2_raw,
1342 channels.chan3_raw,
1343 channels.chan4_raw,
1344 channels.chan5_raw,
1345 channels.chan6_raw,
1346 channels.chan7_raw,
1347 channels.chan8_raw,
1348 channels.chan9_raw,
1349 channels.chan10_raw,
1350 channels.chan11_raw,
1351 channels.chan12_raw,
1352 channels.chan13_raw,
1353 channels.chan14_raw,
1354 channels.chan15_raw,
1355 channels.chan16_raw,
1356 channels.chan17_raw,
1357 channels.chan18_raw,
1358 });
1359
1360 // The internals of radio calibration can ony deal with contiguous channels (other stuff as well!)
1361 int validChannelCount = 0;
1362 int firstUnusedChannelIndex = -1;
1363 for (int i=0; i<rawChannelValues.size(); i++) {
1364 if (rawChannelValues[i] != UINT16_MAX) {
1365 validChannelCount++;
1366 } else if (firstUnusedChannelIndex == -1) {
1367 firstUnusedChannelIndex = i;
1368 }
1369 }
1370 if (firstUnusedChannelIndex != -1 && firstUnusedChannelIndex != validChannelCount) {
1371 qCWarning(VehicleLog) << "Non-contiguous RC channels detected. Not publishing data from RC_CHANNELS.";
1372 return;
1373 }
1374
1375 QVector<int> channelValues(validChannelCount);
1376 QVector<int> clampedValues(validChannelCount);
1377 for (int channelIndex = 0; channelIndex < validChannelCount; ++channelIndex) {
1378 channelValues[channelIndex] = rawChannelValues[channelIndex];
1379 clampedValues[channelIndex] = std::clamp(channelValues[channelIndex], 1000, 2000);
1380 }
1381
1382 // rcRSSI is now a Fact on VehicleFactGroup (this); VehicleFactGroup owns the low-pass
1383 // filter and sentinel handling for the 0-100 / 255-unknown semantics.
1384 updateRCRSSI(channels.rssi);
1385 emit rcChannelsRawChanged(channelValues);
1386 emit rcChannelsClampedChanged(clampedValues);
1387}
1388
1390{
1391 if (!link->isConnected()) {
1392 qCDebug(VehicleLog) << "sendMessageOnLinkThreadSafe" << link << "not connected!";
1393 return false;
1394 }
1395
1396 // Give the plugin a chance to adjust
1397 _firmwarePlugin->adjustOutgoingMavlinkMessageThreadSafe(this, link, &message);
1398
1399 // Write message into buffer, prepending start sign
1400 uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
1401 int len = mavlink_msg_to_send_buffer(buffer, &message);
1402
1403 link->writeBytesThreadSafe((const char*)buffer, len);
1404 _messagesSent++;
1405 emit messagesSentChanged();
1406
1407 return true;
1408}
1409
1411{
1412 uint8_t frameType = 0;
1413 if (_vehicleType == MAV_TYPE_SUBMARINE) {
1414 frameType = parameterManager()->getParameter(_compID, "FRAME_CONFIG")->rawValue().toInt();
1415 }
1416 return QGCMAVLink::motorCount(_vehicleType, frameType);
1417}
1418
1420{
1421 return _firmwarePlugin->multiRotorCoaxialMotors(this);
1422}
1423
1425{
1426 return _firmwarePlugin->multiRotorXConfig(this);
1427}
1428
1429void Vehicle::_activeVehicleChanged(Vehicle *newActiveVehicle)
1430{
1431 _isActiveVehicle = newActiveVehicle == this;
1432}
1433
1435{
1436 return _homePosition;
1437}
1438
1439void Vehicle::setArmed(bool armed, bool showError)
1440{
1441 // We specifically use COMMAND_LONG:MAV_CMD_COMPONENT_ARM_DISARM since it is supported by more flight stacks.
1442 sendMavCommand(_defaultComponentId,
1443 MAV_CMD_COMPONENT_ARM_DISARM,
1444 showError,
1445 armed ? 1.0f : 0.0f);
1446}
1447
1449{
1450 sendMavCommand(_defaultComponentId,
1451 MAV_CMD_COMPONENT_ARM_DISARM,
1452 true, // show error if fails
1453 1.0f, // arm
1454 2989); // force arm
1455}
1456
1458{
1459 return _firmwarePlugin->isCapable(this, FirmwarePlugin::SetFlightModeCapability);
1460}
1461
1463{
1464 QStringList flightModes = _firmwarePlugin->flightModes(this);
1465 return flightModes;
1466}
1467
1468QString Vehicle::flightMode() const
1469{
1470 return _firmwarePlugin->flightMode(_base_mode, _custom_mode);
1471}
1472
1473bool Vehicle::setFlightModeCustom(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode)
1474{
1475 return _firmwarePlugin->setFlightMode(flightMode, base_mode, custom_mode);
1476}
1477
1478void Vehicle::setFlightMode(const QString& flightMode)
1479{
1480 uint8_t base_mode;
1481 uint32_t custom_mode;
1482
1483 if (setFlightModeCustom(flightMode, &base_mode, &custom_mode)) {
1484 SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock();
1485 if (!sharedLink) {
1486 qCDebug(VehicleLog) << "setFlightMode: primary link gone!";
1487 return;
1488 }
1489
1490 uint8_t newBaseMode = _base_mode & ~MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE;
1491
1492 // setFlightMode will only set MAV_MODE_FLAG_CUSTOM_MODE_ENABLED in base_mode, we need to move back in the existing
1493 // states.
1494 newBaseMode |= base_mode;
1495
1496 if (_firmwarePlugin->MAV_CMD_DO_SET_MODE_is_supported()) {
1498 MAV_CMD_DO_SET_MODE,
1499 true, // show error if fails
1500 MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
1501 custom_mode);
1502 } else {
1504 mavlink_msg_set_mode_pack_chan(MAVLinkProtocol::instance()->getSystemId(),
1506 sharedLink->mavlinkChannel(),
1507 &msg,
1508 id(),
1509 newBaseMode,
1510 custom_mode);
1511 sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
1512 }
1513 } else {
1514 qCWarning(VehicleLog) << "FirmwarePlugin::setFlightMode failed, flightMode:" << flightMode;
1515 }
1516}
1517
1518#if 0
1519QVariantList Vehicle::links() const {
1520 QVariantList ret;
1521
1522 for( const auto &item: _links )
1523 ret << QVariant::fromValue(item);
1524
1525 return ret;
1526}
1527#endif
1528
1529void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple)
1530{
1531 SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock();
1532 if (!sharedLink) {
1533 qCDebug(VehicleLog) << "requestDataStream: primary link gone!";
1534 return;
1535 }
1536
1538 mavlink_request_data_stream_t dataStream;
1539
1540 memset(&dataStream, 0, sizeof(dataStream));
1541
1542 dataStream.req_stream_id = stream;
1543 dataStream.req_message_rate = rate;
1544 dataStream.start_stop = 1; // start
1545 dataStream.target_system = id();
1546 dataStream.target_component = _defaultComponentId;
1547
1548 mavlink_msg_request_data_stream_encode_chan(MAVLinkProtocol::instance()->getSystemId(),
1550 sharedLink->mavlinkChannel(),
1551 &msg,
1552 &dataStream);
1553
1554 if (sendMultiple) {
1555 // We use sendMessageMultiple since we really want these to make it to the vehicle
1557 } else {
1558 sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
1559 }
1560}
1561
1562void Vehicle::_sendMessageMultipleNext()
1563{
1564 if (_nextSendMessageMultipleIndex < _sendMessageMultipleList.count()) {
1565 uint32_t msgId = _sendMessageMultipleList[_nextSendMessageMultipleIndex].message.msgid;
1566 const mavlink_message_info_t* info = mavlink_get_message_info_by_id(msgId);
1567 QString msgName = info ? info->name : QString::number(msgId);
1568 qCDebug(VehicleLog) << "_sendMessageMultipleNext:" << msgName;
1569
1570 SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock();
1571 if (sharedLink) {
1572 sendMessageOnLinkThreadSafe(sharedLink.get(), _sendMessageMultipleList[_nextSendMessageMultipleIndex].message);
1573 }
1574
1575 if (--_sendMessageMultipleList[_nextSendMessageMultipleIndex].retryCount <= 0) {
1576 _sendMessageMultipleList.removeAt(_nextSendMessageMultipleIndex);
1577 } else {
1578 _nextSendMessageMultipleIndex++;
1579 }
1580 }
1581
1582 if (_nextSendMessageMultipleIndex >= _sendMessageMultipleList.count()) {
1583 _nextSendMessageMultipleIndex = 0;
1584 }
1585}
1586
1588{
1589 SendMessageMultipleInfo_t info;
1590
1591 info.message = message;
1592 info.retryCount = _sendMessageMultipleRetries;
1593
1594 _sendMessageMultipleList.append(info);
1595}
1596
1597void Vehicle::_missionManagerError(int errorCode, const QString& errorMsg)
1598{
1599 Q_UNUSED(errorCode);
1600 QGC::showAppMessage(tr("Mission transfer failed. Error: %1").arg(errorMsg));
1601}
1602
1603void Vehicle::_geoFenceManagerError(int errorCode, const QString& errorMsg)
1604{
1605 Q_UNUSED(errorCode);
1606 QGC::showAppMessage(tr("GeoFence transfer failed. Error: %1").arg(errorMsg));
1607}
1608
1609void Vehicle::_rallyPointManagerError(int errorCode, const QString& errorMsg)
1610{
1611 Q_UNUSED(errorCode);
1612 QGC::showAppMessage(tr("Rally Point transfer failed. Error: %1").arg(errorMsg));
1613}
1614
1615void Vehicle::_clearCameraTriggerPoints()
1616{
1617 _cameraImageCapturedMessageAvailable = false;
1618 _cameraTriggerPoints->clearAndDeleteContents();
1619}
1620
1621void Vehicle::_flightTimerStart()
1622{
1623 _flightTimer.start();
1624 _flightTimeUpdater.start();
1627}
1628
1629void Vehicle::_flightTimerStop()
1630{
1631 _flightTimeUpdater.stop();
1632}
1633
1634void Vehicle::_updateFlightTime()
1635{
1636 _flightTimeFact.setRawValue((double)_flightTimer.elapsed() / 1000.0);
1637}
1638
1639void Vehicle::_gotProgressUpdate(float progressValue)
1640{
1642 return;
1643 }
1645 progressValue = 0.f;
1646 }
1647 _loadProgress = progressValue;
1648 emit loadProgressChanged(progressValue);
1649}
1650
1651void Vehicle::_firstMissionLoadComplete()
1652{
1653 disconnect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_firstMissionLoadComplete);
1654}
1655
1656void Vehicle::_firstGeoFenceLoadComplete()
1657{
1658 disconnect(_geoFenceManager, &GeoFenceManager::loadComplete, this, &Vehicle::_firstGeoFenceLoadComplete);
1659}
1660
1661void Vehicle::_firstRallyPointLoadComplete()
1662{
1663 disconnect(_rallyPointManager, &RallyPointManager::loadComplete, this, &Vehicle::_firstRallyPointLoadComplete);
1664 _initialPlanRequestComplete = true;
1666}
1667
1668void Vehicle::_parametersReady(bool parametersReady)
1669{
1670 qCDebug(VehicleLog) << "_parametersReady" << parametersReady;
1671
1672 // Try to set current unix time to the vehicle
1673 _sendQGCTimeToVehicle();
1674 // Send time twice, more likely to get to the vehicle on a noisy link
1675 _sendQGCTimeToVehicle();
1676 if (parametersReady) {
1677 disconnect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
1678 _setupAutoDisarmSignalling();
1679 }
1680
1683
1684 emit haveMRSpeedLimChanged();
1685 emit haveFWSpeedLimChanged();
1686}
1687
1688void Vehicle::_sendQGCTimeToVehicle()
1689{
1690 SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock();
1691 if (!sharedLink) {
1692 qCDebug(VehicleLog) << "_sendQGCTimeToVehicle: primary link gone!";
1693 return;
1694 }
1695
1697 mavlink_system_time_t cmd;
1698
1699 // Timestamp of the master clock in microseconds since UNIX epoch.
1700 cmd.time_unix_usec = QDateTime::currentDateTime().currentMSecsSinceEpoch()*1000;
1701 // Timestamp of the component clock since boot time in milliseconds (Not necessary).
1702 cmd.time_boot_ms = 0;
1703 mavlink_msg_system_time_encode_chan(MAVLinkProtocol::instance()->getSystemId(),
1705 sharedLink->mavlinkChannel(),
1706 &msg,
1707 &cmd);
1708
1709 sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
1710}
1711
1712void Vehicle::virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust)
1713{
1714 // The following if statement prevents the virtualTabletJoystick from sending values if the standard joystick is enabled
1715 bool isActiveVehicle = (MultiVehicleManager::instance()->activeVehicle() == this);
1716 bool joystickEnabled = isActiveVehicle && JoystickManager::instance()->activeJoystickEnabledForActiveVehicle();
1717 if (!joystickEnabled) {
1719 static_cast<float>(roll),
1720 static_cast<float>(pitch),
1721 static_cast<float>(yaw),
1722 static_cast<float>(thrust),
1723 0, 0, // buttons
1724 NAN, NAN, NAN, NAN, NAN, NAN, NAN, NAN); // extension values
1725 }
1726}
1727
1728void Vehicle::_say(const QString& text)
1729{
1730 AudioOutput::instance()->say(text.toLower());
1731}
1732
1734{
1736}
1737
1739{
1741}
1742
1743bool Vehicle::rover() const
1744{
1746}
1747
1748bool Vehicle::sub() const
1749{
1751}
1752
1754{
1756}
1757
1759{
1761}
1762
1763bool Vehicle::vtol() const
1764{
1766}
1767
1769{
1770 return QGCMAVLink::mavTypeToString(_vehicleType);
1771}
1772
1777
1779QString Vehicle::_vehicleIdSpeech()
1780{
1781 if (MultiVehicleManager::instance()->vehicles()->count() > 1) {
1782 return tr("Vehicle %1 ").arg(id());
1783 } else {
1784 return QString();
1785 }
1786}
1787
1788void Vehicle::_handleFlightModeChanged(const QString& flightMode)
1789{
1790 if (flightMode != _lastAnnouncedFlightMode) {
1791 _lastAnnouncedFlightMode = flightMode;
1792 _say(tr("%1 %2 flight mode").arg(_vehicleIdSpeech()).arg(flightMode));
1793 }
1794 emit guidedModeChanged(_firmwarePlugin->isGuidedMode(this));
1795}
1796
1797void Vehicle::_announceArmedChanged(bool armed)
1798{
1799 _say(QString("%1 %2").arg(_vehicleIdSpeech()).arg(armed ? tr("armed") : tr("disarmed")));
1800 if(armed) {
1801 //-- Keep track of armed coordinates
1802 _armedPosition = _coordinate;
1803 emit armedPositionChanged();
1804 }
1805}
1806
1807void Vehicle::_setFlying(bool flying)
1808{
1809 if (_flying != flying) {
1810 _flying = flying;
1811 emit flyingChanged(flying);
1812 }
1813}
1814
1815void Vehicle::_setLanding(bool landing)
1816{
1817 if (armed() && _landing != landing) {
1818 _landing = landing;
1819 emit landingChanged(landing);
1820 }
1821}
1822
1824{
1825 return _firmwarePlugin->gotoFlightMode();
1826}
1827
1828void Vehicle::guidedModeRTL(bool smartRTL)
1829{
1830 if (!_vehicleSupports->guidedMode()) {
1832 return;
1833 }
1834 _firmwarePlugin->guidedModeRTL(this, smartRTL);
1835}
1836
1838{
1839 if (!_vehicleSupports->guidedMode()) {
1841 return;
1842 }
1843 _firmwarePlugin->guidedModeLand(this);
1844}
1845
1846void Vehicle::guidedModeTakeoff(double altitudeRelative)
1847{
1848 if (!_vehicleSupports->guidedMode()) {
1850 return;
1851 }
1852 _firmwarePlugin->guidedModeTakeoff(this, altitudeRelative);
1853}
1854
1856{
1857 return _firmwarePlugin->minimumTakeoffAltitudeMeters(this);
1858}
1859
1864
1865
1867{
1868 return _firmwarePlugin->maximumEquivalentAirspeed(this);
1869}
1870
1871
1873{
1874 return _firmwarePlugin->minimumEquivalentAirspeed(this);
1875}
1876
1878{
1879 return _firmwarePlugin->hasGripper(this);
1880}
1881
1883{
1884 _firmwarePlugin->startTakeoff(this);
1885}
1886
1887
1889{
1890 _firmwarePlugin->startMission(this);
1891}
1892
1893bool Vehicle::guidedModeGotoLocation(const QGeoCoordinate& gotoCoord, double forwardFlightLoiterRadius)
1894{
1895 if (!_vehicleSupports->guidedMode()) {
1897 return false;
1898 }
1899 if (!coordinate().isValid()) {
1900 return false;
1901 }
1902 if (!gotoCoord.isValid()) {
1903 return false;
1904 }
1905 double maxDistance = SettingsManager::instance()->flyViewSettings()->maxGoToLocationDistance()->rawValue().toDouble();
1906 if (coordinate().distanceTo(gotoCoord) > maxDistance) {
1907 QGC::showAppMessage(QString("New location is too far. Must be less than %1 %2.").arg(qRound(FactMetaData::metersToAppSettingsHorizontalDistanceUnits(maxDistance).toDouble())).arg(FactMetaData::appSettingsHorizontalDistanceUnitsString()));
1908 return false;
1909 }
1910
1911 return _firmwarePlugin->guidedModeGotoLocation(this, gotoCoord, forwardFlightLoiterRadius);
1912}
1913
1914void Vehicle::guidedModeChangeAltitude(double altitudeChange, bool pauseVehicle)
1915{
1916 if (!_vehicleSupports->guidedMode()) {
1918 return;
1919 }
1920 _firmwarePlugin->guidedModeChangeAltitude(this, altitudeChange, pauseVehicle);
1921}
1922
1923void
1925{
1926 if (!_vehicleSupports->guidedMode()) {
1928 return;
1929 }
1930 _firmwarePlugin->guidedModeChangeGroundSpeedMetersSecond(this, groundspeed);
1931}
1932
1933void
1935{
1936 if (!_vehicleSupports->guidedMode()) {
1938 return;
1939 }
1940 _firmwarePlugin->guidedModeChangeEquivalentAirspeedMetersSecond(this, airspeed);
1941}
1942
1943void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude)
1944{
1945 if (!_vehicleSupports->orbitMode()) {
1946 QGC::showAppMessage(QStringLiteral("Orbit mode not supported by Vehicle."));
1947 return;
1948 }
1949 if (capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
1952 MAV_CMD_DO_ORBIT,
1953 MAV_FRAME_GLOBAL,
1954 true, // show error if fails
1955 static_cast<float>(radius),
1956 static_cast<float>(qQNaN()), // Use default velocity
1957 static_cast<float>(ORBIT_YAW_BEHAVIOUR_UNCHANGED), // Use current or vehicle default yaw behavior
1958 static_cast<float>(qQNaN()), // Use vehicle default num of orbits behavior
1959 centerCoord.latitude(), centerCoord.longitude(), static_cast<float>(amslAltitude));
1960 } else {
1963 MAV_CMD_DO_ORBIT,
1964 true, // show error if fails
1965 static_cast<float>(radius),
1966 static_cast<float>(qQNaN()), // Use default velocity
1967 static_cast<float>(ORBIT_YAW_BEHAVIOUR_UNCHANGED), // Use current or vehicle default yaw behavior
1968 static_cast<float>(qQNaN()), // Use vehicle default num of orbits behavior
1969 static_cast<float>(centerCoord.latitude()),
1970 static_cast<float>(centerCoord.longitude()),
1971 static_cast<float>(amslAltitude));
1972 }
1973}
1974
1975void Vehicle::guidedModeROI(const QGeoCoordinate& centerCoord)
1976{
1977 if (!centerCoord.isValid()) {
1978 return;
1979 }
1980 if (!_vehicleSupports->roiMode()) {
1981 QGC::showAppMessage(QStringLiteral("ROI mode not supported by Vehicle."));
1982 return;
1983 }
1984
1985 if (px4Firmware()) {
1986 // PX4 ignores the coordinate frame in COMMAND_INT and treats the altitude as AMSL,
1987 // so a terrain query is required before we can send the ROI command.
1989 } else {
1990 // ArduPilot handles MAV_FRAME_GLOBAL_RELATIVE_ALT correctly, so altitude 0 relative to
1991 // home is a reasonable default for a map click with no altitude info.
1992 // Sanity check Ardupilot. Max altitude processed is 83000
1993 if ((centerCoord.altitude() >= 83000) || (centerCoord.altitude() <= -83000)) {
1994 return;
1995 }
1996 _terrainQueryCoordinator->sendROICommand(centerCoord, MAV_FRAME_GLOBAL_RELATIVE_ALT, static_cast<float>(centerCoord.altitude()));
1997 }
1998
1999 // This is picked by qml to display coordinate over map
2000 emit roiCoordChanged(centerCoord);
2001}
2002
2004{
2005 if (!_vehicleSupports->roiMode()) {
2006 QGC::showAppMessage(QStringLiteral("ROI mode not supported by Vehicle."));
2007 return;
2008 }
2009 if (capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
2012 MAV_CMD_DO_SET_ROI_NONE,
2013 MAV_FRAME_GLOBAL,
2014 true, // show error if fails
2015 static_cast<float>(qQNaN()), // Empty
2016 static_cast<float>(qQNaN()), // Empty
2017 static_cast<float>(qQNaN()), // Empty
2018 static_cast<float>(qQNaN()), // Empty
2019 static_cast<double>(qQNaN()), // Empty
2020 static_cast<double>(qQNaN()), // Empty
2021 static_cast<float>(qQNaN())); // Empty
2022 } else {
2025 MAV_CMD_DO_SET_ROI_NONE,
2026 true, // show error if fails
2027 static_cast<float>(qQNaN()), // Empty
2028 static_cast<float>(qQNaN()), // Empty
2029 static_cast<float>(qQNaN()), // Empty
2030 static_cast<float>(qQNaN()), // Empty
2031 static_cast<float>(qQNaN()), // Empty
2032 static_cast<float>(qQNaN()), // Empty
2033 static_cast<float>(qQNaN())); // Empty
2034 }
2035}
2036
2037void Vehicle::guidedModeChangeHeading(const QGeoCoordinate &headingCoord)
2038{
2039 if (!_vehicleSupports->changeHeading()) {
2040 QGC::showAppMessage(tr("Change Heading not supported by Vehicle."));
2041 return;
2042 }
2043
2044 _firmwarePlugin->guidedModeChangeHeading(this, headingCoord);
2045}
2046
2048{
2049 if (!_vehicleSupports->pauseVehicle()) {
2050 QGC::showAppMessage(QStringLiteral("Pause not supported by vehicle."));
2051 return;
2052 }
2053 _firmwarePlugin->pauseVehicle(this);
2054}
2055
2056void Vehicle::abortLanding(double climbOutAltitude)
2057{
2060 MAV_CMD_DO_GO_AROUND,
2061 true, // show error if fails
2062 static_cast<float>(climbOutAltitude));
2063}
2064
2066{
2067 return _firmwarePlugin->isGuidedMode(this);
2068}
2069
2070void Vehicle::setGuidedMode(bool guidedMode)
2071{
2072 return _firmwarePlugin->setGuidedMode(this, guidedMode);
2073}
2074
2076{
2077 return fixedWing() || _vtolInFwdFlight;
2078}
2079
2080
2082{
2084 _defaultComponentId,
2085 MAV_CMD_COMPONENT_ARM_DISARM,
2086 true, // show error if fails
2087 0.0f,
2088 21196.0f); // Magic number for emergency stop
2089}
2090
2092{
2095 MAV_CMD_AIRFRAME_CONFIGURATION,
2096 true, // show error if fails
2097 -1.0f, // all gears
2098 0.0f); // down
2099}
2100
2102{
2105 MAV_CMD_AIRFRAME_CONFIGURATION,
2106 true, // show error if fails
2107 -1.0f, // all gears
2108 1.0f); // up
2109}
2110
2112{
2113 if (!_firmwarePlugin->sendHomePositionToVehicle()) {
2114 seq--;
2115 }
2116
2117 // send the mavlink command (created in Jan 2019)
2119 [this,seq]() { // lambda function which uses the deprecated mission_set_current
2120 SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock();
2121 if (!sharedLink) {
2122 qCDebug(VehicleLog) << "setCurrentMissionSequence: primary link gone!";
2123 return;
2124 }
2125
2127
2128 // send mavlink message (deprecated since Aug 2022).
2129 mavlink_msg_mission_set_current_pack_chan(
2130 static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
2131 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
2132 sharedLink->mavlinkChannel(),
2133 &msg,
2134 static_cast<uint8_t>(id()),
2135 _compID,
2136 static_cast<uint16_t>(seq));
2137 sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
2138 },
2139 static_cast<uint8_t>(defaultComponentId()),
2140 MAV_CMD_DO_SET_MISSION_CURRENT,
2141 true, // showError
2142 static_cast<uint16_t>(seq)
2143 );
2144}
2145
2146void Vehicle::sendMavCommand(int compId, MAV_CMD command, bool showError, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
2147{
2148 _mavCmdQueue->sendCommand(compId, command, showError, param1, param2, param3, param4, param5, param6, param7);
2149}
2150
2151void Vehicle::sendMavCommandDelayed(int compId, MAV_CMD command, bool showError, int milliseconds, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
2152{
2153 _mavCmdQueue->sendCommandDelayed(compId, command, showError, milliseconds, param1, param2, param3, param4, param5, param6, param7);
2154}
2155
2156void Vehicle::sendCommand(int compId, int command, bool showError, double param1, double param2, double param3, double param4, double param5, double param6, double param7)
2157{
2159 compId, static_cast<MAV_CMD>(command),
2160 showError,
2161 static_cast<float>(param1),
2162 static_cast<float>(param2),
2163 static_cast<float>(param3),
2164 static_cast<float>(param4),
2165 static_cast<float>(param5),
2166 static_cast<float>(param6),
2167 static_cast<float>(param7));
2168}
2169
2170void Vehicle::sendMavCommandWithHandler(const MavCmdAckHandlerInfo_t* ackHandlerInfo, int compId, MAV_CMD command, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
2171{
2172 _mavCmdQueue->sendCommandWithHandler(ackHandlerInfo, compId, command, param1, param2, param3, param4, param5, param6, param7);
2173}
2174
2175void Vehicle::sendMavCommandInt(int compId, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7)
2176{
2177 _mavCmdQueue->sendCommandInt(compId, command, frame, showError, param1, param2, param3, param4, param5, param6, param7);
2178}
2179
2180void Vehicle::sendMavCommandIntWithHandler(const MavCmdAckHandlerInfo_t* ackHandlerInfo, int compId, MAV_CMD command, MAV_FRAME frame, float param1, float param2, float param3, float param4, double param5, double param6, float param7)
2181{
2182 _mavCmdQueue->sendCommandIntWithHandler(ackHandlerInfo, compId, command, frame, param1, param2, param3, param4, param5, param6, param7);
2183}
2184
2185void Vehicle::sendMavCommandWithLambdaFallback(std::function<void()> lambda, int compId, MAV_CMD command, bool showError, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
2186{
2187 _mavCmdQueue->sendCommandWithLambdaFallback(std::move(lambda), compId, command, showError, param1, param2, param3, param4, param5, param6, param7);
2188}
2189
2190bool Vehicle::isMavCommandPending(int targetCompId, MAV_CMD command)
2191{
2192 return _mavCmdQueue->isPending(targetCompId, command);
2193}
2194
2195int Vehicle::_findMavCommandListEntryIndex(int targetCompId, MAV_CMD command)
2196{
2197 return _mavCmdQueue->findEntryIndex(targetCompId, command);
2198}
2199
2204
2205void Vehicle::_handleCommandAck(mavlink_message_t& message)
2206{
2208 mavlink_msg_command_ack_decode(&message, &ack);
2209
2210 QString rawCommandName = MissionCommandTree::instance()->rawName(static_cast<MAV_CMD>(ack.command));
2211 QString logMsg = QStringLiteral("_handleCommandAck command(%1) result(%2)").arg(rawCommandName).arg(QGCMAVLink::mavResultToString(static_cast<MAV_RESULT>(ack.result)));
2212
2213 // For REQUEST_MESSAGE commands, also log which message was requested.
2214 if (ack.command == MAV_CMD_REQUEST_MESSAGE) {
2215 const int entryIndex = _mavCmdQueue->findEntryIndex(message.compid, static_cast<MAV_CMD>(ack.command));
2216 if (entryIndex != -1) {
2217 // The message id was sent as param1 of MAV_CMD_REQUEST_MESSAGE. We can't read it back
2218 // from the queue without exposing entry internals, so just log the ack summary.
2219 logMsg += QStringLiteral(" (entry=%1)").arg(entryIndex);
2220 }
2221 }
2222
2223 qCDebug(VehicleLog) << logMsg;
2224
2225 // Vehicle-level side effects that must fire regardless of queue-match state.
2226 if (ack.command == MAV_CMD_DO_SET_ROI_LOCATION && ack.result == MAV_RESULT_ACCEPTED) {
2227 _isROIEnabled = true;
2228 emit isROIEnabledChanged();
2229 }
2230 if (ack.command == MAV_CMD_DO_SET_ROI_NONE && ack.result == MAV_RESULT_ACCEPTED) {
2231 _isROIEnabled = false;
2232 emit isROIEnabledChanged();
2233 }
2234 if (ack.command == MAV_CMD_PREFLIGHT_STORAGE) {
2235 emit sensorsParametersResetAck(ack.result == MAV_RESULT_ACCEPTED);
2236 }
2237#if !defined(QGC_NO_ARDUPILOT_DIALECT)
2238 if (ack.command == MAV_CMD_FLASH_BOOTLOADER && ack.result == MAV_RESULT_ACCEPTED) {
2239 QGC::showAppMessage(tr("Bootloader flash succeeded"));
2240 }
2241#endif
2242
2243 // Delegate queue-matching + user callbacks to MavCommandQueue.
2244 _mavCmdQueue->handleCommandAck(message, ack);
2245
2246 // Advance PID tuning setup/teardown.
2247 if (ack.command == MAV_CMD_SET_MESSAGE_INTERVAL) {
2248 _mavlinkStreamConfig->gotSetMessageIntervalAck();
2249 }
2250}
2251
2252void Vehicle::requestMessage(RequestMessageResultHandler resultHandler, void* resultHandlerData, int compId, int messageId, float param1, float param2, float param3, float param4, float param5)
2253{
2254 _reqMsgCoord->requestMessage(resultHandler, resultHandlerData, compId, messageId, param1, param2, param3, param4, param5);
2255}
2256
2257
2258void Vehicle::setPrearmError(const QString& prearmError)
2259{
2260 _prearmError = prearmError;
2261 emit prearmErrorChanged(_prearmError);
2262 if (!_prearmError.isEmpty()) {
2263 _prearmErrorTimer.start();
2264 }
2265}
2266
2267void Vehicle::_prearmErrorTimeout()
2268{
2269 setPrearmError(QString());
2270}
2271
2272void Vehicle::setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType)
2273{
2274 _firmwareMajorVersion = majorVersion;
2275 _firmwareMinorVersion = minorVersion;
2276 _firmwarePatchVersion = patchVersion;
2277 _firmwareVersionType = versionType;
2279}
2280
2281void Vehicle::setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion)
2282{
2283 _firmwareCustomMajorVersion = majorVersion;
2284 _firmwareCustomMinorVersion = minorVersion;
2285 _firmwareCustomPatchVersion = patchVersion;
2287}
2288
2290{
2291 return QGCMAVLink::firmwareVersionTypeToString(_firmwareVersionType);
2292}
2293
2294void Vehicle::_rebootCommandResultHandler(void* resultHandlerData, int /*compId*/, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode)
2295{
2296 Vehicle* vehicle = static_cast<Vehicle*>(resultHandlerData);
2297
2298 if (ack.result != MAV_RESULT_ACCEPTED) {
2299 switch (failureCode) {
2301 qCDebug(VehicleLog) << QStringLiteral("MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN error(%1)").arg(ack.result);
2302 break;
2304 qCDebug(VehicleLog) << "MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN failed: no response from vehicle";
2305 break;
2307 qCDebug(VehicleLog) << "MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN failed: duplicate command";
2308 break;
2309 }
2310 QGC::showAppMessage(tr("Vehicle reboot failed."));
2311 } else {
2312 vehicle->closeVehicle();
2313 }
2314}
2315
2317{
2318 Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {};
2319 handlerInfo.resultHandler = _rebootCommandResultHandler;
2320 handlerInfo.resultHandlerData = this;
2321
2322 sendMavCommandWithHandler(&handlerInfo, _defaultComponentId, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, 1);
2323}
2324
2326{
2327 SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock();
2328 if (!sharedLink) {
2329 qCDebug(VehicleLog) << "startCalibration: primary link gone!";
2330 return;
2331 }
2332
2333 float param1 = 0;
2334 float param2 = 0;
2335 float param3 = 0;
2336 float param4 = 0;
2337 float param5 = 0;
2338 float param6 = 0;
2339 float param7 = 0;
2340
2341 switch (calType) {
2343 param1 = 1;
2344 break;
2346 param2 = 1;
2347 break;
2349 param4 = 1;
2350 break;
2352 param4 = 2;
2353 break;
2355 param5 = 1;
2356 break;
2358 param5 = 2;
2359 break;
2361 param7 = 1;
2362 break;
2364 param6 = 1;
2365 break;
2367 param3 = 1;
2368 break;
2370 param6 = 1;
2371 break;
2373 param3 = 1;
2374 break;
2376 param3 = 1; // GroundPressure/Airspeed
2377 if (multiRotor() || rover()) {
2378 // Gyro cal for ArduCopter only
2379 param1 = 1;
2380 }
2381 break;
2383 param5 = 4;
2384 break;
2386 default:
2387 break;
2388 }
2389
2390 // We can't use sendMavCommand here since we have no idea how long it will be before the command returns a result. This in turn
2391 // causes the retry logic to break down.
2393 mavlink_msg_command_long_pack_chan(MAVLinkProtocol::instance()->getSystemId(),
2395 sharedLink->mavlinkChannel(),
2396 &msg,
2397 id(),
2398 defaultComponentId(), // target component
2399 MAV_CMD_PREFLIGHT_CALIBRATION, // command id
2400 0, // 0=first transmission of command
2401 param1, param2, param3, param4, param5, param6, param7);
2402 sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
2403}
2404
2405void Vehicle::stopCalibration(bool showError)
2406{
2407 sendMavCommand(defaultComponentId(), // target component
2408 MAV_CMD_PREFLIGHT_CALIBRATION, // command id
2409 showError,
2410 0, // gyro cal
2411 0, // mag cal
2412 0, // ground pressure
2413 0, // radio cal
2414 0, // accel cal
2415 0, // airspeed cal
2416 0); // unused
2417}
2418
2420{
2421 sendMavCommand(defaultComponentId(), // target component
2422 MAV_CMD_PREFLIGHT_UAVCAN, // command id
2423 true, // showError
2424 1); // start config
2425}
2426
2428{
2429 sendMavCommand(defaultComponentId(), // target component
2430 MAV_CMD_PREFLIGHT_UAVCAN, // command id
2431 true, // showError
2432 0); // stop config
2433}
2434
2435void Vehicle::setSoloFirmware(bool soloFirmware)
2436{
2437 if (soloFirmware != _soloFirmware) {
2438 _soloFirmware = soloFirmware;
2440 }
2441}
2442
2443void Vehicle::motorTest(int motor, int percent, int timeoutSecs, bool showError)
2444{
2445 sendMavCommand(_defaultComponentId, MAV_CMD_DO_MOTOR_TEST, showError, motor, MOTOR_TEST_THROTTLE_PERCENT, percent, timeoutSecs, 0, MOTOR_TEST_ORDER_BOARD);
2446}
2447
2449{
2450 if (_offlineEditingVehicle) {
2451 _defaultComponentId = defaultComponentId;
2452 } else {
2453 qCWarning(VehicleLog) << "Call to Vehicle::setOfflineEditingDefaultComponentId on vehicle which is not offline";
2454 }
2455}
2456
2457void Vehicle::setVtolInFwdFlight(bool vtolInFwdFlight)
2458{
2459 if (_vtolInFwdFlight != vtolInFwdFlight) {
2460 sendMavCommand(_defaultComponentId,
2461 MAV_CMD_DO_VTOL_TRANSITION,
2462 true, // show errors
2463 vtolInFwdFlight ? MAV_VTOL_STATE_FW : MAV_VTOL_STATE_MC, // transition state
2464 0, 0, 0, 0, 0, 0); // param 2-7 unused
2465 }
2466}
2467
2469{
2470 sendMavCommand(_defaultComponentId, MAV_CMD_LOGGING_START, false /* showError */);
2471}
2472
2474{
2475 sendMavCommand(_defaultComponentId, MAV_CMD_LOGGING_STOP, false /* showError */);
2476}
2477
2478void Vehicle::_ackMavlinkLogData(uint16_t sequence)
2479{
2480 SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock();
2481 if (!sharedLink) {
2482 qCDebug(VehicleLog) << "_ackMavlinkLogData: primary link gone!";
2483 return;
2484 }
2485
2487 mavlink_logging_ack_t ack;
2488
2489 memset(&ack, 0, sizeof(ack));
2490 ack.sequence = sequence;
2491 ack.target_component = _defaultComponentId;
2492 ack.target_system = id();
2493 mavlink_msg_logging_ack_encode_chan(
2494 MAVLinkProtocol::instance()->getSystemId(),
2496 sharedLink->mavlinkChannel(),
2497 &msg,
2498 &ack);
2499 sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
2500}
2501
2502void Vehicle::_handleMavlinkLoggingData(mavlink_message_t& message)
2503{
2504 mavlink_logging_data_t log;
2505 mavlink_msg_logging_data_decode(&message, &log);
2506 if (static_cast<size_t>(log.length) > sizeof(log.data)) {
2507 qWarning() << "Invalid length for LOGGING_DATA, discarding." << log.length;
2508 } else {
2509 emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence,
2510 log.first_message_offset, QByteArray((const char*)log.data, log.length), false);
2511 }
2512}
2513
2514void Vehicle::_handleMavlinkLoggingDataAcked(mavlink_message_t& message)
2515{
2516 mavlink_logging_data_acked_t log;
2517 mavlink_msg_logging_data_acked_decode(&message, &log);
2518 _ackMavlinkLogData(log.sequence);
2519 if (static_cast<size_t>(log.length) > sizeof(log.data)) {
2520 qWarning() << "Invalid length for LOGGING_DATA_ACKED, discarding." << log.length;
2521 } else {
2522 emit mavlinkLogData(this, log.target_system, log.target_component, log.sequence,
2523 log.first_message_offset, QByteArray((const char*)log.data, log.length), false);
2524 }
2525}
2526
2528{
2529 firmwarePluginInstanceData->setParent(this);
2530 _firmwarePluginInstanceData = firmwarePluginInstanceData;
2531}
2532
2534{
2535 return _firmwarePlugin->missionFlightMode();
2536}
2537
2539{
2540 return _firmwarePlugin->pauseFlightMode();
2541}
2542
2544{
2545 return _firmwarePlugin->rtlFlightMode();
2546}
2547
2549{
2550 return _firmwarePlugin->smartRTLFlightMode();
2551}
2552
2554{
2555 return _firmwarePlugin->landFlightMode();
2556}
2557
2559{
2560 return _firmwarePlugin->takeControlFlightMode();
2561}
2562
2564{
2565 return _firmwarePlugin->followFlightMode();
2566}
2567
2569{
2570 return _firmwarePlugin->motorDetectionFlightMode();
2571}
2572
2574{
2575 return _firmwarePlugin->stabilizedFlightMode();
2576}
2577
2579{
2580 if(_firmwarePlugin)
2581 return _firmwarePlugin->vehicleImageOpaque(this);
2582 else
2583 return QString();
2584}
2585
2587{
2588 if(_firmwarePlugin)
2589 return _firmwarePlugin->vehicleImageOutline(this);
2590 else
2591 return QString();
2592}
2593
2594const QVariantList& Vehicle::toolIndicators()
2595{
2596 if(_firmwarePlugin) {
2597 return _firmwarePlugin->toolIndicators(this);
2598 }
2599 static QVariantList emptyList;
2600 return emptyList;
2601}
2602
2603void Vehicle::_setupAutoDisarmSignalling()
2604{
2605 QString param = _firmwarePlugin->autoDisarmParameter(this);
2606
2607 if (!param.isEmpty() && _parameterManager->parameterExists(ParameterManager::defaultComponentId, param)) {
2608 Fact* fact = _parameterManager->getParameter(ParameterManager::defaultComponentId,param);
2609 connect(fact, &Fact::rawValueChanged, this, &Vehicle::autoDisarmChanged);
2610 emit autoDisarmChanged();
2611 }
2612}
2613
2615{
2616 QString param = _firmwarePlugin->autoDisarmParameter(this);
2617
2618 if (!param.isEmpty() && _parameterManager->parameterExists(ParameterManager::defaultComponentId, param)) {
2619 Fact* fact = _parameterManager->getParameter(ParameterManager::defaultComponentId,param);
2620 return fact->rawValue().toDouble() > 0;
2621 }
2622
2623 return false;
2624}
2625
2626void Vehicle::_updateDistanceHeadingHome()
2627{
2628 if (coordinate().isValid() && homePosition().isValid()) {
2630 if (_distanceToHomeFact.rawValue().toDouble() > 1.0) {
2633 } else {
2636 }
2637 } else {
2641 }
2642}
2643
2644void Vehicle::_updateHeadingToNextWP()
2645{
2646 const int currentIndex = _missionManager->currentIndex();
2647 QList<MissionItem*> llist = _missionManager->missionItems();
2648
2649 if(llist.size()>currentIndex && currentIndex!=-1
2650 && llist[currentIndex]->coordinate().longitude()!=0.0
2651 && coordinate().distanceTo(llist[currentIndex]->coordinate())>5.0 ){
2652
2653 _headingToNextWPFact.setRawValue(coordinate().azimuthTo(llist[currentIndex]->coordinate()));
2654 }
2655 else{
2657 }
2658}
2659
2660void Vehicle::_updateMissionItemIndex()
2661{
2662 const int currentIndex = _missionManager->currentIndex();
2663
2664 unsigned offset = 0;
2665 if (!_firmwarePlugin->sendHomePositionToVehicle()) {
2666 offset = 1;
2667 }
2668
2669 _missionItemIndexFact.setRawValue(currentIndex + offset);
2670}
2671
2672void Vehicle::_updateDistanceHeadingGCS()
2673{
2674 QGeoCoordinate gcsPosition = QGCPositionManager::instance()->gcsPosition();
2675 if (coordinate().isValid() && gcsPosition.isValid()) {
2676 _distanceToGCSFact.setRawValue(coordinate().distanceTo(gcsPosition));
2677 _headingFromGCSFact.setRawValue(gcsPosition.azimuthTo(coordinate()));
2678 } else {
2681 }
2682}
2683
2684void Vehicle::_updateHomepoint()
2685{
2686 const bool setHomeCmdSupported = firmwarePlugin()->supportedMissionCommands(vehicleClass()).contains(MAV_CMD_DO_SET_HOME);
2687 const bool updateHomeActivated = SettingsManager::instance()->flyViewSettings()->updateHomePosition()->rawValue().toBool();
2688 if(setHomeCmdSupported && updateHomeActivated){
2689 QGeoCoordinate gcsPosition = QGCPositionManager::instance()->gcsPosition();
2690 if (coordinate().isValid() && gcsPosition.isValid()) {
2692 MAV_CMD_DO_SET_HOME, false,
2693 0,
2694 0, 0, 0,
2695 static_cast<float>(gcsPosition.latitude()) ,
2696 static_cast<float>(gcsPosition.longitude()),
2697 static_cast<float>(gcsPosition.altitude()));
2698 }
2699 }
2700}
2701
2702void Vehicle::_updateHobbsMeter()
2703{
2705}
2706
2708{
2709 _initialPlanRequestComplete = true;
2711}
2712
2713void Vehicle::sendPlan(QString planFile)
2714{
2716}
2717
2719{
2720 return _firmwarePlugin->getHobbsMeter(this);
2721}
2722
2723void Vehicle::_vehicleParamLoaded(bool ready)
2724{
2725 //-- TODO: This seems silly but can you think of a better
2726 // way to update this?
2727 if(ready) {
2728 emit hobbsMeterChanged();
2729 }
2730}
2731
2732void Vehicle::_mavlinkMessageStatus(int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent)
2733{
2734 if(uasId == _systemID) {
2735 _mavlinkSentCount = totalSent;
2736 _mavlinkReceivedCount = totalReceived;
2737 _mavlinkLossCount = totalLoss;
2738 _mavlinkLossPercent = lossPercent;
2739 emit mavlinkStatusChanged();
2740 }
2741}
2742
2743int Vehicle::versionCompare(const QString& compare) const
2744{
2745 return _firmwarePlugin->versionCompare(this, compare);
2746}
2747
2748int Vehicle::versionCompare(int major, int minor, int patch) const
2749{
2750 return _firmwarePlugin->versionCompare(this, major, minor, patch);
2751}
2752
2754{
2755 bool liveUpdate = mode != ModeDisabled;
2756 setLiveUpdates(liveUpdate);
2760
2761 switch (mode) {
2762 case ModeDisabled:
2763 _mavlinkStreamConfig->restoreDefaults();
2764 break;
2766 _mavlinkStreamConfig->setHighRateRateAndAttitude();
2767 break;
2769 _mavlinkStreamConfig->setHighRateVelAndPos();
2770 break;
2772 _mavlinkStreamConfig->setHighRateAltAirspeed();
2773 // reset the altitude offset to the current value, so the plotted value is around 0
2774 if (!qIsNaN(_altitudeTuningOffset)) {
2778 }
2779 break;
2780 }
2781}
2782
2783void Vehicle::_setMessageInterval(int messageId, int rate)
2784{
2786 MAV_CMD_SET_MESSAGE_INTERVAL,
2787 true, // show error
2788 messageId,
2789 rate);
2790}
2791
2792QString Vehicle::_formatMavCommand(MAV_CMD command, float param1)
2793{
2794 QString commandName = MissionCommandTree::instance()->rawName(command);
2795
2796 if (command == MAV_CMD_REQUEST_MESSAGE && param1 > 0) {
2797 const mavlink_message_info_t* info = mavlink_get_message_info_by_id(static_cast<uint32_t>(param1));
2798 QString param1Str = info ? QString("%1(%2)").arg(param1).arg(info->name) : QString::number(param1);
2799 return QString("%1: %2").arg(commandName).arg(param1Str);
2800 }
2801 return QString("%1: %2").arg(commandName).arg(param1);
2802}
2803
2808
2809void Vehicle::_initializeCsv()
2810{
2811 if (!SettingsManager::instance()->mavlinkSettings()->saveCsvTelemetry()->rawValue().toBool()) {
2812 return;
2813 }
2814 QString now = QDateTime::currentDateTime().toString("yyyy-MM-dd hh-mm-ss");
2815 QString fileName = QString("%1 vehicle%2.csv").arg(now).arg(_systemID);
2816 QDir saveDir(SettingsManager::instance()->appSettings()->telemetrySavePath());
2817 _csvLogFile.setFileName(saveDir.absoluteFilePath(fileName));
2818
2819 if (!_csvLogFile.open(QIODevice::Append)) {
2820 qCWarning(VehicleLog) << "unable to open file for csv logging, Stopping csv logging!";
2821 return;
2822 }
2823
2824 QTextStream stream(&_csvLogFile);
2825 QStringList allFactNames;
2826 allFactNames << factNames();
2827 for (const QString& groupName: factGroupNames()) {
2828 for(const QString& factName: getFactGroup(groupName)->factNames()){
2829 allFactNames << QString("%1.%2").arg(groupName, factName);
2830 }
2831 }
2832 qCDebug(VehicleLog) << "Facts logged to csv:" << allFactNames;
2833 stream << "Timestamp," << allFactNames.join(",") << "\n";
2834}
2835
2836void Vehicle::_writeCsvLine()
2837{
2838 // Only save the logs after the the vehicle gets armed, unless "Save logs even if vehicle was not armed" is checked
2839 if(!_csvLogFile.isOpen() &&
2840 (_armed || SettingsManager::instance()->mavlinkSettings()->telemetrySaveNotArmed()->rawValue().toBool())){
2841 _initializeCsv();
2842 }
2843
2844 if(!_csvLogFile.isOpen()){
2845 return;
2846 }
2847
2848 QStringList allFactValues;
2849 QTextStream stream(&_csvLogFile);
2850
2851 // Write timestamp to csv file
2852 allFactValues << QDateTime::currentDateTime().toString(QStringLiteral("yyyy-MM-dd hh:mm:ss.zzz"));
2853 // Write Vehicle's own facts
2854 for (const QString& factName : factNames()) {
2855 allFactValues << getFact(factName)->cookedValueString();
2856 }
2857 // write facts from Vehicle's FactGroups
2858 for (const QString& groupName: factGroupNames()) {
2859 for (const QString& factName : getFactGroup(groupName)->factNames()) {
2860 allFactValues << getFactGroup(groupName)->getFact(factName)->cookedValueString();
2861 }
2862 }
2863
2864 stream << allFactValues.join(",") << "\n";
2865}
2866
2867void Vehicle::doSetHome(const QGeoCoordinate& coord)
2868{
2870}
2871
2872void Vehicle::_handleObstacleDistance(const mavlink_message_t& message)
2873{
2875 mavlink_msg_obstacle_distance_decode(&message, &o);
2876 _objectAvoidance->update(&o);
2877}
2878
2879void Vehicle::_handleFenceStatus(const mavlink_message_t& message)
2880{
2881 mavlink_fence_status_t fenceStatus;
2882
2883 mavlink_msg_fence_status_decode(&message, &fenceStatus);
2884
2885 qCDebug(VehicleLog) << "_handleFenceStatus breach_status" << fenceStatus.breach_status;
2886
2887 static qint64 lastUpdate = 0;
2888 qint64 now = QDateTime::currentMSecsSinceEpoch();
2889 if (fenceStatus.breach_status == 1) {
2890 if (now - lastUpdate > 3000) {
2891 lastUpdate = now;
2892 QString breachTypeStr;
2893 switch (fenceStatus.breach_type) {
2894 case FENCE_BREACH_NONE:
2895 return;
2896 case FENCE_BREACH_MINALT:
2897 breachTypeStr = tr("minimum altitude");
2898 break;
2899 case FENCE_BREACH_MAXALT:
2900 breachTypeStr = tr("maximum altitude");
2901 break;
2902 case FENCE_BREACH_BOUNDARY:
2903 breachTypeStr = tr("boundary");
2904 break;
2905 default:
2906 break;
2907 }
2908
2909 _say(breachTypeStr + " " + tr("fence breached"));
2910 }
2911 } else {
2912 lastUpdate = now;
2913 }
2914}
2915
2917{
2919}
2920
2921void Vehicle::sendParamMapRC(const QString& paramName, double scale, double centerValue, int tuningID, double minValue, double maxValue)
2922{
2923 SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock();
2924 if (!sharedLink) {
2925 qCDebug(VehicleLog) << "sendParamMapRC: primary link gone!";
2926 return;
2927 }
2928
2929 mavlink_message_t message;
2930
2931 char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};
2932 // Copy string into buffer, ensuring not to exceed the buffer size
2933 for (unsigned int i = 0; i < sizeof(param_id_cstr); i++) {
2934 if ((int)i < paramName.length()) {
2935 param_id_cstr[i] = paramName.toLatin1()[i];
2936 }
2937 }
2938
2939 mavlink_msg_param_map_rc_pack_chan(static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
2940 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
2941 sharedLink->mavlinkChannel(),
2942 &message,
2943 _systemID,
2944 MAV_COMP_ID_AUTOPILOT1,
2945 param_id_cstr,
2946 -1, // parameter name specified as string in previous argument
2947 static_cast<uint8_t>(tuningID),
2948 static_cast<float>(centerValue),
2949 static_cast<float>(scale),
2950 static_cast<float>(minValue),
2951 static_cast<float>(maxValue));
2952 sendMessageOnLinkThreadSafe(sharedLink.get(), message);
2953}
2954
2956{
2957 SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock();
2958 if (!sharedLink) {
2959 qCDebug(VehicleLog)<< "clearAllParamMapRC: primary link gone!";
2960 return;
2961 }
2962
2963 char param_id_cstr[MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN] = {};
2964
2965 for (int i = 0; i < 3; i++) {
2966 mavlink_message_t message;
2967 mavlink_msg_param_map_rc_pack_chan(static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
2968 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
2969 sharedLink->mavlinkChannel(),
2970 &message,
2971 _systemID,
2972 MAV_COMP_ID_AUTOPILOT1,
2973 param_id_cstr,
2974 -2, // Disable map for specified tuning id
2975 i, // tuning id
2976 0, 0, 0, 0); // unused
2977 sendMessageOnLinkThreadSafe(sharedLink.get(), message);
2978 }
2979}
2980
2981void Vehicle::sendJoystickDataThreadSafe(float roll, float pitch, float yaw, float thrust, quint16 buttons, quint16 buttons2, float pitchExtension, float rollExtension, float aux1, float aux2, float aux3, float aux4, float aux5, float aux6)
2982{
2983 SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock();
2984 if (!sharedLink) {
2985 qCDebug(VehicleLog)<< "sendJoystickDataThreadSafe: primary link gone!";
2986 return;
2987 }
2988
2989 if (sharedLink->linkConfiguration()->isHighLatency()) {
2990 return;
2991 }
2992
2993 mavlink_message_t message;
2994
2995 float axesScaling = 1.0 * 1000.0;
2996 uint8_t extensions = 0;
2997
2998 // Incoming values are in the range -1:1
2999 float newRollCommand = roll * axesScaling;
3000 float newPitchCommand = pitch * axesScaling;
3001 float newYawCommand = yaw * axesScaling;
3002 float newThrustCommand = thrust * axesScaling;
3003
3004 // Scale and set extension bits/values
3005 float incomingExtensionValues[] = { pitchExtension, rollExtension, aux1, aux2, aux3, aux4, aux5, aux6 };
3006 int16_t outgoingExtensionValues[std::size(incomingExtensionValues)];
3007 for (size_t i = 0; i < std::size(incomingExtensionValues); i++) {
3008 int16_t scaledValue = 0;
3009 if (!qIsNaN(incomingExtensionValues[i])) {
3010 scaledValue = static_cast<int16_t>(incomingExtensionValues[i] * axesScaling);
3011 extensions |= (1 << i);
3012 }
3013 outgoingExtensionValues[i] = scaledValue;
3014 }
3015 mavlink_msg_manual_control_pack_chan(
3016 static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
3017 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
3018 sharedLink->mavlinkChannel(),
3019 &message,
3020 static_cast<uint8_t>(_systemID),
3021 static_cast<int16_t>(newPitchCommand),
3022 static_cast<int16_t>(newRollCommand),
3023 static_cast<int16_t>(newThrustCommand),
3024 static_cast<int16_t>(newYawCommand),
3025 buttons, buttons2,
3026 extensions,
3027 outgoingExtensionValues[0],
3028 outgoingExtensionValues[1],
3029 outgoingExtensionValues[2],
3030 outgoingExtensionValues[3],
3031 outgoingExtensionValues[4],
3032 outgoingExtensionValues[5],
3033 outgoingExtensionValues[6],
3034 outgoingExtensionValues[7]
3035 );
3036 sendMessageOnLinkThreadSafe(sharedLink.get(), message);
3037}
3038
3039// Sends RC_CHANNELS_OVERRIDE for joystick aux axes mapped to RC channels 5–10 only.
3040// Channels 1–4 (attitude axes) always carry UINT16_MAX (ignore) and channels 11–18 are unused.
3041void Vehicle::sendJoystickAuxRcOverrideThreadSafe(const std::array<uint16_t, kAuxRcOverrideChannelCount> &channelValues, const std::array<bool, kAuxRcOverrideChannelCount> &channelEnabled, bool useRcOverride)
3042{
3043 SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock();
3044 if (!sharedLink) {
3045 qCDebug(VehicleLog) << "sendJoystickAuxRcOverrideThreadSafe: primary link gone!";
3046 return;
3047 }
3048
3049 if (sharedLink->linkConfiguration()->isHighLatency()) {
3050 return;
3051 }
3052
3053 bool anyEnabledChannel = false;
3054 for (bool enabled : channelEnabled) {
3055 if (enabled) {
3056 anyEnabledChannel = true;
3057 break;
3058 }
3059 }
3060
3061 if (!useRcOverride || !anyEnabledChannel) {
3062 // Atomically transition true → false so only one thread sends the release packet.
3063 bool expected = true;
3064 if (!_joystickAuxRcOverrideActive.compare_exchange_strong(expected, false)) {
3065 return;
3066 }
3067
3068 mavlink_message_t releaseMessage;
3069 mavlink_msg_rc_channels_override_pack_chan(
3070 static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
3071 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
3072 sharedLink->mavlinkChannel(),
3073 &releaseMessage,
3074 static_cast<uint8_t>(_systemID),
3075 static_cast<uint8_t>(_defaultComponentId),
3076 UINT16_MAX, // chan1: ignore (not overriding attitude axes)
3077 UINT16_MAX, // chan2: ignore
3078 UINT16_MAX, // chan3: ignore
3079 UINT16_MAX, // chan4: ignore
3080 0, // chan5: release (MAVLink standard: 0 = release override)
3081 0, // chan6: release
3082 0, // chan7: release
3083 0, // chan8: release
3084 static_cast<uint16_t>(UINT16_MAX - 1), // chan9: release (extension field: UINT16_MAX-1 = release)
3085 static_cast<uint16_t>(UINT16_MAX - 1), // chan10: release
3086 0, // chan11–18: not used
3087 0,
3088 0,
3089 0,
3090 0,
3091 0,
3092 0,
3093 0);
3094 sendMessageOnLinkThreadSafe(sharedLink.get(), releaseMessage);
3095 return;
3096 }
3097
3098 mavlink_message_t message;
3099 mavlink_msg_rc_channels_override_pack_chan(
3100 static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
3101 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
3102 sharedLink->mavlinkChannel(),
3103 &message,
3104 static_cast<uint8_t>(_systemID),
3105 static_cast<uint8_t>(_defaultComponentId),
3106 UINT16_MAX, // chan1: ignore (not overriding attitude axes)
3107 UINT16_MAX, // chan2: ignore
3108 UINT16_MAX, // chan3: ignore
3109 UINT16_MAX, // chan4: ignore
3110 channelEnabled[0] ? channelValues[0] : static_cast<uint16_t>(0), // chan5: value or release
3111 channelEnabled[1] ? channelValues[1] : static_cast<uint16_t>(0), // chan6: value or release
3112 channelEnabled[2] ? channelValues[2] : static_cast<uint16_t>(0), // chan7: value or release
3113 channelEnabled[3] ? channelValues[3] : static_cast<uint16_t>(0), // chan8: value or release
3114 channelEnabled[4] ? channelValues[4] : static_cast<uint16_t>(UINT16_MAX - 1), // chan9: value or release (extension field)
3115 channelEnabled[5] ? channelValues[5] : static_cast<uint16_t>(UINT16_MAX - 1), // chan10: value or release (extension field)
3116 0, // chan11–18: not used
3117 0,
3118 0,
3119 0,
3120 0,
3121 0,
3122 0,
3123 0);
3124 sendMessageOnLinkThreadSafe(sharedLink.get(), message);
3125 _joystickAuxRcOverrideActive = true;
3126}
3127
3129{
3130 sendMavCommand(_defaultComponentId,
3131 MAV_CMD_DO_DIGICAM_CONTROL,
3132 true, // show errors
3133 0.0, 0.0, 0.0, 0.0, // param 1-4 unused
3134 1.0); // trigger camera
3135}
3136
3137void Vehicle::sendGripperAction(GRIPPER_ACTIONS gripperAction)
3138{
3140 _defaultComponentId,
3141 MAV_CMD_DO_GRIPPER,
3142 true, // Show errors
3143 0, // Param1: Gripper ID (Always set to 0)
3144 gripperAction); // Param2: Gripper Action
3145}
3146
3147void Vehicle::setEstimatorOrigin(const QGeoCoordinate& centerCoord)
3148{
3149 SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock();
3150 if (!sharedLink) {
3151 qCDebug(VehicleLog) << "setEstimatorOrigin: primary link gone!";
3152 return;
3153 }
3154
3156 mavlink_msg_set_gps_global_origin_pack_chan(
3157 MAVLinkProtocol::instance()->getSystemId(),
3159 sharedLink->mavlinkChannel(),
3160 &msg,
3161 id(),
3162 centerCoord.latitude() * 1e7,
3163 centerCoord.longitude() * 1e7,
3164 centerCoord.altitude() * 1e3,
3165 static_cast<float>(qQNaN())
3166 );
3167 sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
3168}
3169
3170void Vehicle::pairRX(int rxType, int rxSubType)
3171{
3172 sendMavCommand(_defaultComponentId,
3173 MAV_CMD_START_RX_PAIR,
3174 true,
3175 rxType,
3176 rxSubType);
3177}
3178
3180{
3181 _timerRevertAllowTakeover.stop();
3182 _timerRevertAllowTakeover.setSingleShot(true);
3183 _timerRevertAllowTakeover.setInterval(operatorControlTakeoverTimeoutMsecs());
3184 // Disconnect any previous connections to avoid multiple handlers
3185 disconnect(&_timerRevertAllowTakeover, &QTimer::timeout, nullptr, nullptr);
3186
3187 connect(&_timerRevertAllowTakeover, &QTimer::timeout, this, [this](){
3188 if (MAVLinkProtocol::instance()->getSystemId() == _sysid_in_control) {
3189 this->requestOperatorControl(false);
3190 }
3191 });
3192 _timerRevertAllowTakeover.start();
3193}
3194
3195void Vehicle::requestOperatorControl(bool allowOverride, int requestTimeoutSecs)
3196{
3197 int safeRequestTimeoutSecs;
3198 int requestTimeoutSecsMin = SettingsManager::instance()->flyViewSettings()->requestControlTimeout()->cookedMin().toInt();
3199 int requestTimeoutSecsMax = SettingsManager::instance()->flyViewSettings()->requestControlTimeout()->cookedMax().toInt();
3200 if (requestTimeoutSecs >= requestTimeoutSecsMin && requestTimeoutSecs <= requestTimeoutSecsMax) {
3201 safeRequestTimeoutSecs = requestTimeoutSecs;
3202 } else {
3203 // If out of limits use default value
3204 safeRequestTimeoutSecs = SettingsManager::instance()->flyViewSettings()->requestControlTimeout()->cookedDefaultValue().toInt();
3205 }
3206
3207 const MavCmdAckHandlerInfo_t handlerInfo = {&Vehicle::_requestOperatorControlAckHandler, this, nullptr, nullptr};
3209 &handlerInfo,
3210 _defaultComponentId,
3211 MAV_CMD_REQUEST_OPERATOR_CONTROL,
3212 0, // System ID of GCS requesting control, 0 if it is this GCS
3213 1, // Action - 0: Release control, 1: Request control.
3214 allowOverride ? 1 : 0, // Allow takeover - Enable automatic granting of ownership on request. 0: Ask current owner and reject request, 1: Allow automatic takeover.
3215 safeRequestTimeoutSecs // Timeout in seconds before a request to a GCS to allow takeover is assumed to be rejected. This is used to display the timeout graphically on requestor and GCS in control.
3216 );
3217
3218 // If this is a request we sent to other GCS, start timer so User can not keep sending requests until the current timeout expires
3219 if (requestTimeoutSecs > 0) {
3220 requestOperatorControlStartTimer(requestTimeoutSecs * 1000);
3221 }
3222}
3223
3224void Vehicle::_requestOperatorControlAckHandler(void* resultHandlerData, int compId, const mavlink_command_ack_t& ack, MavCmdResultFailureCode_t failureCode)
3225{
3226 // For the moment, this will always come from an autopilot, compid 1
3227 Q_UNUSED(compId);
3228
3229 // If duplicated or no response, show popup to user. Otherwise only log it.
3230 switch (failureCode) {
3232 QGC::showAppMessage(tr("Waiting for previous operator control request"));
3233 return;
3235 QGC::showAppMessage(tr("No response to operator control request"));
3236 return;
3237 default:
3238 break;
3239 }
3240
3241 Vehicle* vehicle = static_cast<Vehicle*>(resultHandlerData);
3242 if (!vehicle) {
3243 return;
3244 }
3245
3246 if (ack.result == MAV_RESULT_ACCEPTED) {
3247 qCDebug(VehicleLog) << "Operator control request accepted";
3248 } else {
3249 qCDebug(VehicleLog) << "Operator control request rejected";
3250 }
3251}
3252
3253void Vehicle::requestOperatorControlStartTimer(int requestTimeoutMsecs)
3254{
3255 // First flag requests not allowed
3256 _sendControlRequestAllowed = false;
3258 // Setup timer to re enable it again after timeout
3259 _timerRequestOperatorControl.stop();
3260 _timerRequestOperatorControl.setSingleShot(true);
3261 _timerRequestOperatorControl.setInterval(requestTimeoutMsecs);
3262 // Disconnect any previous connections to avoid multiple handlers
3263 disconnect(&_timerRequestOperatorControl, &QTimer::timeout, nullptr, nullptr);
3264 connect(&_timerRequestOperatorControl, &QTimer::timeout, this, [this](){
3265 _sendControlRequestAllowed = true;
3267 });
3268 _timerRequestOperatorControl.start();
3269}
3270
3271void Vehicle::_handleControlStatus(const mavlink_message_t& message)
3272{
3273 mavlink_control_status_t controlStatus;
3274 mavlink_msg_control_status_decode(&message, &controlStatus);
3275
3276 bool updateControlStatusSignals = false;
3277 if (_gcsControlStatusFlags != controlStatus.flags) {
3278 _gcsControlStatusFlags = controlStatus.flags;
3279 _gcsControlStatusFlags_SystemManager = controlStatus.flags & GCS_CONTROL_STATUS_FLAGS_SYSTEM_MANAGER;
3280 _gcsControlStatusFlags_TakeoverAllowed = controlStatus.flags & GCS_CONTROL_STATUS_FLAGS_TAKEOVER_ALLOWED;
3281 updateControlStatusSignals = true;
3282 }
3283
3284 if (_sysid_in_control != controlStatus.sysid_in_control) {
3285 _sysid_in_control = controlStatus.sysid_in_control;
3286 updateControlStatusSignals = true;
3287 }
3288
3289 if (!_firstControlStatusReceived) {
3290 _firstControlStatusReceived = true;
3291 updateControlStatusSignals = true;
3292 }
3293
3294 if (updateControlStatusSignals) {
3296 }
3297
3298 // If we were waiting for a request to be accepted and now it was accepted, adjust flags accordingly so
3299 // UI unlocks the request/take control button
3300 if (!sendControlRequestAllowed() && _gcsControlStatusFlags_TakeoverAllowed) {
3301 disconnect(&_timerRequestOperatorControl, &QTimer::timeout, nullptr, nullptr);
3302 _sendControlRequestAllowed = true;
3304 }
3305}
3306
3307void Vehicle::_handleCommandRequestOperatorControl(const mavlink_command_long_t commandLong)
3308{
3309 emit requestOperatorControlReceived(commandLong.param1, commandLong.param3, commandLong.param4);
3310}
3311
3312void Vehicle::_handleCommandLong(const mavlink_message_t& message)
3313{
3314 mavlink_command_long_t commandLong;
3315 mavlink_msg_command_long_decode(&message, &commandLong);
3316 // Ignore command if it is not targeted for us
3317 if (commandLong.target_system != MAVLinkProtocol::instance()->getSystemId()) {
3318 return;
3319 }
3320 if (commandLong.command == MAV_CMD_REQUEST_OPERATOR_CONTROL) {
3321 _handleCommandRequestOperatorControl(commandLong);
3322 }
3323}
3324
3325int Vehicle::operatorControlTakeoverTimeoutMsecs() const
3326{
3328}
3329
3330int32_t Vehicle::getMessageRate(uint8_t compId, uint16_t msgId)
3331{
3332 return _messageIntervalManager->getMessageRate(compId, msgId);
3333}
3334
3335void Vehicle::setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate)
3336{
3337 _messageIntervalManager->setMessageRate(compId, msgId, rate);
3338}
3339
3340QVariant Vehicle::expandedToolbarIndicatorSource(const QString& indicatorName)
3341{
3342 return _firmwarePlugin->expandedToolbarIndicatorSource(this, indicatorName);
3343}
3344
3349
3354
3355/*===========================================================================*/
3356/* ardupilotmega Dialect */
3357/*===========================================================================*/
3358
3360{
3361 if (apmFirmware()) {
3364 MAV_CMD_FLASH_BOOTLOADER,
3365 true, // show error
3366 0, 0, 0, 0, // param 1-4 not used
3367 290876); // magic number
3368 }
3369}
3370
3372{
3373 if (apmFirmware()) {
3376 MAV_CMD_DO_AUX_FUNCTION,
3377 true,
3379 enable ? MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL_HIGH : MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL_LOW);
3380 }
3381}
3382
3383/*---------------------------------------------------------------------------*/
3384/*===========================================================================*/
3385/* Status Text Handler */
3386/*===========================================================================*/
3387
3388void Vehicle::resetAllMessages() { m_statusTextHandler->resetAllMessages(); }
3390void Vehicle::clearMessages() { m_statusTextHandler->clearMessages(); }
3391bool Vehicle::messageTypeNone() const { return m_statusTextHandler->messageTypeNone(); }
3392bool Vehicle::messageTypeNormal() const { return m_statusTextHandler->messageTypeNormal(); }
3393bool Vehicle::messageTypeWarning() const { return m_statusTextHandler->messageTypeWarning(); }
3394bool Vehicle::messageTypeError() const { return m_statusTextHandler->messageTypeError(); }
3395int Vehicle::messageCount() const { return m_statusTextHandler->messageCount(); }
3396QString Vehicle::formattedMessages() const { return m_statusTextHandler->formattedMessages(); }
3397
3398void Vehicle::_createStatusTextHandler()
3399{
3400 m_statusTextHandler = new StatusTextHandler(this);
3401 (void) connect(m_statusTextHandler, &StatusTextHandler::messageTypeChanged, this, &Vehicle::messageTypeChanged);
3402 (void) connect(m_statusTextHandler, &StatusTextHandler::messageCountChanged, this, &Vehicle::messageCountChanged);
3403 (void) connect(m_statusTextHandler, &StatusTextHandler::newFormattedMessage, this, &Vehicle::newFormattedMessage);
3404 (void) connect(m_statusTextHandler, &StatusTextHandler::textMessageReceived, this, &Vehicle::_textMessageReceived);
3405 (void) connect(m_statusTextHandler, &StatusTextHandler::newErrorMessage, this, &Vehicle::_errorMessageReceived);
3406}
3407
3408void Vehicle::_onStatusTextFromEvent(uint8_t compid, int severity, const QString &text, const QString &description)
3409{
3410 m_statusTextHandler->handleHTMLEscapedTextMessage(static_cast<MAV_COMPONENT>(compid),
3411 static_cast<MAV_SEVERITY>(severity), text, description);
3412}
3413
3414void Vehicle::_textMessageReceived(MAV_COMPONENT componentid, MAV_SEVERITY severity, QString text, QString description)
3415{
3416 // PX4 backwards compatibility: messages sent out ending with a tab are also sent as event
3417 if (px4Firmware() && text.endsWith('\t')) {
3418 qCDebug(VehicleLog) << "Dropping message (expected as event):" << text;
3419 return;
3420 }
3421
3422 bool skipSpoken = false;
3423 const bool ardupilotPrearm = text.startsWith(QStringLiteral("PreArm"));
3424 const bool px4Prearm = text.startsWith(QStringLiteral("preflight"), Qt::CaseInsensitive) && (severity >= MAV_SEVERITY::MAV_SEVERITY_CRITICAL);
3425 if (ardupilotPrearm || px4Prearm) {
3426 if (_healthAndArmingChecksSupported(componentid)) {
3427 qCDebug(VehicleLog) << "Dropping preflight message (expected as event):" << text;
3428 return;
3429 }
3430
3431 // Limit repeated PreArm message to once every 10 seconds
3432 if (_noisySpokenPrearmMap.contains(text) && _noisySpokenPrearmMap.value(text).msecsTo(QTime::currentTime()) < (10 * 1000)) {
3433 skipSpoken = true;
3434 } else {
3435 (void) _noisySpokenPrearmMap.insert(text, QTime::currentTime());
3436 setPrearmError(text);
3437 }
3438 }
3439
3440 bool readAloud = false;
3441
3442 if (text.startsWith("#")) {
3443 (void) text.remove(0, 1);
3444 readAloud = true;
3445 } else if (severity <= MAV_SEVERITY::MAV_SEVERITY_NOTICE) {
3446 readAloud = true;
3447 }
3448
3449 if (readAloud && !skipSpoken) {
3450 _say(text);
3451 }
3452
3453 emit textMessageReceived(id(), componentid, severity, text, description);
3454 m_statusTextHandler->handleHTMLEscapedTextMessage(componentid, severity, text.toHtmlEscaped(), description);
3455}
3456
3457void Vehicle::_errorMessageReceived(QString message)
3458{
3459 QString vehicleIdPrefix;
3460
3461 if (MultiVehicleManager::instance()->vehicles()->count() > 1) {
3462 vehicleIdPrefix = tr("Vehicle %1: ").arg(id());
3463 }
3464 QGC::showCriticalVehicleMessage(vehicleIdPrefix + message);
3465}
3466
3467/*---------------------------------------------------------------------------*/
3468/*===========================================================================*/
3469/* Signing */
3470/*===========================================================================*/
3471
3472void Vehicle::_createSigningController()
3473{
3474 _signingController = new VehicleSigningController(this);
3475}
3476
3477/*---------------------------------------------------------------------------*/
3478/*===========================================================================*/
3479/* Image Protocol Manager */
3480/*===========================================================================*/
3481
3482void Vehicle::_createImageProtocolManager()
3483{
3484 _imageProtocolManager = new ImageProtocolManager(this);
3485 (void) connect(_imageProtocolManager, &ImageProtocolManager::flowImageIndexChanged, this, &Vehicle::flowImageIndexChanged);
3486 (void) connect(_imageProtocolManager, &ImageProtocolManager::imageReady, this, [this](const QImage &image) {
3487 qgcApp()->qgcImageProvider()->setImage(image, _systemID);
3488 });
3489}
3490
3492{
3493 return (_imageProtocolManager ? _imageProtocolManager->flowImageIndex() : 0);
3494}
3495
3496/*---------------------------------------------------------------------------*/
3497/*===========================================================================*/
3498/* MAVLink Log Manager */
3499/*===========================================================================*/
3500
3501void Vehicle::_createMAVLinkLogManager()
3502{
3503 _mavlinkLogManager = new MAVLinkLogManager(this, this);
3504}
3505
3507{
3508 return _mavlinkLogManager;
3509}
3510
3511/*---------------------------------------------------------------------------*/
3512/*===========================================================================*/
3513/* Camera Manager */
3514/*===========================================================================*/
3515
3516void Vehicle::_createCameraManager()
3517{
3518 if (!_cameraManager && _firmwarePlugin) {
3519 _cameraManager = _firmwarePlugin->createCameraManager(this);
3520 emit cameraManagerChanged();
3521 }
3522}
3523
3524const QVariantList &Vehicle::staticCameraList() const
3525{
3526 if (_cameraManager) {
3527 return _cameraManager->cameraList();
3528 }
3529
3530 static QVariantList emptyCameraList;
3531 return emptyCameraList;
3532}
3533
3534/*---------------------------------------------------------------------------*/
3535/*===========================================================================*/
3536/* MAVLinkEventsManager */
3537/*===========================================================================*/
3538
3539void Vehicle::_createMAVLinkEventManager()
3540{
3541 _eventManager = std::make_unique<MAVLinkEventManager>(this);
3542
3543 (void) connect(_eventManager.get(), &MAVLinkEventManager::statusTextMessageFromEvent, this, &Vehicle::_onStatusTextFromEvent);
3544}
3545
3546void Vehicle::_handleEventMessage(const mavlink_message_t& msg)
3547{
3548 _eventManager->handleEventMessage(msg);
3549}
3550
3551bool Vehicle::_healthAndArmingChecksSupported(uint8_t compid)
3552{
3553 return _eventManager->healthAndArmingChecksSupported(compid);
3554}
3555
3557{
3558 return _eventManager->healthAndArmingCheckReport();
3559}
3560
3561void Vehicle::setEventsMetadata(uint8_t compid, const QString &metadataJsonFileName)
3562{
3563 _eventManager->setMetadata(compid, metadataJsonFileName);
3564
3565 sendMavCommand(_defaultComponentId, MAV_CMD_RUN_PREARM_CHECKS, false);
3566}
3567
3568/*---------------------------------------------------------------------------*/
static const QString guided_mode_not_supported_by_vehicle
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
#define qgcApp()
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
struct __mavlink_command_ack_t mavlink_command_ack_t
struct __mavlink_high_latency2_t mavlink_high_latency2_t
struct __mavlink_command_long_t mavlink_command_long_t
struct __mavlink_obstacle_distance_t mavlink_obstacle_distance_t
#define REQUEST_OPERATOR_CONTROL_ALLOW_TAKEOVER_TIMEOUT_MSECS
Definition Vehicle.cc:96
const QString guided_mode_not_supported_by_vehicle
Definition Vehicle.cc:98
void mavlinkMessageReceived(const mavlink_message_t &message)
static ADSBVehicleManager * instance()
void load(const QString &json_file)
Definition Actuators.cc:114
void say(const QString &text, TextMods textMods=TextMod::None)
static AudioOutput * instance()
void handleMessageForFactGroupCreation(Vehicle *vehicle, const mavlink_message_t &message)
Allows for creation/updating of dynamic FactGroups based on incoming messages.
Used to group Facts together into an object hierarachy.
Definition FactGroup.h:16
const QMap< QString, FactGroup * > & factGroups() const
Definition FactGroup.h:46
Q_INVOKABLE Fact * getFact(const QString &name) const
Definition FactGroup.cc:72
QStringList factNames() const
Definition FactGroup.h:43
void _addFactGroup(FactGroup *factGroup, const QString &name)
Definition FactGroup.cc:133
Q_INVOKABLE FactGroup * getFactGroup(const QString &name) const
Definition FactGroup.cc:102
QStringList factGroupNames() const
Definition FactGroup.h:44
Q_INVOKABLE void setLiveUpdates(bool liveUpdates)
Turning on live updates will allow value changes to flow through as they are received.
Definition FactGroup.cc:152
static QVariant metersToAppSettingsHorizontalDistanceUnits(const QVariant &meters)
Converts from meters to the user specified horizontal distance unit.
static QString appSettingsHorizontalDistanceUnitsString()
Returns the string for horizontal distance units which has configued by user.
A Fact is used to hold a single value within the system.
Definition Fact.h:17
FactMetaData * metaData()
Definition Fact.h:171
void rawValueChanged(const QVariant &value)
void setRawValue(const QVariant &value)
Definition Fact.cc:128
QString cookedValueString() const
Definition Fact.cc:438
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
FirmwarePlugin * firmwarePluginForAutopilot(MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType)
static FirmwarePluginManager * instance()
virtual QString motorDetectionFlightMode() const
Returns the flight mode for Motor Detection.
virtual QString pauseFlightMode() const
Returns The flight mode which indicates the vehicle is paused.
virtual void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle *vehicle, double airspeed_equiv) const
virtual void guidedModeChangeAltitude(Vehicle *vehicle, double altitudeChange, bool pauseVehicle)
virtual void startMission(Vehicle *vehicle) const
Command the vehicle to start the mission.
virtual bool multiRotorCoaxialMotors(Vehicle *) const
virtual double minimumEquivalentAirspeed(Vehicle *) const
virtual const QVariantList & toolIndicators(const Vehicle *vehicle)
virtual void guidedModeChangeGroundSpeedMetersSecond(Vehicle *vehicle, double groundspeed) const
virtual bool setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const
@ SetFlightModeCapability
FirmwarePlugin::setFlightMode method is supported.
virtual QString vehicleImageOutline(const Vehicle *) const
Return the resource file which contains the vehicle icon used in the flight view when the view is lig...
virtual void guidedModeTakeoff(Vehicle *vehicle, double takeoffAltRel) const
Command vehicle to takeoff from current location to the specified height.
virtual bool isCapable(const Vehicle *, FirmwareCapabilities) const
virtual double maximumEquivalentAirspeed(Vehicle *) const
virtual QString missionFlightMode() const
Returns the flight mode for running missions.
virtual void adjustMetaData(MAV_TYPE, FactMetaData *)
virtual bool adjustIncomingMavlinkMessage(Vehicle *, mavlink_message_t *)
virtual bool fixedWingAirSpeedLimitsAvailable(Vehicle *) const
virtual void guidedModeChangeHeading(Vehicle *vehicle, const QGeoCoordinate &headingCoord) const
Command vehicle to rotate towards specified location.
virtual QString smartRTLFlightMode() const
Returns the flight mode for Smart RTL.
virtual bool guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius=0.0) const
virtual bool multiRotorXConfig(Vehicle *) const
virtual QString takeControlFlightMode() const
Returns the flight mode to use when the operator wants to take back control from autonomouse flight.
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode) const
virtual QString vehicleImageOpaque(const Vehicle *) const
Return the resource file which contains the vehicle icon used in the flight view when the view is dar...
virtual void startTakeoff(Vehicle *vehicle) const
Command the vehicle to start a takeoff.
virtual void pauseVehicle(Vehicle *vehicle) const
virtual QVariant expandedToolbarIndicatorSource(const Vehicle *, const QString &) const
virtual bool mulirotorSpeedLimitsAvailable(Vehicle *) const
int versionCompare(const Vehicle *vehicle, const QString &compare) const
virtual bool hasGripper(const Vehicle *) const
virtual QString landFlightMode() const
Returns the flight mode for Land.
virtual QString gotoFlightMode() const
Returns the flight mode which the vehicle will be in if it is performing a goto location.
virtual Autotune * createAutotune(Vehicle *vehicle) const
Creates Autotune object.
virtual QStringList flightModes(Vehicle *) const
virtual AutoPilotPlugin * autopilotPlugin(Vehicle *vehicle) const
virtual void guidedModeRTL(Vehicle *vehicle, bool smartRTL) const
Command vehicle to return to launch.
virtual QList< MAV_CMD > supportedMissionCommands(QGCMAVLinkTypes::VehicleClass_t) const
List of supported mission commands. Empty list for all commands supported.
virtual QString autoDisarmParameter(Vehicle *) const
virtual QString stabilizedFlightMode() const
Returns the flight mode for Stabilized.
virtual void adjustOutgoingMavlinkMessageThreadSafe(Vehicle *, LinkInterface *, mavlink_message_t *)
void toolIndicatorsChanged()
virtual void setGuidedMode(Vehicle *vehicle, bool guidedMode) const
Set guided flight mode.
virtual QString followFlightMode() const
Returns the flight mode which the vehicle will be for follow me.
virtual uint32_t highLatencyCustomModeTo32Bits(uint16_t hlCustomMode) const
Convert from HIGH_LATENCY2.custom_mode value to correct 32 bit value.
virtual QGCCameraManager * createCameraManager(Vehicle *vehicle) const
Creates vehicle camera manager.
virtual QMap< QString, FactGroup * > * factGroups()
Returns a pointer to a dictionary of firmware-specific FactGroups.
virtual void initializeVehicle(Vehicle *)
Called when Vehicle is first created to perform any firmware specific setup.
virtual bool MAV_CMD_DO_SET_MODE_is_supported() const
returns true if this flight stack supports MAV_CMD_DO_SET_MODE
virtual QString rtlFlightMode() const
Returns the flight mode for RTL.
virtual double maximumHorizontalSpeedMultirotorMetersSecond(Vehicle *) const
virtual void guidedModeLand(Vehicle *vehicle) const
Command vehicle to land at current location.
virtual bool sendHomePositionToVehicle() const
virtual bool isGuidedMode(const Vehicle *) const
Returns whether the vehicle is in guided mode or not.
virtual double minimumTakeoffAltitudeMeters(Vehicle *) const
virtual QString getHobbsMeter(Vehicle *vehicle) const
gets hobbs meter from autopilot. This should be reimplmeented for each firmware
This is the base class for firmware specific geofence managers.
void error(int errorCode, const QString &errorMsg)
void loadComplete(void)
Supports the Mavlink image transmission protocol (https://mavlink.io/en/services/image_transmission....
uint32_t flowImageIndex() const
void flowImageIndexChanged(uint32_t index)
void imageReady(const QImage &image)
bool activeJoystickEnabledForActiveVehicle() const
static JoystickManager * instance()
The link interface defines the interface for all links used to communicate with the ground station ap...
virtual bool isConnected() const =0
void writeBytesThreadSafe(const char *bytes, int length)
void statusTextMessageFromEvent(uint8_t compid, int severity, const QString &text, const QString &description)
static int getComponentId()
void mavlinkMessageStatus(int sysid, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent)
void messageReceived(LinkInterface *link, const mavlink_message_t &message)
static MAVLinkProtocol * instance()
int getSystemId() const
Allows to configure a set of mavlink streams to a specific rate, and restore back to default.
Owns the COMMAND_LONG / COMMAND_INT send/retry/ack pipeline for a single Vehicle.
void sendCommandInt(int compId, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7)
static QString failureCodeToString(MavCmdResultFailureCode_t failureCode)
void commandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
Emitted for every terminal ack that has no user-provided resultHandler.
void sendCommandIntWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, MAV_FRAME frame, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, double param5=0.0, double param6=0.0, float param7=0.0f)
void sendCommandWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
void handleCommandAck(const mavlink_message_t &message, const mavlink_command_ack_t &ack)
Process a COMMAND_ACK — match it to a pending entry and fire callbacks.
void sendCommandDelayed(int compId, MAV_CMD command, bool showError, int milliseconds, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
bool isPending(int targetCompId, MAV_CMD command) const
True if a matching (targetCompId, command) is already queued or awaiting ack.
static void showCommandAckError(const mavlink_command_ack_t &ack)
void sendCommand(int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
int findEntryIndex(int targetCompId, MAV_CMD command) const
Index of a matching entry in the pending queue, or -1. Exposed for test use.
void sendCommandWithLambdaFallback(std::function< void()> lambda, int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Tracks per-component MAVLink message intervals and mediates SET_MESSAGE_INTERVAL commands plus MESSAG...
void handleMessageInterval(const mavlink_message_t &message)
void mavlinkMsgIntervalsChanged(uint8_t compid, uint16_t msgId, int32_t rate)
void setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate)
int32_t getMessageRate(uint8_t compId, uint16_t msgId)
static MissionCommandTree * instance()
QString rawName(MAV_CMD command) const
Returns the raw name for the specified command.
int currentIndex(void) const
Current mission item as reported by MISSION_CURRENT.
static MultiVehicleManager * instance()
Vehicle * activeVehicle() const
void parameterReadyVehicleAvailableChanged(bool parameterReadyVehicleAvailable)
void activeVehicleChanged(Vehicle *activeVehicle)
Fact * getParameter(int componentId, const QString &paramName)
void parametersReadyChanged(bool parametersReady)
static constexpr int defaultComponentId
void loadProgressChanged(float value)
void currentIndexChanged(int currentIndex)
void sendComplete(bool error)
void newMissionItemsAvailable(bool removeAllRequested)
const QList< MissionItem * > & missionItems(void)
Definition PlanManager.h:22
void error(int errorCode, const QString &errorMsg)
static void sendPlanToVehicle(Vehicle *vehicle, const QString &filename)
const QVariantList & cameraList() const
void showAdvancedUIChanged(bool showAdvancedUI)
static QGCCorePlugin * instance()
The QGCMapCircle represents a circular area which can be displayed on a Map control.
static QGCPositionManager * instance()
QGeoCoordinate gcsPosition() const
void gcsPositionChanged(QGeoCoordinate gcsPosition)
This is a QGeoCoordinate within a QObject such that it can be used on a QmlObjectListModel.
static QGCPressure * instance()
void progressUpdate(float progress)
bool active() const
int count() const override final
Radio link telemetry decoded from MAVLINK_MSG_ID_RADIO_STATUS.
This is the base class for firmware specific rally point managers. A rally point manager is responsib...
void loadComplete(void)
void error(int errorCode, const QString &errorMsg)
void mavlinkMessageReceived(mavlink_message_t &message)
Coordinates MAV_CMD_REQUEST_MESSAGE workflows: per-component queueing, ack/message correlation,...
void handleReceivedMessage(const mavlink_message_t &message)
static QString failureCodeToString(RequestMessageResultHandlerFailureCode_t failureCode)
void requestMessage(RequestMessageResultHandler resultHandler, void *resultHandlerData, int compId, int messageId, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f)
void stop()
Clear pending state without firing callbacks (used during vehicle shutdown).
Provides access to all app settings.
static SettingsManager * instance()
VideoSettings * videoSettings() const
FlyViewSettings * flyViewSettings() const
MavlinkSettings * mavlinkSettings() const
void modesUpdated()
void availableModesMonitorReceived(uint8_t seq)
bool messageTypeNone() const
bool messageTypeError() const
void handleHTMLEscapedTextMessage(MAV_COMPONENT componentid, MAV_SEVERITY severity, const QString &text, const QString &description)
bool messageTypeNormal() const
void newErrorMessage(QString message)
void mavlinkMessageReceived(const mavlink_message_t &message)
void messageCountChanged(uint32_t newCount)
void textMessageReceived(MAV_COMPONENT componentid, MAV_SEVERITY severity, QString text, QString description)
uint32_t messageCount() const
void newFormattedMessage(QString message)
QString formattedMessages() const
void messageTypeChanged()
bool messageTypeWarning() const
Class which represents sensor info from the SYS_STATUS mavlink message.
bool mavlinkMessageReceived(const mavlink_message_t &message)
Coordinates the three terrain-query workflows attached to a Vehicle:
void roiWithTerrain(const QGeoCoordinate &coord)
void sendROICommand(const QGeoCoordinate &coord, MAV_FRAME frame, float altitude)
void doSetHomeWithTerrain(const QGeoCoordinate &coord)
void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) override
Allows a FactGroup to parse incoming messages and fill in values.
void updateRCRSSI(uint8_t rssi)
void bindToGps(VehicleGPSFactGroup *gps1, VehicleGPSFactGroup *gps2)
WeakLinkInterfacePtr primaryLink() const
void mavlinkMessageReceived(LinkInterface *link, const mavlink_message_t &message)
bool containsLink(LinkInterface *link)
void update(mavlink_obstacle_distance_t *message)
Per-vehicle signing facade. Owns the wiring between Vehicle and the active SigningController (which l...
bool guidedMode() const
bool changeHeading() const
bool orbitMode() const
bool roiMode() const
bool pauseVehicle() const
Q_INVOKABLE void triggerSimpleCamera(void)
Trigger camera using MAV_CMD_DO_DIGICAM_CONTROL command.
Definition Vehicle.cc:3128
bool sub() const
Definition Vehicle.cc:1748
bool isInitialConnectComplete() const
Definition Vehicle.cc:2804
Q_INVOKABLE void guidedModeChangeAltitude(double altitudeChange, bool pauseVehicle)
Definition Vehicle.cc:1914
void _setLanding(bool landing)
Definition Vehicle.cc:1815
Vehicle(LinkInterface *link, int vehicleId, int defaultComponentId, MAV_AUTOPILOT firmwareType, MAV_TYPE vehicleType, QObject *parent=nullptr)
Definition Vehicle.cc:101
void autoDisarmChanged()
bool px4Firmware() const
Definition Vehicle.h:494
Q_INVOKABLE void motorInterlock(bool enable)
Command vehicle to Enable/Disable Motor Interlock.
Definition Vehicle.cc:3371
Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust)
Definition Vehicle.cc:1712
int32_t getMessageRate(uint8_t compId, uint16_t msgId)
Definition Vehicle.cc:3330
VehicleDistanceSensorFactGroup * _distanceSensorFactGroup
Definition Vehicle.h:1093
TerrainProtocolHandler * _terrainProtocolHandler
Definition Vehicle.h:1111
void firmwareTypeChanged()
QGCMAVLink::VehicleClass_t vehicleClass(void) const
Definition Vehicle.h:429
void setInitialGCSPressure(qreal pressure)
Definition Vehicle.h:414
Q_INVOKABLE void flashBootloader()
Definition Vehicle.cc:3359
void sensorsPresentBitsChanged(int sensorsPresentBits)
void defaultHoverSpeedChanged(double hoverSpeed)
friend class InitialConnectStateMachine
Definition Vehicle.h:105
const QString _vibrationFactGroupName
Definition Vehicle.h:1069
bool _multirotor_speed_limits_available
Definition Vehicle.h:1059
void gcsControlStatusChanged()
void defaultCruiseSpeedChanged(double cruiseSpeed)
bool messageTypeError() const
Definition Vehicle.cc:3394
const QString _gpsFactGroupName
Definition Vehicle.h:1065
FactGroup * localPositionFactGroup()
Definition Vehicle.cc:420
void haveMRSpeedLimChanged()
FactGroup * vibrationFactGroup()
Definition Vehicle.cc:415
void sendMavCommandWithLambdaFallback(std::function< void()> lambda, int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Definition Vehicle.cc:2185
BatteryFactGroupListModel * _batteryFactGroupListModel
Definition Vehicle.h:1108
void sendMavCommand(int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Definition Vehicle.cc:2146
VehicleLocalPositionFactGroup * _localPositionFactGroup
Definition Vehicle.h:1094
const QString _hygrometerFactGroupName
Definition Vehicle.h:1078
void messagesLostChanged()
Q_INVOKABLE void rebootVehicle()
Reboot vehicle.
Definition Vehicle.cc:2316
FactGroup * gpsAggregateFactGroup()
Definition Vehicle.cc:413
VehicleRPMFactGroup * _rpmFactGroup
Definition Vehicle.h:1100
const QString _localPositionFactGroupName
Definition Vehicle.h:1074
void vtolInFwdFlightChanged(bool vtolInFwdFlight)
QString missionFlightMode() const
Definition Vehicle.cc:2533
void readyToFlyAvailableChanged(bool readyToFlyAvailable)
void forceInitialPlanRequestComplete()
Definition Vehicle.cc:2707
void isROIEnabledChanged()
Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate &centerCoord, double radius, double amslAltitude)
Definition Vehicle.cc:1943
const QString _terrainFactGroupName
Definition Vehicle.h:1077
Actuators * _actuators
Definition Vehicle.h:1119
const QString _temperatureFactGroupName
Definition Vehicle.h:1070
void _offlineVehicleTypeSettingChanged(QVariant varVehicleType)
Definition Vehicle.cc:487
Q_INVOKABLE void guidedModeTakeoff(double altitudeRelative)
Command vehicle to takeoff from current location.
Definition Vehicle.cc:1846
Q_INVOKABLE void sendGripperAction(GRIPPER_ACTIONS gripperOption)
Definition Vehicle.cc:3137
QString flightMode() const
Definition Vehicle.cc:1468
static QString mavCmdResultFailureCodeToString(MavCmdResultFailureCode_t failureCode)
Definition Vehicle.cc:3350
QString stabilizedFlightMode() const
Definition Vehicle.cc:2573
const QVariantList & staticCameraList() const
Definition Vehicle.cc:3524
void requestOperatorControlReceived(int sysIdRequestingControl, int allowTakeover, int requestTimeoutSecs)
Q_INVOKABLE QVariant expandedToolbarIndicatorSource(const QString &indicatorName)
Definition Vehicle.cc:3340
void sendJoystickAuxRcOverrideThreadSafe(const std::array< uint16_t, kAuxRcOverrideChannelCount > &channelValues, const std::array< bool, kAuxRcOverrideChannelCount > &channelEnabled, bool useRcOverride)
Definition Vehicle.cc:3041
void setActuatorsMetadata(uint8_t compid, const QString &metadataJsonFileName)
Definition Vehicle.cc:1265
bool vtol() const
Definition Vehicle.cc:1763
void setSoloFirmware(bool soloFirmware)
Definition Vehicle.cc:2435
void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple=true)
Definition Vehicle.cc:1529
FactGroup * rpmFactGroup()
Definition Vehicle.cc:427
QGeoCoordinate homePosition()
Definition Vehicle.cc:1434
const QString _estimatorStatusFactGroupName
Definition Vehicle.h:1076
const QString _radioStatusFactGroupName
Definition Vehicle.h:1082
QString vehicleImageOutline() const
Definition Vehicle.cc:2586
MissionManager * _missionManager
Definition Vehicle.h:1113
VehicleLocalPositionSetpointFactGroup * _localPositionSetpointFactGroup
Definition Vehicle.h:1095
void textMessageReceived(int sysid, int componentid, int severity, QString text, QString description)
void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete)
Q_INVOKABLE double minimumEquivalentAirspeed()
Definition Vehicle.cc:1872
const QString _clockFactGroupName
Definition Vehicle.h:1071
bool rover() const
Definition Vehicle.cc:1743
bool multiRotor() const
Definition Vehicle.cc:1758
bool flying() const
Definition Vehicle.h:500
Q_INVOKABLE void stopGuidedModeROI()
Definition Vehicle.cc:2003
void firmwareCustomVersionChanged()
QString pauseFlightMode() const
Definition Vehicle.cc:2538
QString prearmError() const
Definition Vehicle.h:473
EscStatusFactGroupListModel * _escStatusFactGroupListModel
Definition Vehicle.h:1109
Q_INVOKABLE void guidedModeROI(const QGeoCoordinate &centerCoord)
Definition Vehicle.cc:1975
float latitude()
Definition Vehicle.h:492
const QString _efiFactGroupName
Definition Vehicle.h:1080
void inFwdFlightChanged()
void flyingChanged(bool flying)
void setFirmwarePluginInstanceData(FirmwarePluginInstanceData *firmwarePluginInstanceData)
Definition Vehicle.cc:2527
Q_INVOKABLE double maximumHorizontalSpeedMultirotorMetersSecond()
Definition Vehicle.cc:1860
bool hasGripper() const
Definition Vehicle.cc:1877
void sendMessageMultiple(mavlink_message_t message)
Definition Vehicle.cc:1587
void capabilityBitsChanged(uint64_t capabilityBits)
bool messageTypeNone() const
Definition Vehicle.cc:3391
void _setHomePosition(QGeoCoordinate &homeCoord)
Definition Vehicle.cc:1188
void hobbsMeterChanged()
VehicleClockFactGroup * _clockFactGroup
Definition Vehicle.h:1091
uint64_t capabilityBits() const
Definition Vehicle.h:697
Q_INVOKABLE void abortLanding(double climbOutAltitude)
Command vehicle to abort landing.
Definition Vehicle.cc:2056
void setGuidedMode(bool guidedMode)
Definition Vehicle.cc:2070
void readyToFlyChanged(bool readyToFy)
QString firmwareVersionTypeString() const
Definition Vehicle.cc:2289
QString landFlightMode() const
Definition Vehicle.cc:2553
static void showCommandAckError(const mavlink_command_ack_t &ack)
Definition Vehicle.cc:2200
void newFormattedMessage(QString formattedMessage)
MAV_TYPE vehicleType() const
Definition Vehicle.h:428
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
void cameraManagerChanged()
Q_INVOKABLE void sendParamMapRC(const QString &paramName, double scale, double centerValue, int tuningID, double minValue, double maxValue)
Sends PARAM_MAP_RC message to vehicle.
Definition Vehicle.cc:2921
HealthAndArmingCheckReport * healthAndArmingCheckReport()
Definition Vehicle.cc:3556
void armedChanged(bool armed)
void firmwareVersionChanged()
FactGroup * distanceSensorFactGroup()
Definition Vehicle.cc:419
void logEntry(uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num)
void sendControlRequestAllowedChanged(bool sendControlRequestAllowed)
void hasGripperChanged()
FactGroup * generatorFactGroup()
Definition Vehicle.cc:425
void rcChannelsRawChanged(QVector< int > channelValues)
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
Definition Vehicle.h:444
void sendMavCommandInt(int compId, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7)
Definition Vehicle.cc:2175
Q_INVOKABLE double minimumTakeoffAltitudeMeters()
Definition Vehicle.cc:1855
InitialConnectStateMachine * _initialConnectStateMachine
Definition Vehicle.h:1118
void sensorsParametersResetAck(bool success)
void sendMavCommandDelayed(int compId, MAV_CMD command, bool showError, int milliseconds, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Definition Vehicle.cc:2151
bool guidedMode() const
Definition Vehicle.cc:2065
const QString _distanceSensorFactGroupName
Definition Vehicle.h:1073
Q_INVOKABLE double maximumEquivalentAirspeed()
Definition Vehicle.cc:1866
PIDTuningTelemetryMode
Definition Vehicle.h:370
@ ModeDisabled
Definition Vehicle.h:371
@ ModeAltitudeAndAirspeed
Definition Vehicle.h:374
@ ModeVelocityAndPosition
Definition Vehicle.h:373
@ ModeRateAndAttitude
Definition Vehicle.h:372
void setPrearmError(const QString &prearmError)
Definition Vehicle.cc:2258
bool landing() const
Definition Vehicle.h:501
VehicleVibrationFactGroup * _vibrationFactGroup
Definition Vehicle.h:1089
~Vehicle()
Definition Vehicle.cc:388
void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion)
Definition Vehicle.cc:2281
Q_INVOKABLE void startTimerRevertAllowTakeover()
Definition Vehicle.cc:3179
int messageCount() const
Definition Vehicle.cc:3395
VehicleGeneratorFactGroup * _generatorFactGroup
Definition Vehicle.h:1098
const QString _generatorFactGroupName
Definition Vehicle.h:1079
void messagesSentChanged()
Q_INVOKABLE void sendPlan(QString planFile)
Definition Vehicle.cc:2713
bool vtolInFwdFlight() const
Definition Vehicle.h:504
Q_INVOKABLE void startMission()
Definition Vehicle.cc:1888
bool isMavCommandPending(int targetCompId, MAV_CMD command)
isMavCommandPending Query whether the specified MAV_CMD is in queue to be sent or has already been se...
Definition Vehicle.cc:2190
void capabilitiesKnownChanged(bool capabilitiesKnown)
Q_INVOKABLE void requestOperatorControl(bool allowOverride, int requestTimeoutSecs=0)
Definition Vehicle.cc:3195
void rcChannelsClampedChanged(QVector< int > channelValues)
VehicleEstimatorStatusFactGroup * _estimatorStatusFactGroup
Definition Vehicle.h:1096
VehicleTemperatureFactGroup * _temperatureFactGroup
Definition Vehicle.h:1090
bool soloFirmware() const
Definition Vehicle.h:667
void coordinateChanged(QGeoCoordinate coordinate)
QString vehicleImageOpaque() const
Definition Vehicle.cc:2578
float _altitudeTuningOffset
Definition Vehicle.h:1056
Q_INVOKABLE void setPIDTuningTelemetryMode(PIDTuningTelemetryMode mode)
Definition Vehicle.cc:2753
void mavlinkLogData(Vehicle *vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked)
Q_INVOKABLE void emergencyStop()
Command vehicle to kill all motors no matter what state.
Definition Vehicle.cc:2081
void updateFlightDistance(double distance)
Definition Vehicle.cc:2916
int id() const
Definition Vehicle.h:425
const QString _gpsAggregateFactGroupName
Definition Vehicle.h:1067
Q_INVOKABLE bool guidedModeGotoLocation(const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius=0.0f)
Definition Vehicle.cc:1893
void pairRX(int rxType, int rxSubType)
Definition Vehicle.cc:3170
const QString _setpointFactGroupName
Definition Vehicle.h:1072
Q_INVOKABLE void setCurrentMissionSequence(int seq)
Alter the current mission item on the vehicle.
Definition Vehicle.cc:2111
FactGroup * gps2FactGroup()
Definition Vehicle.cc:412
void toolIndicatorsChanged()
void sensorsUnhealthyBitsChanged(int sensorsUnhealthyBits)
void landingChanged(bool landing)
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1389
VehicleWindFactGroup * _windFactGroup
Definition Vehicle.h:1088
bool inFwdFlight() const
Definition Vehicle.cc:2075
const QString _rpmFactGroupName
Definition Vehicle.h:1081
FactGroup * hygrometerFactGroup()
Definition Vehicle.cc:424
static const MAV_AUTOPILOT MAV_AUTOPILOT_TRACK
Definition Vehicle.h:127
Q_INVOKABLE void startTakeoff()
Definition Vehicle.cc:1882
Q_INVOKABLE void resetAllMessages()
Definition Vehicle.cc:3388
VehicleHygrometerFactGroup * _hygrometerFactGroup
Definition Vehicle.h:1097
void setFlightMode(const QString &flightMode)
Definition Vehicle.cc:1478
bool messageTypeWarning() const
Definition Vehicle.cc:3393
Q_INVOKABLE void sendCommand(int compId, int command, bool showError, double param1=0.0, double param2=0.0, double param3=0.0, double param4=0.0, double param5=0.0, double param6=0.0, double param7=0.0)
Same as sendMavCommand but available from Qml.
Definition Vehicle.cc:2156
void loadProgressChanged(float value)
QString smartRTLFlightMode() const
Definition Vehicle.cc:2548
QString followFlightMode() const
Definition Vehicle.cc:2563
bool _fixed_wing_airspeed_limits_available
Definition Vehicle.h:1060
Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs, bool showError)
Definition Vehicle.cc:2443
void mavlinkMessageReceived(const mavlink_message_t &message)
void setMessageRate(uint8_t compId, uint16_t msgId, int32_t rate)
Definition Vehicle.cc:3335
Q_INVOKABLE void resetCounters()
< Flight mode vehicle is in while performing goto
Definition Vehicle.cc:510
const QVariantList & toolIndicators()
Definition Vehicle.cc:2594
void _offlineFirmwareTypeSettingChanged(QVariant varFirmwareType)
Definition Vehicle.cc:474
FactGroup * localPositionSetpointFactGroup()
Definition Vehicle.cc:421
Q_INVOKABLE void guidedModeChangeEquivalentAirspeedMetersSecond(double airspeed)
Definition Vehicle.cc:1934
QmlObjectListModel * escs()
Definition Vehicle.cc:431
void guidedModeChanged(bool guidedMode)
FactGroup * efiFactGroup()
Definition Vehicle.cc:426
void setEventsMetadata(uint8_t compid, const QString &metadataJsonFileName)
Definition Vehicle.cc:3561
QString formattedMessages() const
Definition Vehicle.cc:3396
int _findMavCommandListEntryIndex(int targetCompId, MAV_CMD command)
Test-only helper: forwards to MavCommandQueue::findEntryIndex.
Definition Vehicle.cc:2195
bool autoDisarm()
Definition Vehicle.cc:2614
QObject * sysStatusSensorInfo()
Definition Vehicle.cc:433
QString motorDetectionFlightMode() const
Definition Vehicle.cc:2568
Q_INVOKABLE void resetErrorLevelMessages()
Definition Vehicle.cc:3389
bool coaxialMotors()
Definition Vehicle.cc:1419
void orbitActiveChanged(bool orbitActive)
bool messageTypeNormal() const
Definition Vehicle.cc:3392
void allSensorsHealthyChanged(bool allSensorsHealthy)
Q_INVOKABLE void guidedModeRTL(bool smartRTL)
Command vehicle to return to launch.
Definition Vehicle.cc:1828
VehicleGPS2FactGroup * _gps2FactGroup
Definition Vehicle.h:1086
bool xConfigMotors()
Definition Vehicle.cc:1424
void trackFirmwareVehicleTypeChanges(void)
Definition Vehicle.cc:212
Q_INVOKABLE void landingGearDeploy()
Command vichecle to deploy landing gear.
Definition Vehicle.cc:2091
void armedPositionChanged()
VehicleEFIFactGroup * _efiFactGroup
Definition Vehicle.h:1099
int motorCount()
Definition Vehicle.cc:1410
void stopMavlinkLog()
Definition Vehicle.cc:2473
static QString requestMessageResultHandlerFailureCodeToString(RequestMessageResultHandlerFailureCode_t failureCode)
Definition Vehicle.cc:3345
RemoteIDManager * _remoteIDManager
Definition Vehicle.h:1120
Q_INVOKABLE void doSetHome(const QGeoCoordinate &coord)
Set home from flight map coordinate.
Definition Vehicle.cc:2867
void stopUAVCANBusConfig(void)
Definition Vehicle.cc:2427
void soloFirmwareChanged(bool soloFirmware)
uint32_t flowImageIndex() const
Definition Vehicle.cc:3491
int compId() const
Definition Vehicle.h:426
void homePositionChanged(const QGeoCoordinate &homePosition)
QMap< uint8_t, uint8_t > _lowestBatteryChargeStateAnnouncedMap
Definition Vehicle.h:1054
FactGroup * radioStatusFactGroup()
Definition Vehicle.cc:428
Q_INVOKABLE void pauseVehicle()
Definition Vehicle.cc:2047
void stopTrackingFirmwareVehicleTypeChanges(void)
Definition Vehicle.cc:221
FactGroup * windFactGroup()
Definition Vehicle.cc:414
void flightModesChanged()
const QString _gps2FactGroupName
Definition Vehicle.h:1066
FactGroup * temperatureFactGroup()
Definition Vehicle.cc:416
bool apmFirmware() const
Definition Vehicle.h:495
Q_INVOKABLE void closeVehicle()
Removes the vehicle from the system.
Definition Vehicle.cc:435
void flightModeChanged(const QString &flightMode)
void flowImageIndexChanged()
void roiCoordChanged(const QGeoCoordinate &centerCoord)
Q_INVOKABLE void clearAllParamMapRC(void)
Clears all PARAM_MAP_RC settings from vehicle.
Definition Vehicle.cc:2955
void messageTypeChanged()
FactGroup * estimatorStatusFactGroup()
Definition Vehicle.cc:422
Q_INVOKABLE void setEstimatorOrigin(const QGeoCoordinate &centerCoord)
Definition Vehicle.cc:3147
void setVtolInFwdFlight(bool vtolInFwdFlight)
Definition Vehicle.cc:2457
Q_INVOKABLE void guidedModeChangeGroundSpeedMetersSecond(double groundspeed)
Definition Vehicle.cc:1924
int defaultComponentId() const
Definition Vehicle.h:670
void setInitialGCSTemperature(qreal temperature)
Definition Vehicle.h:415
void mavlinkStatusChanged()
MAVLinkLogManager * mavlinkLogManager() const
Definition Vehicle.cc:3506
Q_INVOKABLE void clearMessages()
Definition Vehicle.cc:3390
FactGroup * setpointFactGroup()
Definition Vehicle.cc:418
void sendJoystickDataThreadSafe(float roll, float pitch, float yaw, float thrust, quint16 buttons, quint16 buttons2, float pitchExtension, float rollExtension, float aux1, float aux2, float aux3, float aux4, float aux5, float aux6)
Definition Vehicle.cc:2981
QmlObjectListModel * cameraTriggerPoints()
Definition Vehicle.cc:434
FTPManager * _ftpManager
Definition Vehicle.h:1117
GeoFenceManager * _geoFenceManager
Definition Vehicle.h:1114
float longitude()
Definition Vehicle.h:493
bool flightModeSetAvailable()
Definition Vehicle.cc:1457
ParameterManager * parameterManager()
Definition Vehicle.h:573
VehicleGPSFactGroup * _gpsFactGroup
Definition Vehicle.h:1085
void sensorsHealthBitsChanged(int sensorsHealthBits)
void _setFlying(bool flying)
Definition Vehicle.cc:1807
Q_INVOKABLE void guidedModeChangeHeading(const QGeoCoordinate &headingCoord)
Definition Vehicle.cc:2037
QString takeControlFlightMode() const
Definition Vehicle.cc:2558
void messagesReceivedChanged()
const QString _localPositionSetpointFactGroupName
Definition Vehicle.h:1075
void setOfflineEditingDefaultComponentId(int defaultComponentId)
Sets the default component id for an offline editing vehicle.
Definition Vehicle.cc:2448
void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType=FIRMWARE_VERSION_TYPE_OFFICIAL)
Definition Vehicle.cc:2272
QString rtlFlightMode() const
Definition Vehicle.cc:2543
bool fixedWing() const
Definition Vehicle.cc:1738
void requestMessage(RequestMessageResultHandler resultHandler, void *resultHandlerData, int compId, int messageId, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f)
Definition Vehicle.cc:2252
QGeoCoordinate coordinate()
Definition Vehicle.h:409
void startCalibration(QGCMAVLink::CalibrationType calType)
Definition Vehicle.cc:2325
QVector< int > _servoOutputRawValues
Definition Vehicle.h:1105
QString firmwareTypeString() const
Definition Vehicle.cc:505
FactGroup * clockFactGroup()
Definition Vehicle.cc:417
void stopCalibration(bool showError)
Definition Vehicle.cc:2405
void messageCountChanged()
friend class VehicleLinkManager
Definition Vehicle.h:106
QmlObjectListModel * batteries()
Definition Vehicle.cc:430
void haveFWSpeedLimChanged()
RallyPointManager * _rallyPointManager
Definition Vehicle.h:1115
void startUAVCANBusConfig(void)
Definition Vehicle.cc:2419
RadioStatusFactGroup * _radioStatusFactGroup
Definition Vehicle.h:1102
QString gotoFlightMode() const
Definition Vehicle.cc:1823
void sendMavCommandIntWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, MAV_FRAME frame, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, double param5=0.0f, double param6=0.0f, float param7=0.0f)
Definition Vehicle.cc:2180
bool armed() const
Definition Vehicle.h:449
Q_INVOKABLE void landingGearRetract()
Command vichecle to retract landing gear.
Definition Vehicle.cc:2101
VehicleSupports * supports()
Definition Vehicle.h:402
const QString _windFactGroupName
Definition Vehicle.h:1068
void mavCommandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
VehicleGPSAggregateFactGroup * _gpsAggregateFactGroup
Definition Vehicle.h:1087
FactGroup * gpsFactGroup()
Definition Vehicle.cc:411
void sensorsEnabledBitsChanged(int sensorsEnabledBits)
class FirmwarePluginInstanceData * firmwarePluginInstanceData()
Definition Vehicle.h:685
VehicleSetpointFactGroup * _setpointFactGroup
Definition Vehicle.h:1092
Q_INVOKABLE int versionCompare(const QString &compare) const
Used to check if running current version is equal or higher than the one being compared.
Definition Vehicle.cc:2743
TerrainFactGroup * _terrainFactGroup
Definition Vehicle.h:1101
Q_INVOKABLE void forceArm()
Definition Vehicle.cc:1448
void requiresGpsFixChanged()
void setArmed(bool armed, bool showError)
Definition Vehicle.cc:1439
QStringList flightModes()
Definition Vehicle.cc:1462
void mavlinkMsgIntervalsChanged(uint8_t compid, uint16_t msgId, int32_t rate)
FactGroup * terrainFactGroup()
Definition Vehicle.cc:423
void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data)
Q_INVOKABLE QString vehicleClassInternalName() const
Definition Vehicle.cc:1773
VehicleLinkManager * _vehicleLinkManager
Definition Vehicle.h:1116
void servoOutputsChanged(QVector< int > servoValues)
QString hobbsMeter()
Definition Vehicle.cc:2718
TerrainQueryCoordinator * _terrainQueryCoordinator
Definition Vehicle.h:1124
void prearmErrorChanged(const QString &prearmError)
void startMavlinkLog()
Definition Vehicle.cc:2468
void vehicleTypeChanged()
Q_INVOKABLE void guidedModeLand()
Command vehicle to land at current location.
Definition Vehicle.cc:1837
void sendMavCommandWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Sends the command and calls the callback with the result.
Definition Vehicle.cc:2170
bool airship() const
Definition Vehicle.cc:1733
StandardModes * _standardModes
Definition Vehicle.h:1121
QString vehicleUIDStr()
Definition Vehicle.cc:1012
bool spacecraft() const
Definition Vehicle.cc:1753
friend class GimbalController
Definition Vehicle.h:114
QString vehicleTypeString() const
Definition Vehicle.cc:1768
void logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t *data)
static VideoManager * instance()
Q_INVOKABLE void stopVideo()
static constexpr const char * videoSourceUDPH264
static constexpr const char * videoDisabled
@ MOTOR_INTERLOCK
Definition APM.h:35
bool runningUnitTests()
bool fuzzyCompare(double value1, double value2)
Returns true if the two values are equal or close. Correctly handles 0 and NaN values.
Definition QGCMath.cc:109
void showCriticalVehicleMessage(const QString &message)
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
Definition AppMessages.cc:9
Callback info bundle for sendMavCommandWithHandler.
MavCmdResultHandler resultHandler
nullptr for no handler
@ MavCmdResultFailureDuplicateCommand
Unable to send command since duplicate is already being waited on for response.
@ MavCmdResultCommandResultOnly
commandResult specifies full success/fail info
@ MavCmdResultFailureNoResponseToCommand
No response from vehicle to command.
RequestMessageResultHandlerFailureCode_t