QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
APMFirmwarePlugin.cc
Go to the documentation of this file.
1#include "APMFirmwarePlugin.h"
3#include "QGCMAVLink.h"
4#include "AppMessages.h"
5#include "QGCApplication.h"
6#include "MissionManager.h"
7#include "ParameterManager.h"
8#include "SettingsManager.h"
9#include "MavlinkSettings.h"
10#include "PlanViewSettings.h"
11#include "VideoSettings.h"
18#include "LinkManager.h"
19#include "Vehicle.h"
20#include "VehicleLinkManager.h"
21#include "StatusTextHandler.h"
22#include "MAVLinkProtocol.h"
23#include "QGCLoggingCategory.h"
24#include "QGCSensors.h"
25
26#include <QtNetwork/QTcpSocket>
27
28#include <QtCore/QRegularExpression>
29#include <QtCore/QRegularExpressionMatch>
30
31QGC_LOGGING_CATEGORY(APMFirmwarePluginLog, "FirmwarePlugin.APMFirmwarePlugin")
32
34 : FirmwarePlugin(parent)
35{
36 _setModeEnumToModeStringMapping({
37 { APMCustomMode::GUIDED, _guidedFlightMode },
38 { APMCustomMode::RTL, _rtlFlightMode },
39 { APMCustomMode::SMART_RTL, _smartRtlFlightMode },
40 { APMCustomMode::AUTO, _autoFlightMode },
41 });
42
43 static FlightModeList modeList {
44 // Mode Name , Custom Mode CanBeSet adv
45 { _guidedFlightMode , APMCustomMode::GUIDED, true , true },
46 { _rtlFlightMode , APMCustomMode::RTL, true , true },
47 { _smartRtlFlightMode , APMCustomMode::SMART_RTL, true , true },
48 { _autoFlightMode , APMCustomMode::AUTO, true , true },
49 };
50
51 updateAvailableFlightModes(modeList);
52}
53
58
60{
61 return new APMAutoPilotPlugin(vehicle, vehicle);
62}
63
64bool APMFirmwarePlugin::isCapable(const Vehicle* vehicle, FirmwareCapabilities capabilities) const
65{
67 if (vehicle->fixedWing()) {
68 available |= TakeoffVehicleCapability;
69 } else if (vehicle->multiRotor()) {
70 available |= TakeoffVehicleCapability;
71 available |= GuidedTakeoffCapability;
72 available |= ChangeHeadingCapability;
73 } else if (vehicle->vtol()) {
74 available |= TakeoffVehicleCapability;
75 available |= GuidedTakeoffCapability;
76 } else if (vehicle->sub()) {
77 available |= ChangeHeadingCapability;
78 }
79
80 return (capabilities & available) == capabilities;
81}
82
83QStringList APMFirmwarePlugin::flightModes(Vehicle *vehicle) const
84{
85 Q_UNUSED(vehicle)
86 QStringList flightModesList;
87 for (const FirmwareFlightMode &mode : _flightModeList) {
88 if (mode.canBeSet){
89 flightModesList += mode.mode_name;
90 }
91 }
92 return flightModesList;
93}
94
95QString APMFirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode) const
96{
97 QString flightMode = "Unknown";
98
99 if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
100 return _modeEnumToString.value(custom_mode, flightMode);
101 }
102 return flightMode;
103}
104
105bool APMFirmwarePlugin::setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const
106{
107 *base_mode = 0;
108 *custom_mode = 0;
109
110 bool found = false;
111
112 for (const FirmwareFlightMode &mode: _flightModeList){
113 if (flightMode.compare(mode.mode_name, Qt::CaseInsensitive) == 0){
114 *base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
115 *custom_mode = mode.custom_mode;
116 found = true;
117 break;
118 }
119 }
120
121 if (!found) {
122 qCWarning(APMFirmwarePluginLog) << "Unknown flight Mode" << flightMode;
123 }
124
125 return found;
126}
127
128void APMFirmwarePlugin::_handleIncomingParamValue(Vehicle *vehicle, mavlink_message_t *message)
129{
130 Q_UNUSED(vehicle);
131
132 mavlink_param_value_t paramValue;
133 mavlink_param_union_t paramUnion;
134
135 (void) memset(&paramValue, 0, sizeof(paramValue));
136
137 // APM stack passes all parameter values in mavlink_param_union_t.param_float no matter what
138 // type they are. Fix that up to correct usage.
139
140 mavlink_msg_param_value_decode(message, &paramValue);
141
142 switch (paramValue.param_type) {
143 case MAV_PARAM_TYPE_UINT8:
144 paramUnion.param_uint8 = static_cast<uint8_t>(paramValue.param_value);
145 break;
146 case MAV_PARAM_TYPE_INT8:
147 paramUnion.param_int8 = static_cast<int8_t>(paramValue.param_value);
148 break;
149 case MAV_PARAM_TYPE_UINT16:
150 paramUnion.param_uint16 = static_cast<uint16_t>(paramValue.param_value);
151 break;
152 case MAV_PARAM_TYPE_INT16:
153 paramUnion.param_int16 = static_cast<int16_t>(paramValue.param_value);
154 break;
155 case MAV_PARAM_TYPE_UINT32:
156 paramUnion.param_uint32 = static_cast<uint32_t>(paramValue.param_value);
157 break;
158 case MAV_PARAM_TYPE_INT32:
159 paramUnion.param_int32 = static_cast<int32_t>(paramValue.param_value);
160 break;
161 case MAV_PARAM_TYPE_REAL32:
162 paramUnion.param_float = paramValue.param_value;
163 break;
164 default:
165 qCCritical(APMFirmwarePluginLog) << "Invalid/Unsupported data type used in parameter:" << paramValue.param_type;
166 }
167
168 paramValue.param_value = paramUnion.param_float;
169
170 // Re-Encoding is always done using mavlink 1.0
171 const uint8_t channel = _reencodeMavlinkChannel();
172 QMutexLocker reencode_lock{&_reencodeMavlinkChannelMutex()};
173
174 mavlink_status_t *mavlinkStatusReEncode = mavlink_get_channel_status(channel);
175 mavlinkStatusReEncode->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
176
177 Q_ASSERT(qgcApp()->thread() == QThread::currentThread());
178 (void) mavlink_msg_param_value_encode_chan(
179 message->sysid,
180 message->compid,
181 channel,
182 message,
183 &paramValue
184 );
185}
186
187void APMFirmwarePlugin::_handleOutgoingParamSetThreadSafe(Vehicle* /*vehicle*/, LinkInterface *outgoingLink, mavlink_message_t *message)
188{
189 mavlink_param_set_t paramSet;
190 mavlink_param_union_t paramUnion;
191
192 (void) memset(&paramSet, 0, sizeof(paramSet));
193
194 // APM stack passes all parameter values in mavlink_param_union_t.param_float no matter what
195 // type they are. Fix it back to the wrong way on the way out.
196
197 mavlink_msg_param_set_decode(message, &paramSet);
198
199 if (!_ardupilotComponentMap[paramSet.target_system][paramSet.target_component]) {
200 // Message is targetted to non-ArduPilot firmware component, assume it uses current mavlink spec
201 return;
202 }
203
204 paramUnion.param_float = paramSet.param_value;
205
206 switch (paramSet.param_type) {
207 case MAV_PARAM_TYPE_UINT8:
208 paramSet.param_value = paramUnion.param_uint8;
209 break;
210 case MAV_PARAM_TYPE_INT8:
211 paramSet.param_value = paramUnion.param_int8;
212 break;
213 case MAV_PARAM_TYPE_UINT16:
214 paramSet.param_value = paramUnion.param_uint16;
215 break;
216 case MAV_PARAM_TYPE_INT16:
217 paramSet.param_value = paramUnion.param_int16;
218 break;
219 case MAV_PARAM_TYPE_UINT32:
220 paramSet.param_value = paramUnion.param_uint32;
221 break;
222 case MAV_PARAM_TYPE_INT32:
223 paramSet.param_value = paramUnion.param_int32;
224 break;
225 case MAV_PARAM_TYPE_REAL32:
226 // Already in param_float
227 break;
228 default:
229 qCCritical(APMFirmwarePluginLog) << "Invalid/Unsupported data type used in parameter:" << paramSet.param_type;
230 }
231
232 _adjustOutgoingMavlinkMutex.lock();
233 mavlink_msg_param_set_encode_chan(
234 message->sysid,
235 message->compid,
236 outgoingLink->mavlinkChannel(),
237 message,
238 &paramSet
239 );
240 _adjustOutgoingMavlinkMutex.unlock();
241}
242
243bool APMFirmwarePlugin::_handleIncomingStatusText(Vehicle* /*vehicle*/, mavlink_message_t *message)
244{
245 // APM user facing calibration messages come through as high severity, we need to parse them out
246 // and lower the severity on them so that they don't pop in the users face.
247
248 const QString messageText = StatusTextHandler::getMessageText(*message);
249 if (messageText.contains("Place vehicle") || messageText.contains("Calibration successful")) {
250 _adjustCalibrationMessageSeverity(message);
251 return true;
252 }
253
254 static const QRegularExpression APM_FRAME_REXP("^Frame: (\\S*)");
255 const QRegularExpressionMatch match = APM_FRAME_REXP.match(messageText);
256 if (match.hasMatch()) {
257 static const QSet<QString> coaxialFrames = {"Y6", "OCTA_QUAD", "COAX", "QUAD/PLUS"};
258 const QString frameType = match.captured(1);
259 _coaxialMotors = coaxialFrames.contains(frameType);
260 }
261
262 return true;
263}
264
265void APMFirmwarePlugin::_handleIncomingHeartbeat(Vehicle *vehicle, mavlink_message_t *message)
266{
267 mavlink_heartbeat_t heartbeat{};
268 mavlink_msg_heartbeat_decode(message, &heartbeat);
269
270 if (message->compid == MAV_COMP_ID_AUTOPILOT1) {
271 bool flying = false;
272
273 // We pull Vehicle::flying state from HEARTBEAT on ArduPilot. This is a firmware specific test.
274 if (vehicle->armed() && ((heartbeat.system_status == MAV_STATE_ACTIVE) || (heartbeat.system_status == MAV_STATE_CRITICAL) || (heartbeat.system_status == MAV_STATE_EMERGENCY))) {
275 flying = true;
276 }
277 vehicle->_setFlying(flying);
278 }
279
280 // We need to know whether this component is part of the ArduPilot stack code or not so we can adjust mavlink quirks appropriately.
281 // If the component sends a heartbeat we can know that. If it's doesn't there is pretty much no way to know.
282 _ardupilotComponentMap[message->sysid][message->compid] = heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA;
283
284 // Force the ESP8266 to be non-ArduPilot code (it doesn't send heartbeats)
285 _ardupilotComponentMap[message->sysid][MAV_COMP_ID_UDP_BRIDGE] = false;
286}
287
289{
290 // We use loss of BATTERY_STATUS/HOME_POSITION as a trigger to reinitialize stream rates
291 auto instanceData = qobject_cast<APMFirmwarePluginInstanceData*>(vehicle->firmwarePluginInstanceData());
292
293 if (message->msgid == MAVLINK_MSG_ID_HEARTBEAT) {
294 // We need to look at all heartbeats that go by from any component
295 _handleIncomingHeartbeat(vehicle, message);
296 } else if (message->msgid == MAVLINK_MSG_ID_BATTERY_STATUS && instanceData) {
297 instanceData->lastBatteryStatusTime = QTime::currentTime();
298 } else if (message->msgid == MAVLINK_MSG_ID_HOME_POSITION && instanceData) {
299 instanceData->lastHomePositionTime = QTime::currentTime();
300 } else {
301 // Only translate messages which come from ArduPilot code. All other components are expected to follow current mavlink spec.
302 if (_ardupilotComponentMap[vehicle->id()][message->compid]) {
303 switch (message->msgid) {
304 case MAVLINK_MSG_ID_PARAM_VALUE:
305 _handleIncomingParamValue(vehicle, message);
306 break;
307 case MAVLINK_MSG_ID_STATUSTEXT:
308 return _handleIncomingStatusText(vehicle, message);
309 case MAVLINK_MSG_ID_RC_CHANNELS:
310 _handleRCChannels(vehicle, message);
311 break;
312 case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
313 _handleRCChannelsRaw(vehicle, message);
314 break;
315 }
316 }
317 }
318
319 // If we lose BATTERY_STATUS/HOME_POSITION for reinitStreamsTimeoutSecs seconds we re-initialize stream rates
320 const int reinitStreamsTimeoutSecs = 10;
321 if (instanceData && ((instanceData->lastBatteryStatusTime.secsTo(QTime::currentTime()) > reinitStreamsTimeoutSecs) || (instanceData->lastHomePositionTime.secsTo(QTime::currentTime()) > reinitStreamsTimeoutSecs))) {
322 initializeStreamRates(vehicle);
323 }
324
325 return true;
326}
327
329{
330 switch (message->msgid) {
331 case MAVLINK_MSG_ID_PARAM_SET:
332 _handleOutgoingParamSetThreadSafe(vehicle, outgoingLink, message);
333 break;
334 default:
335 break;
336 }
337}
338
339void APMFirmwarePlugin::_setInfoSeverity(mavlink_message_t *message) const
340{
341 // Re-Encoding is always done using mavlink 1.0
342 const uint8_t channel = _reencodeMavlinkChannel();
343 QMutexLocker reencode_lock{&_reencodeMavlinkChannelMutex()};
344 mavlink_status_t *mavlinkStatusReEncode = mavlink_get_channel_status(channel);
345 mavlinkStatusReEncode->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
346
347 mavlink_statustext_t statusText{};
348 mavlink_msg_statustext_decode(message, &statusText);
349
350 statusText.severity = MAV_SEVERITY_INFO;
351
352 Q_ASSERT(qgcApp()->thread() == QThread::currentThread());
353 (void) mavlink_msg_statustext_encode_chan(
354 message->sysid,
355 message->compid,
356 channel,
357 message,
358 &statusText
359 );
360}
361
362void APMFirmwarePlugin::_adjustCalibrationMessageSeverity(mavlink_message_t *message) const
363{
364 mavlink_statustext_t statusText{};
365 mavlink_msg_statustext_decode(message, &statusText);
366
367 // Re-Encoding is always done using mavlink 1.0
368 const uint8_t channel = _reencodeMavlinkChannel();
369 QMutexLocker reencode_lock{&_reencodeMavlinkChannelMutex()};
370
371 mavlink_status_t *mavlinkStatusReEncode = mavlink_get_channel_status(channel);
372 mavlinkStatusReEncode->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
373 statusText.severity = MAV_SEVERITY_INFO;
374
375 Q_ASSERT(qgcApp()->thread() == QThread::currentThread());
376 (void) mavlink_msg_statustext_encode_chan(
377 message->sysid,
378 message->compid,
379 channel,
380 message,
381 &statusText
382 );
383}
384
386{
387 // We use loss of BATTERY_STATUS/HOME_POSITION as a trigger to reinitialize stream rates
388 auto instanceData = qobject_cast<APMFirmwarePluginInstanceData*>(vehicle->firmwarePluginInstanceData());
389 if (!instanceData) {
390 instanceData = new APMFirmwarePluginInstanceData(vehicle);
391 instanceData->lastBatteryStatusTime = instanceData->lastHomePositionTime = QTime::currentTime();
392 vehicle->setFirmwarePluginInstanceData(instanceData);
393 }
394
395 if (SettingsManager::instance()->mavlinkSettings()->apmStartMavlinkStreams()->rawValue().toBool()) {
396
398
399 struct StreamInfo_s {
400 MAV_DATA_STREAM mavStream;
401 int streamRate;
402 };
403
404 const StreamInfo_s rgStreamInfo[] = {
405 { MAV_DATA_STREAM_RAW_SENSORS, streamRates->streamRateRawSensors()->rawValue().toInt() },
406 { MAV_DATA_STREAM_EXTENDED_STATUS, streamRates->streamRateExtendedStatus()->rawValue().toInt() },
407 { MAV_DATA_STREAM_RC_CHANNELS, streamRates->streamRateRCChannels()->rawValue().toInt() },
408 { MAV_DATA_STREAM_POSITION, streamRates->streamRatePosition()->rawValue().toInt() },
409 { MAV_DATA_STREAM_EXTRA1, streamRates->streamRateExtra1()->rawValue().toInt() },
410 { MAV_DATA_STREAM_EXTRA2, streamRates->streamRateExtra2()->rawValue().toInt() },
411 { MAV_DATA_STREAM_EXTRA3, streamRates->streamRateExtra3()->rawValue().toInt() },
412 };
413
414 for (size_t i = 0; i < std::size(rgStreamInfo); i++) {
415 const StreamInfo_s &streamInfo = rgStreamInfo[i];
416
417 if (streamInfo.streamRate >= 0) {
418 vehicle->requestDataStream(streamInfo.mavStream, static_cast<uint16_t>(streamInfo.streamRate));
419 }
420 }
421 }
422
423 // The MAV_CMD_SET_MESSAGE_INTERVAL command is only supported on newer firmwares. So we set showError=false.
424 // Which also means than on older firmwares you may be left with some missing features.
425
426 // ArduPilot only sends home position on first boot and then when it arms. It does not stream the position.
427 // This means that depending on when QGC connects to the vehicle it may not have home position.
428 // This can cause various features to not be available. So we request home position streaming ourselves.
429 vehicle->sendMavCommand(MAV_COMP_ID_AUTOPILOT1, MAV_CMD_SET_MESSAGE_INTERVAL, false /* showError */, MAVLINK_MSG_ID_HOME_POSITION, 1000000 /* 1 second interval in usec */);
430
431 // ArduPilot doesn't send MAVLINK_MSG_ID_EXTENDED_SYS_STATE messages unless requested, so we request it to
432 // make the LandAbort action available.
433 vehicle->sendMavCommand(MAV_COMP_ID_AUTOPILOT1, MAV_CMD_SET_MESSAGE_INTERVAL, false /* showError */, MAVLINK_MSG_ID_EXTENDED_SYS_STATE, 1000000 /* 1 second interval in usec */);
434
435 instanceData->lastBatteryStatusTime = instanceData->lastHomePositionTime = QTime::currentTime();
436}
437
438APMFirmwarePlugin::FirmwareParameterHeader APMFirmwarePlugin::_parseParamsHeader(const QString &filePath)
439{
440 APMFirmwarePlugin::FirmwareParameterHeader data{};
441
442 QFile file(filePath);
443 if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
444 return data;
445 }
446
447 QTextStream stream(&file);
448 while (!stream.atEnd()) {
449 const QString line = stream.readLine();
450
451 // Stop once non-comment parameter rows begin and we already saw some header
452 if (!line.startsWith('#')) {
453 break;
454 }
455
456 using namespace Qt::StringLiterals;
457
458 static const QRegularExpression reStack(uR"(^#\s*Stack:\s*(.+)\s*$)"_s);
459 auto match = reStack.match(line);
460 if (match.hasMatch()) {
461 const QString firmwareTypeStr = match.captured(1).trimmed();
462 const MAV_AUTOPILOT firmwareType = QGCMAVLink::firmwareTypeFromString(firmwareTypeStr);
463 data.firmwareType = firmwareType;
464 continue;
465 }
466
467 static const QRegularExpression reVehicle(uR"(^#\s*Vehicle:\s*(.+)\s*$)"_s);
468 match = reVehicle.match(line);
469 if (match.hasMatch()) {
470 const QString vehicleTypeStr = match.captured(1).trimmed();
471 const MAV_TYPE vehicleType = QGCMAVLink::vehicleTypeFromString(vehicleTypeStr);
472 data.vehicleType = vehicleType;
473 continue;
474 }
475
476 static const QRegularExpression reVersion(uR"(^#\s*Version:\s*([0-9]+(?:\.[0-9]+){0,2})(?:\s+([A-Za-z0-9]+))?\s*$)"_s);
477 match = reVersion.match(line);
478 if (match.hasMatch()) {
479 const QString versionNumber = match.captured(1).trimmed();
480 data.versionNumber = QVersionNumber::fromString(versionNumber);
481
482 const QString versionType = match.captured(2).trimmed();
483 if (versionType.isEmpty()) {
484 data.versionType = FIRMWARE_VERSION_TYPE_OFFICIAL;
485 } else {
486 data.versionType = QGCMAVLink::firmwareVersionTypeFromString(versionType);
487 }
488 continue;
489 }
490
491 static const QRegularExpression reGit(uR"(^#\s*Git Revision:\s*([0-9a-fA-F]+)\s*$)"_s);
492 match = reGit.match(line);
493 if (match.hasMatch()) {
494 data.gitRevision = match.captured(1).trimmed();
495 continue;
496 }
497 }
498
499 return data;
500}
501
503{
504 if (vehicle->isOfflineEditingVehicle()) {
505 const QString offlineParameterFile = offlineEditingParamFile(vehicle);
506 const APMFirmwarePlugin::FirmwareParameterHeader offlineParameterHeader = _parseParamsHeader(offlineParameterFile);
507 if (offlineParameterHeader.vehicleType != MAV_TYPE_GENERIC) {
508 vehicle->setFirmwareVersion(offlineParameterHeader.versionNumber.majorVersion(), offlineParameterHeader.versionNumber.minorVersion(), offlineParameterHeader.versionNumber.microVersion());
509 }
510 } else {
511 initializeStreamRates(vehicle);
512 }
513
514 if (SettingsManager::instance()->videoSettings()->videoSource()->rawValue() == VideoSettings::videoSource3DRSolo) {
515 _soloVideoHandshake();
516 }
517}
518
520{
521 QList<MAV_CMD> supportedCommands = {
522 MAV_CMD_NAV_WAYPOINT,
523 MAV_CMD_NAV_LOITER_UNLIM, MAV_CMD_NAV_LOITER_TURNS, MAV_CMD_NAV_LOITER_TIME,
524 MAV_CMD_NAV_RETURN_TO_LAUNCH,
525 MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT,
526 MAV_CMD_NAV_LOITER_TO_ALT,
527 MAV_CMD_NAV_SPLINE_WAYPOINT,
528 MAV_CMD_NAV_GUIDED_ENABLE,
529 MAV_CMD_NAV_DELAY,
530 MAV_CMD_CONDITION_DELAY, MAV_CMD_CONDITION_DISTANCE, MAV_CMD_CONDITION_YAW,
531 MAV_CMD_DO_SET_MODE,
532 MAV_CMD_DO_JUMP,
533 MAV_CMD_DO_CHANGE_SPEED,
534 MAV_CMD_DO_SET_HOME,
535 MAV_CMD_DO_SET_RELAY, MAV_CMD_DO_REPEAT_RELAY,
536 MAV_CMD_DO_SET_SERVO, MAV_CMD_DO_REPEAT_SERVO,
537 MAV_CMD_DO_LAND_START,
538 MAV_CMD_DO_SET_ROI,
539 MAV_CMD_DO_DIGICAM_CONFIGURE, MAV_CMD_DO_DIGICAM_CONTROL,
540 MAV_CMD_DO_MOUNT_CONTROL,
541 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW,
542 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
543 MAV_CMD_IMAGE_START_CAPTURE, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_CMD_VIDEO_START_CAPTURE, MAV_CMD_VIDEO_STOP_CAPTURE,
544 MAV_CMD_DO_FENCE_ENABLE,
545 MAV_CMD_DO_PARACHUTE,
546 MAV_CMD_DO_INVERTED_FLIGHT,
547 MAV_CMD_DO_GRIPPER,
548 MAV_CMD_DO_GUIDED_LIMITS,
549 MAV_CMD_DO_AUTOTUNE_ENABLE,
550 };
551
552 QList<MAV_CMD> vtolCommands = {
553 MAV_CMD_NAV_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_LAND, MAV_CMD_DO_VTOL_TRANSITION,
554 };
555
556 QList<MAV_CMD> flightCommands = {
557 MAV_CMD_NAV_LAND, MAV_CMD_NAV_TAKEOFF,
558 };
559
560 if (vehicleClass == QGCMAVLink::VehicleClassGeneric) {
561 supportedCommands += vtolCommands;
562 supportedCommands += flightCommands;
563 }
564 if (vehicleClass == QGCMAVLink::VehicleClassVTOL) {
565 supportedCommands += vtolCommands;
566 supportedCommands += flightCommands;
567 } else if (vehicleClass == QGCMAVLink::VehicleClassFixedWing || vehicleClass == QGCMAVLink::VehicleClassMultiRotor) {
568 supportedCommands += flightCommands;
569 }
570
571 if (SettingsManager::instance()->planViewSettings()->useConditionGate()->rawValue().toBool()) {
572 supportedCommands.append(MAV_CMD_CONDITION_GATE);
573 }
574
575 return supportedCommands;
576}
577
579{
580 switch (vehicleClass) {
582 return QStringLiteral(":/json/APM-MavCmdInfoCommon.json");
584 return QStringLiteral(":/json/APM-MavCmdInfoFixedWing.json");
586 return QStringLiteral(":/json/APM-MavCmdInfoMultiRotor.json");
588 return QStringLiteral(":/json/APM-MavCmdInfoVTOL.json");
590 return QStringLiteral(":/json/APM-MavCmdInfoSub.json");
592 return QStringLiteral(":/json/APM-MavCmdInfoRover.json");
593 default:
594 qCWarning(APMFirmwarePluginLog) << "APMFirmwarePlugin::missionCommandOverrides called with bad VehicleClass_t:" << vehicleClass;
595 return QString();
596 }
597}
598
603
605{
606 uint64_t hobbsTimeSeconds = 0;
607
609 Fact *const factFltTime = vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, "STAT_FLTTIME");
610 hobbsTimeSeconds = static_cast<uint64_t>(factFltTime->rawValue().toUInt());
611 qCDebug(APMFirmwarePluginLog) << "Hobbs Meter raw Ardupilot(s):" << "(" << hobbsTimeSeconds << ")";
612 }
613
614 const int hours = hobbsTimeSeconds / 3600;
615 const int minutes = (hobbsTimeSeconds % 3600) / 60;
616 const int seconds = hobbsTimeSeconds % 60;
617 const QString timeStr = QString::asprintf("%04d:%02d:%02d", hours, minutes, seconds);
618 qCDebug(APMFirmwarePluginLog) << "Hobbs Meter string:" << timeStr;
619 return timeStr;
620}
621
622bool APMFirmwarePlugin::hasGripper(const Vehicle *vehicle) const
623{
625 const bool _hasGripper = ((vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, QStringLiteral("GRIP_ENABLE"))->rawValue().toInt()) == 1);
626 return _hasGripper;
627 }
628 return false;
629}
630
631const QVariantList &APMFirmwarePlugin::toolIndicators(const Vehicle *vehicle)
632{
633 if (_toolIndicatorList.isEmpty()) {
634 // First call the base class to get the standard QGC list
635 _toolIndicatorList = FirmwarePlugin::toolIndicators(vehicle);
636
637 // Add the forwarding support indicator
638 _toolIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/FirmwarePlugin/APM/APMSupportForwardingIndicator.qml")));
639 }
640
641 return _toolIndicatorList;
642}
643
644bool APMFirmwarePlugin::isGuidedMode(const Vehicle *vehicle) const
645{
646 return (vehicle->flightMode() == guidedFlightMode());
647}
648
653
658
663
668
669void APMFirmwarePlugin::_soloVideoHandshake()
670{
671 QTcpSocket *const socket = new QTcpSocket(this);
672
673 (void) QObject::connect(socket, &QAbstractSocket::errorOccurred, this, &APMFirmwarePlugin::_artooSocketError);
674 socket->connectToHost(_artooIP, _artooVideoHandshakePort);
675}
676
677void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketError)
678{
679 QGC::showAppMessage(tr("Error during Solo video link setup: %1").arg(socketError));
680}
681
682QString APMFirmwarePlugin::_vehicleClassToString(QGCMAVLink::VehicleClass_t vehicleClass) const
683{
684 switch (vehicleClass) {
686 return QStringLiteral("Copter");
689 return QStringLiteral("Plane");
691 return QStringLiteral("Rover");
693 return QStringLiteral("Sub");
694 default:
695 qCWarning(APMFirmwarePluginLog) << Q_FUNC_INFO << "called with bad VehicleClass_t:" << vehicleClass;
696 return QString();
697 }
698}
699
701{
702 const QGCMAVLink::VehicleClass_t vehicleClass = QGCMAVLink::vehicleClass(vehicle->vehicleType());
703
704 const QString vehicleName = _vehicleClassToString(vehicleClass);
705 if (vehicleName.isEmpty()) {
706 qCWarning(APMFirmwarePluginLog) << Q_FUNC_INFO << "called with bad VehicleClass_t:" << vehicleClass;
707 return QString();
708 }
709
710 int currMajor = vehicle->firmwareMajorVersion();
711 int currMinor = vehicle->firmwareMinorVersion();
712
713 // Find next newest version available
714 while ((currMajor >= 4) && (currMinor > 0)) {
715 const QString file = QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.%1.%2.%3.json").arg(vehicleName).arg(currMajor).arg(currMinor);
716 if (QFileInfo::exists(file)) {
717 return file;
718 }
719 currMinor--;
720 if (currMinor == 0) {
721 currMinor = 10;
722 currMajor--;
723 }
724 }
725
726 // Fallback: use oldest version available
727 for (int i = 0; i < 10; i++) {
728 const QString file = QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.%1.%2.%3.json").arg(vehicleName).arg(4).arg(i);
729 if (QFileInfo::exists(file)) {
730 return file;
731 }
732 }
733
734 qCWarning(APMFirmwarePluginLog) << Q_FUNC_INFO << "Meta Data File Not Found";
735 return QString();
736}
737
738void APMFirmwarePlugin::setGuidedMode(Vehicle *vehicle, bool guidedMode) const
739{
740 if (guidedMode) {
742 } else {
743 pauseVehicle(vehicle);
744 }
745}
746
751
755
756static void _MAV_CMD_DO_REPOSITION_ResultHandler(void *resultHandlerData, int /*compId*/, const mavlink_command_ack_t &ack, Vehicle::MavCmdResultFailureCode_t /*failureCode*/)
757{
758 auto *data = static_cast<MAV_CMD_DO_REPOSITION_HandlerData*>(resultHandlerData);
759 auto *vehicle = data->vehicle;
760 auto *instanceData = qobject_cast<APMFirmwarePluginInstanceData*>(vehicle->firmwarePluginInstanceData());
761
762 if (instanceData->MAV_CMD_DO_REPOSITION_supported ||
763 instanceData->MAV_CMD_DO_REPOSITION_unsupported) {
764 // we never change out minds once set
765 goto out;
766 }
767
768 instanceData->MAV_CMD_DO_REPOSITION_supported = (ack.result == MAV_RESULT_ACCEPTED);
769 instanceData->MAV_CMD_DO_REPOSITION_unsupported = (ack.result == MAV_RESULT_UNSUPPORTED);
770
771out:
772 delete data;
773}
774
775bool APMFirmwarePlugin::guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius) const
776{
777 if (qIsNaN(vehicle->altitudeRelative()->rawValue().toDouble())) {
778 QGC::showAppMessage(QStringLiteral("Unable to go to location, vehicle position not known."));
779 return false;
780 }
781
782 // attempt to use MAV_CMD_DO_REPOSITION to move vehicle. If that
783 // comes back as unsupported, try using the old system of sending
784 // through mission items with custom "current" field values.
785 auto *instanceData = qobject_cast<APMFirmwarePluginInstanceData*>(vehicle->firmwarePluginInstanceData());
786
787 // if we know it is supported or we don't know for sure it is
788 // unsupported then send the command:
789 if (instanceData) {
790 if (instanceData->MAV_CMD_DO_REPOSITION_supported || !instanceData->MAV_CMD_DO_REPOSITION_unsupported) {
791 auto *result_handler_data = new MAV_CMD_DO_REPOSITION_HandlerData {
792 vehicle
793 };
794
795 Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {};
797 handlerInfo.resultHandlerData = result_handler_data;
798
799 // For copters, this parameter specifies a yaw heading (heading
800 // reference defined in Bitmask field). NaN to use the current
801 // system yaw heading mode (e.g. yaw towards next waypoint, yaw to
802 // home, etc.).
803 // For planes it indicates loiter direction (0: clockwise, 1:
804 // counter clockwise)
805 float yawParam = NAN;
806 if (forwardFlightLoiterRadius > 0) {
807 yawParam = 0.0f;
808 } else if (forwardFlightLoiterRadius < 0) {
809 yawParam = 1.0f;
810 }
811
813 &handlerInfo,
814 vehicle->defaultComponentId(),
815 MAV_CMD_DO_REPOSITION,
816 MAV_FRAME_GLOBAL,
817 -1.0f,
818 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
819 static_cast<float>(abs(forwardFlightLoiterRadius)),
820 yawParam,
821 gotoCoord.latitude(),
822 gotoCoord.longitude(),
823 vehicle->altitudeAMSL()->rawValue().toFloat()
824 );
825 }
826 if (instanceData->MAV_CMD_DO_REPOSITION_supported) {
827 // no need to fall back
828 return true;
829 }
830 }
831
832 setGuidedMode(vehicle, true);
833
834 QGeoCoordinate coordWithAltitude = gotoCoord;
835 coordWithAltitude.setAltitude(vehicle->altitudeRelative()->rawValue().toDouble());
836 vehicle->missionManager()->writeArduPilotGuidedMissionItem(coordWithAltitude, false /* altChangeOnly */);
837
838 return true;
839}
840
841void APMFirmwarePlugin::guidedModeRTL(Vehicle *vehicle, bool smartRTL) const
842{
844}
845
846void APMFirmwarePlugin::guidedModeChangeAltitude(Vehicle *vehicle, double altitudeChange, bool pauseVehicle)
847{
848 if (qIsNaN(vehicle->altitudeRelative()->rawValue().toDouble())) {
849 QGC::showAppMessage(tr("Unable to change altitude, vehicle altitude not known."));
850 return;
851 }
852
854 QGC::showAppMessage(tr("Unable to pause vehicle."));
855 return;
856 }
857
858 if (abs(altitudeChange) < 0.01) {
859 // This prevents unecessary changes to Guided mode when the users selects pause and doesn't really touch the altitude slider
860 return;
861 }
862
863 setGuidedMode(vehicle, true);
864
865 SharedLinkInterfacePtr sharedLink = vehicle->vehicleLinkManager()->primaryLink().lock();
866 if (sharedLink) {
867 mavlink_message_t msg{};
868 mavlink_set_position_target_local_ned_t cmd{};
869
870 (void) memset(&cmd, 0, sizeof(cmd));
871
872 cmd.target_system = static_cast<uint8_t>(vehicle->id());
873 cmd.target_component = static_cast<uint8_t>(vehicle->defaultComponentId());
874 cmd.coordinate_frame = MAV_FRAME_LOCAL_OFFSET_NED;
875 cmd.type_mask = 0xFFF8; // Only x/y/z valid
876 cmd.x = 0.0f;
877 cmd.y = 0.0f;
878 cmd.z = static_cast<float>(-(altitudeChange));
879
880 mavlink_msg_set_position_target_local_ned_encode_chan(
881 static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
882 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
883 sharedLink->mavlinkChannel(),
884 &msg,
885 &cmd
886 );
887
888 (void) vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
889 }
890}
891
893{
894 // Use noremap. to bypass remap and check for specific parameter names directly,
895 // since the old and new parameters have different units.
896 return vehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, QStringLiteral("noremap.WP_SPD"))
897 || vehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, QStringLiteral("noremap.WPNAV_SPEED"));
898}
899
901{
902 // Use noremap. to bypass remap and check for specific parameter names directly,
903 // since the old and new parameters have different units.
904
905 // 4.7+: WP_SPD is in m/s
906 if (vehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, QStringLiteral("noremap.WP_SPD"))) {
907 return vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, QStringLiteral("noremap.WP_SPD"))->rawValue().toDouble();
908 }
909
910 // pre-4.7: WPNAV_SPEED is in cm/s
911 if (vehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, QStringLiteral("noremap.WPNAV_SPEED"))) {
912 return vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, QStringLiteral("noremap.WPNAV_SPEED"))->rawValue().toDouble() * 0.01;
913 }
914
916}
917
919{
920 vehicle->sendMavCommand(
921 vehicle->defaultComponentId(),
922 MAV_CMD_DO_CHANGE_SPEED,
923 true, // show error is fails
924 1, // 0: airspeed, 1: groundspeed
925 static_cast<float>(groundspeed), // groundspeed setpoint
926 -1, // throttle
927 0, // 0: absolute speed, 1: relative to current
928 NAN, NAN, NAN // param 5-7 unused
929 );
930}
931
932void APMFirmwarePlugin::guidedModeTakeoff(Vehicle *vehicle, double altitudeRel) const
933{
934 _guidedModeTakeoff(vehicle, altitudeRel);
935}
936
937void APMFirmwarePlugin::guidedModeChangeHeading(Vehicle *vehicle, const QGeoCoordinate &headingCoord) const
938{
940 QGC::showAppMessage(tr("Vehicle does not support guided rotate"));
941 return;
942 }
943
944 const float degrees = vehicle->coordinate().azimuthTo(headingCoord);
945 const float currentHeading = vehicle->heading()->rawValue().toFloat();
946
947 float diff = degrees - currentHeading;
948 if (diff < -180) {
949 diff += 360;
950 } else if (diff > 180) {
951 diff -= 360;
952 }
953
954 const int8_t direction = (diff > 0) ? 1 : -1;
955 diff = qAbs(diff);
956
957 float maxYawRate = 0.f;
958 static const QString maxYawRateParam = QStringLiteral("ATC_RATE_Y_MAX");
960 maxYawRate = vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, maxYawRateParam)->rawValue().toFloat();
961 }
962
963 vehicle->sendMavCommand(
964 vehicle->defaultComponentId(),
965 MAV_CMD_CONDITION_YAW,
966 true,
967 diff,
968 maxYawRate,
969 direction,
970 true
971 );
972}
973
975{
976 double minTakeoffAlt = 0;
977
978 // Use noremap. to bypass remap and check for specific parameter names directly,
979 // since the old and new parameters have different units.
980
981 if (vehicle->vtol()) {
982 // 4.7+: Q_PILOT_TKO_ALT_M (meters)
983 if (vehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, QStringLiteral("noremap.Q_PILOT_TKO_ALT_M"))) {
984 minTakeoffAlt = vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, QStringLiteral("noremap.Q_PILOT_TKO_ALT_M"))->rawValue().toDouble();
985 } else if (vehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, QStringLiteral("noremap.Q_PILOT_TKOFF_ALT"))) {
986 // pre-4.7: Q_PILOT_TKOFF_ALT (centimeters)
987 minTakeoffAlt = vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, QStringLiteral("noremap.Q_PILOT_TKOFF_ALT"))->rawValue().toDouble() / 100.0;
988 } else if (vehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, QStringLiteral("Q_RTL_ALT"))) {
989 minTakeoffAlt = vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, QStringLiteral("Q_RTL_ALT"))->rawValue().toDouble();
990 }
991 } else {
992 // 4.7+: PILOT_TKO_ALT_M (meters)
993 if (vehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, QStringLiteral("noremap.PILOT_TKO_ALT_M"))) {
994 minTakeoffAlt = vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, QStringLiteral("noremap.PILOT_TKO_ALT_M"))->rawValue().toDouble();
995 } else if (vehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, QStringLiteral("noremap.PILOT_TKOFF_ALT"))) {
996 // pre-4.7: PILOT_TKOFF_ALT (centimeters)
997 minTakeoffAlt = vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, QStringLiteral("noremap.PILOT_TKOFF_ALT"))->rawValue().toDouble() / 100.0;
998 }
999 }
1000
1001 if (minTakeoffAlt == 0) {
1002 minTakeoffAlt = FirmwarePlugin::minimumTakeoffAltitudeMeters(vehicle);
1003 }
1004
1005 return minTakeoffAlt;
1006}
1007
1008bool APMFirmwarePlugin::_guidedModeTakeoff(Vehicle *vehicle, double altitudeRel) const
1009{
1010 if (!vehicle->multiRotor() && !vehicle->vtol()) {
1011 QGC::showAppMessage(tr("Vehicle does not support guided takeoff"));
1012 return false;
1013 }
1014
1015 const double vehicleAltitudeAMSL = vehicle->altitudeAMSL()->rawValue().toDouble();
1016 if (qIsNaN(vehicleAltitudeAMSL)) {
1017 QGC::showAppMessage(tr("Unable to takeoff, vehicle position not known."));
1018 return false;
1019 }
1020
1021 double takeoffAltRel = minimumTakeoffAltitudeMeters(vehicle);
1022 if (!qIsNaN(altitudeRel) && altitudeRel > takeoffAltRel) {
1023 takeoffAltRel = altitudeRel;
1024 }
1025
1027 QGC::showAppMessage(tr("Unable to takeoff: Vehicle failed to change to Guided mode."));
1028 return false;
1029 }
1030
1031 if (!_armVehicleAndValidate(vehicle)) {
1032 QGC::showAppMessage(tr("Unable to takeoff: Vehicle failed to arm."));
1033 return false;
1034 }
1035
1036 vehicle->sendMavCommand(
1037 vehicle->defaultComponentId(),
1038 MAV_CMD_NAV_TAKEOFF,
1039 true, // show error
1040 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f,
1041 static_cast<float>(takeoffAltRel) // Relative altitude
1042 );
1043
1044 return true;
1045}
1046
1048{
1049 if (vehicle->flying()) {
1050 QGC::showAppMessage(tr("Unable to start takeoff: Vehicle is already in the air."));
1051 return;
1052 }
1053
1054 if (!vehicle->armed()) {
1056 QGC::showAppMessage(tr("Unable to start takeoff: Vehicle failed to change to Takeoff mode."));
1057 return;
1058 }
1059
1060 if (!_armVehicleAndValidate(vehicle)) {
1061 QGC::showAppMessage(tr("Unable to start takeoff: Vehicle failed to arm."));
1062 return;
1063 }
1064 }
1065}
1066
1068{
1069 if (vehicle->flying()) {
1070 // Vehicle already in the air, we just need to switch to auto
1072 QGC::showAppMessage(tr("Unable to start mission: Vehicle failed to change to Auto mode."));
1073 }
1074 return;
1075 }
1076
1077 if (!vehicle->armed()) {
1078 // First switch to flight mode we can arm from
1079 // In Ardupilot for vtols and airplanes we need to set the mode to auto and then arm, otherwise if arming in guided
1080 // If the vehicle has tilt rotors, it will arm them in forward flight position, being dangerous.
1081 if (vehicle->fixedWing()) {
1083 QGC::showAppMessage(tr("Unable to start mission: Vehicle failed to change to Auto mode."));
1084 return;
1085 }
1086 } else {
1088 QGC::showAppMessage(tr("Unable to start mission: Vehicle failed to change to Guided mode."));
1089 return;
1090 }
1091 }
1092
1093 if (!_armVehicleAndValidate(vehicle)) {
1094 QGC::showAppMessage(tr("Unable to start mission: Vehicle failed to arm."));
1095 return;
1096 }
1097 }
1098
1099 // For non aircraft vehicles, we would be in guided mode, so we need to send the mission start command
1100 if (!vehicle->fixedWing()) {
1101 vehicle->sendMavCommand(vehicle->defaultComponentId(), MAV_CMD_MISSION_START, true /*show error */);
1102 }
1103}
1104
1105QString APMFirmwarePlugin::_getLatestVersionFileUrl(Vehicle *vehicle) const
1106{
1107 const static QString baseUrl("http://firmware.ardupilot.org/%1/stable/Pixhawk1/git-version.txt");
1108
1109 if (qobject_cast<ArduPlaneFirmwarePlugin*>(vehicle->firmwarePlugin())) {
1110 return baseUrl.arg("Plane");
1111 } else if (qobject_cast<ArduRoverFirmwarePlugin*>(vehicle->firmwarePlugin())) {
1112 return baseUrl.arg("Rover");
1113 } else if (qobject_cast<ArduSubFirmwarePlugin*>(vehicle->firmwarePlugin())) {
1114 return baseUrl.arg("Sub");
1115 } else if (qobject_cast<ArduCopterFirmwarePlugin*>(vehicle->firmwarePlugin())) {
1116 return baseUrl.arg("Copter");
1117 } else {
1118 qCWarning(APMFirmwarePluginLog) << "APMFirmwarePlugin::_getLatestVersionFileUrl Unknown vehicle firmware type" << vehicle->vehicleType();
1119 return QString();
1120 }
1121}
1122
1123void APMFirmwarePlugin::_handleRCChannels(Vehicle *vehicle, mavlink_message_t *message)
1124{
1125 SharedLinkInterfacePtr sharedLink = vehicle->vehicleLinkManager()->primaryLink().lock();
1126 if (sharedLink) {
1127 mavlink_rc_channels_t channels{};
1128
1129 mavlink_msg_rc_channels_decode(message, &channels);
1130 //-- Ardupilot uses 0-254 to indicate 0-100% where QGC expects 0-100
1131 // As per mavlink specs, 255 means invalid, we must leave it like that for indicators to hide if no rssi data
1132 if (channels.rssi && (channels.rssi != 255)) {
1133 channels.rssi = static_cast<uint8_t>((static_cast<double>(channels.rssi) / 254.0) * 100.0);
1134 }
1135 mavlink_msg_rc_channels_encode_chan(
1136 static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
1137 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
1138 sharedLink->mavlinkChannel(),
1139 message,
1140 &channels
1141 );
1142 }
1143}
1144
1145void APMFirmwarePlugin::_handleRCChannelsRaw(Vehicle *vehicle, mavlink_message_t *message)
1146{
1147 SharedLinkInterfacePtr sharedLink = vehicle->vehicleLinkManager()->primaryLink().lock();
1148 if (sharedLink) {
1149 mavlink_rc_channels_raw_t channels{};
1150
1151 mavlink_msg_rc_channels_raw_decode(message, &channels);
1152 //-- Ardupilot uses 0-255 to indicate 0-100% where QGC expects 0-100
1153 if (channels.rssi) {
1154 channels.rssi = static_cast<uint8_t>((static_cast<double>(channels.rssi) / 255.0) * 100.0);
1155 }
1156 mavlink_msg_rc_channels_raw_encode_chan(
1157 static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
1158 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
1159 sharedLink->mavlinkChannel(),
1160 message,
1161 &channels
1162 );
1163 }
1164}
1165
1166void APMFirmwarePlugin::sendGCSMotionReport(Vehicle *vehicle, const FollowMe::GCSMotionReport &motionReport, uint8_t estimationCapabilities) const
1167{
1168 if (!vehicle->homePosition().isValid()) {
1169 static bool sentOnce = false;
1170 if (!sentOnce) {
1171 sentOnce = true;
1172 QGC::showAppMessage(QStringLiteral("Follow failed: Home position not set."));
1173 }
1174 return;
1175 }
1176
1177 if (!(estimationCapabilities & (FollowMe::POS | FollowMe::VEL | FollowMe::HEADING))) {
1178 static bool sentOnce = false;
1179 if (!sentOnce) {
1180 sentOnce = true;
1181 qCWarning(APMFirmwarePluginLog) << "estimateCapabilities" << estimationCapabilities;
1182 QGC::showAppMessage(QStringLiteral("Follow failed: Ground station cannot provide required position information."));
1183 }
1184 return;
1185 }
1186
1187 SharedLinkInterfacePtr sharedLink = vehicle->vehicleLinkManager()->primaryLink().lock();
1188 if (!sharedLink) {
1189 return;
1190 }
1191
1192 const mavlink_global_position_int_t globalPositionInt = {
1193 static_cast<uint32_t>(qgcApp()->msecsSinceBoot()), /*< [ms] Timestamp (time since system boot).*/
1194 motionReport.lat_int, /*< [degE7] Latitude, expressed*/
1195 motionReport.lon_int, /*< [degE7] Longitude, expressed*/
1196 static_cast<int32_t>(vehicle->homePosition().altitude() * 1000), /*< [mm] Altitude (MSL).*/
1197 static_cast<int32_t>(0), /*< [mm] Altitude above home*/
1198 static_cast<int16_t>(motionReport.vxMetersPerSec * 100), /*< [cm/s] Ground X Speed (Latitude, positive north)*/
1199 static_cast<int16_t>(motionReport.vyMetersPerSec * 100), /*< [cm/s] Ground Y Speed (Longitude, positive east)*/
1200 static_cast<int16_t>(motionReport.vzMetersPerSec * 100), /*< [cm/s] Ground Z Speed (Altitude, positive down)*/
1201 static_cast<uint16_t>(motionReport.headingDegrees * 100.0) /*< [cdeg] Vehicle heading (yaw angle)*/
1202 };
1203
1204 mavlink_message_t message{};
1205 (void) mavlink_msg_global_position_int_encode_chan(
1206 static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
1207 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
1208 sharedLink->mavlinkChannel(),
1209 &message,
1210 &globalPositionInt
1211 );
1212 (void) vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), message);
1213}
1214
1215uint8_t APMFirmwarePlugin::_reencodeMavlinkChannel()
1216{
1217 // This mutex is only to guard against a race on allocating the channel id
1218 // if two firmware plugins are created simultaneously from different threads
1219 //
1220 // Use of the allocated channel should be guarded by the mutex returned from
1221 // _reencodeMavlinkChannelMutex()
1222 //
1223 static QMutex _channelMutex{};
1224 _channelMutex.lock();
1225 static uint8_t channel{LinkManager::invalidMavlinkChannel()};
1226 if (LinkManager::invalidMavlinkChannel() == channel) {
1228 }
1229 _channelMutex.unlock();
1230 return channel;
1231}
1232
1233QMutex &APMFirmwarePlugin::_reencodeMavlinkChannelMutex()
1234{
1235 static QMutex _mutex{};
1236 return _mutex;
1237}
1238
1240{
1241 const QString airspeedMax("AIRSPEED_MAX");
1242
1244 return vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, airspeedMax)->rawValue().toDouble();
1245 }
1246
1248}
1249
1251{
1252 const QString airspeedMin("AIRSPEED_MIN");
1253
1255 return vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, airspeedMin)->rawValue().toDouble();
1256 }
1257
1259}
1260
1266
1268{
1269 vehicle->sendMavCommand(
1270 vehicle->defaultComponentId(),
1271 MAV_CMD_DO_CHANGE_SPEED,
1272 true, // show error is fails
1273 0, // 0: airspeed, 1: groundspeed
1274 static_cast<float>(airspeed_equiv), // speed setpoint
1275 -1, // throttle, no change
1276 0 // 0: absolute speed, 1: relative to current
1277 ); // param 5-7 unused
1278}
1279
1280void APMFirmwarePlugin::_setBaroGndTemp(Vehicle* vehicle, qreal temp)
1281{
1282 if (!vehicle) {
1283 return;
1284 }
1285
1286 const QString bareGndTemp("BARO_GND_TEMP");
1287
1289 Fact* const param = vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, bareGndTemp);
1290 param->setRawValue(temp);
1291 }
1292}
1293
1294void APMFirmwarePlugin::_setBaroAltOffset(Vehicle* vehicle, qreal offset)
1295{
1296 if (!vehicle) {
1297 return;
1298 }
1299
1300 const QString baroAltOffset("BARO_ALT_OFFSET");
1301
1303 Fact* const param = vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, baroAltOffset);
1304 param->setRawValue(offset);
1305 }
1306}
1307
1308#define ALT_METERS (145366.45 * 0.3048)
1309#define ALT_EXP (1. / 5.225)
1310#define SEA_PRESSURE 101325.
1311#define CELSIUS_TO_KELVIN(celsius) (celsius + 273.15)
1312#define ALT_OFFSET_P(pressure) (1. - pow((pressure / SEA_PRESSURE), ALT_EXP))
1313#define ALT_OFFSET_PT(pressure,temperature) ((ALT_OFFSET_P(pressure) * CELSIUS_TO_KELVIN(temperature)) / 0.0065)
1314
1315qreal APMFirmwarePlugin::calcAltOffsetPT(uint32_t atmospheric1, qreal temperature1, uint32_t atmospheric2, qreal temperature2)
1316{
1317 const qreal alt1 = ALT_OFFSET_PT(atmospheric1, temperature1);
1318 const qreal alt2 = ALT_OFFSET_PT(atmospheric2, temperature2);
1319 const qreal offset = alt1 - alt2;
1320 return offset;
1321}
1322
1323qreal APMFirmwarePlugin::calcAltOffsetP(uint32_t atmospheric1, uint32_t atmospheric2)
1324{
1325 const qreal alt1 = ALT_OFFSET_P(atmospheric1) * ALT_METERS;
1326 const qreal alt2 = ALT_OFFSET_P(atmospheric2) * ALT_METERS;
1327 const qreal offset = alt1 - alt2;
1328 return offset;
1329}
1330
1331QPair<QMetaObject::Connection,QMetaObject::Connection> APMFirmwarePlugin::startCompensatingBaro(Vehicle *vehicle)
1332{
1333 // TODO: Running Average?
1334 const QMetaObject::Connection baroPressureUpdater = QObject::connect(QGCSensors::QGCPressure::instance(), &QGCSensors::QGCPressure::pressureUpdated, vehicle, [vehicle](qreal pressure, qreal temperature){
1335 if (!vehicle || !vehicle->flying()) {
1336 return;
1337 }
1338
1339 if (qFuzzyIsNull(pressure)) {
1340 return;
1341 }
1342
1343 const qreal initialPressure = vehicle->getInitialGCSPressure();
1344 if (qFuzzyIsNull(initialPressure)) {
1345 return;
1346 }
1347
1348 const qreal initialTemperature = vehicle->getInitialGCSTemperature();
1349
1350 qreal offset = 0.;
1351 if (!qFuzzyIsNull(temperature) && !qFuzzyIsNull(initialTemperature)) {
1352 offset = APMFirmwarePlugin::calcAltOffsetPT(initialPressure, initialTemperature, pressure, temperature);
1353 } else {
1354 offset = APMFirmwarePlugin::calcAltOffsetP(initialPressure, pressure);
1355 }
1356
1357 APMFirmwarePlugin::_setBaroAltOffset(vehicle, offset);
1358 });
1359
1360 const QMetaObject::Connection baroTempUpdater = connect(QGCSensors::QGCAmbientTemperature::instance(), &QGCSensors::QGCAmbientTemperature::temperatureUpdated, vehicle, [vehicle](qreal temperature){
1361 if (!vehicle || !vehicle->flying()) {
1362 return;
1363 }
1364
1365 if (qFuzzyIsNull(temperature)) {
1366 return;
1367 }
1368
1369 APMFirmwarePlugin::_setBaroGndTemp(vehicle, temperature);
1370 });
1371
1372 return QPair<QMetaObject::Connection,QMetaObject::Connection>(baroPressureUpdater, baroTempUpdater);
1373}
1374
1375bool APMFirmwarePlugin::stopCompensatingBaro(const Vehicle *vehicle, QPair<QMetaObject::Connection,QMetaObject::Connection> updaters)
1376{
1377 Q_UNUSED(vehicle);
1378 /*if (!vehicle) {
1379 return false;
1380 }*/
1381
1382 bool result = false;
1383
1384 if (updaters.first) {
1385 result |= QObject::disconnect(updaters.first);
1386 }
1387
1388 if (updaters.second) {
1389 result |= QObject::disconnect(updaters.second);
1390 }
1391
1392 return result;
1393}
1394
1395QVariant APMFirmwarePlugin::expandedToolbarIndicatorSource(const Vehicle* vehicle, const QString& indicatorName) const
1396{
1397 if (indicatorName == "Battery") {
1398 return QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/FirmwarePlugin/APM/APMBatteryIndicator.qml"));
1399 } else if (indicatorName == "FlightMode" && vehicle->multiRotor()) {
1400 return QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/FirmwarePlugin/APM/APMFlightModeIndicator.qml"));
1401 } else if (indicatorName == "MainStatus") {
1402 return QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/FirmwarePlugin/APM/APMMainStatusIndicator.qml"));
1403 }
1404
1405 return QVariant();
1406}
static void _MAV_CMD_DO_REPOSITION_ResultHandler(void *resultHandlerData, int, const mavlink_command_ack_t &ack, Vehicle::MavCmdResultFailureCode_t)
QList< FirmwareFlightMode > FlightModeList
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
mavlink_status_t * mavlink_get_channel_status(uint8_t chan)
Definition QGCMAVLink.cc:53
#define qgcApp()
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
struct __mavlink_command_ack_t mavlink_command_ack_t
struct param_union mavlink_param_union_t
This is the AutoPilotPlugin implementation for the MAV_AUTOPILOT_ARDUPILOT type.
This is the base class for all stack specific APM firmware plugins.
bool isGuidedMode(const Vehicle *vehicle) const override
Returns whether the vehicle is in guided mode or not.
QVariant expandedToolbarIndicatorSource(const Vehicle *vehicle, const QString &indicatorName) const override
void setGuidedMode(Vehicle *vehicle, bool guidedMode) const override
Set guided flight mode.
QString flightMode(uint8_t base_mode, uint32_t custom_mode) const override
QString rtlFlightMode() const override
Returns the flight mode for RTL.
bool setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const override
static qreal calcAltOffsetPT(uint32_t atmospheric1, qreal temperature1, uint32_t atmospheric2, qreal temperature2)
QString getHobbsMeter(Vehicle *vehicle) const override
gets hobbs meter from autopilot. This should be reimplmeented for each firmware
void sendGCSMotionReport(Vehicle *vehicle, const FollowMe::GCSMotionReport &motionReport, uint8_t estimatationCapabilities) const override
Sends the appropriate mavlink message for follow me support.
bool fixedWingAirSpeedLimitsAvailable(Vehicle *vehicle) const override
bool guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius) const override
static QPair< QMetaObject::Connection, QMetaObject::Connection > startCompensatingBaro(Vehicle *vehicle)
void startMission(Vehicle *vehicle) const override
Command the vehicle to start the mission.
virtual void initializeStreamRates(Vehicle *vehicle)
const QString _guidedFlightMode
QString missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const override
void guidedModeChangeGroundSpeedMetersSecond(Vehicle *vehicle, double speed) const override
void guidedModeChangeHeading(Vehicle *vehicle, const QGeoCoordinate &headingCoord) const override
Command vehicle to rotate towards specified location.
bool hasGripper(const Vehicle *vehicle) const override
double minimumTakeoffAltitudeMeters(Vehicle *vehicle) const override
QStringList flightModes(Vehicle *vehicle) const override
void guidedModeRTL(Vehicle *vehicle, bool smartRTL) const override
Command vehicle to return to launch.
bool adjustIncomingMavlinkMessage(Vehicle *vehicle, mavlink_message_t *message) override
static bool stopCompensatingBaro(const Vehicle *vehicle, QPair< QMetaObject::Connection, QMetaObject::Connection > updaters)
void guidedModeTakeoff(Vehicle *vehicle, double altitudeRel) const override
Command vehicle to takeoff from current location to the specified height.
double minimumEquivalentAirspeed(Vehicle *vehicle) const override
void startTakeoff(Vehicle *vehicle) const override
Command the vehicle to start a takeoff.
void adjustOutgoingMavlinkMessageThreadSafe(Vehicle *vehicle, LinkInterface *outgoingLink, mavlink_message_t *message) override
ParameterMetaData * _createParameterMetaData() override
QString smartRTLFlightMode() const override
Returns the flight mode for Smart RTL.
const QString _autoFlightMode
double maximumEquivalentAirspeed(Vehicle *vehicle) const override
QString missionFlightMode() const override
Returns the flight mode for running missions.
void guidedModeChangeAltitude(Vehicle *vehicle, double altitudeChange, bool pauseVehicle) override
bool mulirotorSpeedLimitsAvailable(Vehicle *vehicle) const override
QList< MAV_CMD > supportedMissionCommands(QGCMAVLink::VehicleClass_t vehicleClass) const override
List of supported mission commands. Empty list for all commands supported.
const QString _smartRtlFlightMode
double maximumHorizontalSpeedMultirotorMetersSecond(Vehicle *vehicle) const override
bool isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) const override
void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle *vehicle, double airspeed_equiv) const override
static qreal calcAltOffsetP(uint32_t atmospheric1, uint32_t atmospheric2)
AutoPilotPlugin * autopilotPlugin(Vehicle *vehicle) const override
virtual QString guidedFlightMode() const
const QVariantList & toolIndicators(const Vehicle *vehicle) override
QString _internalParameterMetaDataFile(const Vehicle *vehicle) const override
void pauseVehicle(Vehicle *vehicle) const override
void initializeVehicle(Vehicle *vehicle) override
Called when Vehicle is first created to perform any firmware specific setup.
const QString _rtlFlightMode
The AutoPilotPlugin class is an abstract base class which represents the methods and objects which ar...
A Fact is used to hold a single value within the system.
Definition Fact.h:17
void setRawValue(const QVariant &value)
Definition Fact.cc:128
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
The FirmwarePlugin class represents the methods and objects which are specific to a certain Firmware ...
virtual QString pauseFlightMode() const
Returns The flight mode which indicates the vehicle is paused.
FlightModeList _flightModeList
virtual double minimumEquivalentAirspeed(Vehicle *) const
virtual const QVariantList & toolIndicators(const Vehicle *vehicle)
FirmwareCapabilities
Set of optional capabilites which firmware may support.
@ ChangeHeadingCapability
Vehicle supports changing heading at current location.
@ GuidedTakeoffCapability
Vehicle supports guided takeoff.
@ TakeoffVehicleCapability
Vehicle supports taking off.
@ GuidedModeCapability
Vehicle supports guided mode commands.
@ SetFlightModeCapability
FirmwarePlugin::setFlightMode method is supported.
@ ROIModeCapability
Vehicle supports ROI (both in Fly guided mode and from Plan creation)
@ PauseVehicleCapability
Vehicle supports pausing at current location.
virtual double maximumEquivalentAirspeed(Vehicle *) const
bool _setFlightModeAndValidate(Vehicle *vehicle, const QString &flightMode) const
virtual uint32_t _convertToCustomFlightModeEnum(uint32_t val) const
bool _armVehicleAndValidate(Vehicle *vehicle) const
virtual QString takeOffFlightMode() const
Returns the flight mode for TakeOff.
FlightModeCustomModeMap _modeEnumToString
virtual QString offlineEditingParamFile(Vehicle *) const
Return the resource file which contains the set of params loaded for offline editing.
virtual double maximumHorizontalSpeedMultirotorMetersSecond(Vehicle *) const
virtual double minimumTakeoffAltitudeMeters(Vehicle *) const
@ HEADING
Definition FollowMe.h:38
The link interface defines the interface for all links used to communicate with the ground station ap...
uint8_t mavlinkChannel() const
uint8_t allocateMavlinkChannel()
static LinkManager * instance()
static constexpr uint8_t invalidMavlinkChannel()
static int getComponentId()
static MAVLinkProtocol * instance()
int getSystemId() const
void writeArduPilotGuidedMissionItem(const QGeoCoordinate &gotoCoord, bool altChangeOnly)
bool parameterExists(int componentId, const QString &paramName) const
Fact * getParameter(int componentId, const QString &paramName)
static constexpr int defaultComponentId
static QGCAmbientTemperature * instance()
Definition QGCSensors.cc:15
void temperatureUpdated(qreal temperature)
static QGCPressure * instance()
void pressureUpdated(qreal pressure, qreal temperature)
static SettingsManager * instance()
APMMavlinkStreamRateSettings * apmMavlinkStreamRateSettings() const
static QString getMessageText(const mavlink_message_t &message)
WeakLinkInterfacePtr primaryLink() const
bool sub() const
Definition Vehicle.cc:1748
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
qreal getInitialGCSPressure() const
Definition Vehicle.h:412
QString flightMode() const
Definition Vehicle.cc:1468
bool vtol() const
Definition Vehicle.cc:1763
void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple=true)
Definition Vehicle.cc:1529
QGeoCoordinate homePosition()
Definition Vehicle.cc:1434
bool multiRotor() const
Definition Vehicle.cc:1758
bool flying() const
Definition Vehicle.h:500
void setFirmwarePluginInstanceData(FirmwarePluginInstanceData *firmwarePluginInstanceData)
Definition Vehicle.cc:2527
MAV_TYPE vehicleType() const
Definition Vehicle.h:428
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
Definition Vehicle.h:444
qreal getInitialGCSTemperature() const
Definition Vehicle.h:413
int firmwareMinorVersion() const
Definition Vehicle.h:650
bool isOfflineEditingVehicle() const
Definition Vehicle.h:510
int id() const
Definition Vehicle.h:425
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1389
int defaultComponentId() const
Definition Vehicle.h:670
ParameterManager * parameterManager()
Definition Vehicle.h:573
void _setFlying(bool flying)
Definition Vehicle.cc:1807
void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType=FIRMWARE_VERSION_TYPE_OFFICIAL)
Definition Vehicle.cc:2272
bool fixedWing() const
Definition Vehicle.cc:1738
QGeoCoordinate coordinate()
Definition Vehicle.h:409
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
class FirmwarePluginInstanceData * firmwarePluginInstanceData()
Definition Vehicle.h:685
int firmwareMajorVersion() const
Definition Vehicle.h:649
MissionManager * missionManager()
Definition Vehicle.h:570
static constexpr const char * videoSource3DRSolo
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
Definition AppMessages.cc:9
static constexpr VehicleClass_t VehicleClassGeneric
Callback info bundle for sendMavCommandWithHandler.
MavCmdResultHandler resultHandler
nullptr for no handler