26#include <QtNetwork/QTcpSocket>
28#include <QtCore/QRegularExpression>
29#include <QtCore/QRegularExpressionMatch>
36 _setModeEnumToModeStringMapping({
51 updateAvailableFlightModes(modeList);
73 }
else if (vehicle->
vtol()) {
76 }
else if (vehicle->
sub()) {
80 return (capabilities & available) == capabilities;
86 QStringList flightModesList;
89 flightModesList += mode.mode_name;
92 return flightModesList;
99 if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
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;
122 qCWarning(APMFirmwarePluginLog) <<
"Unknown flight Mode" <<
flightMode;
132 mavlink_param_value_t paramValue;
135 (void) memset(¶mValue, 0,
sizeof(paramValue));
140 mavlink_msg_param_value_decode(message, ¶mValue);
142 switch (paramValue.param_type) {
143 case MAV_PARAM_TYPE_UINT8:
144 paramUnion.param_uint8 =
static_cast<uint8_t
>(paramValue.param_value);
146 case MAV_PARAM_TYPE_INT8:
147 paramUnion.param_int8 =
static_cast<int8_t
>(paramValue.param_value);
149 case MAV_PARAM_TYPE_UINT16:
150 paramUnion.param_uint16 =
static_cast<uint16_t
>(paramValue.param_value);
152 case MAV_PARAM_TYPE_INT16:
153 paramUnion.param_int16 =
static_cast<int16_t
>(paramValue.param_value);
155 case MAV_PARAM_TYPE_UINT32:
156 paramUnion.param_uint32 =
static_cast<uint32_t
>(paramValue.param_value);
158 case MAV_PARAM_TYPE_INT32:
159 paramUnion.param_int32 =
static_cast<int32_t
>(paramValue.param_value);
161 case MAV_PARAM_TYPE_REAL32:
162 paramUnion.param_float = paramValue.param_value;
165 qCCritical(APMFirmwarePluginLog) <<
"Invalid/Unsupported data type used in parameter:" << paramValue.param_type;
168 paramValue.param_value = paramUnion.param_float;
171 const uint8_t channel = _reencodeMavlinkChannel();
172 QMutexLocker reencode_lock{&_reencodeMavlinkChannelMutex()};
175 mavlinkStatusReEncode->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
177 Q_ASSERT(
qgcApp()->thread() == QThread::currentThread());
178 (void) mavlink_msg_param_value_encode_chan(
189 mavlink_param_set_t paramSet;
192 (void) memset(¶mSet, 0,
sizeof(paramSet));
197 mavlink_msg_param_set_decode(message, ¶mSet);
199 if (!_ardupilotComponentMap[paramSet.target_system][paramSet.target_component]) {
204 paramUnion.param_float = paramSet.param_value;
206 switch (paramSet.param_type) {
207 case MAV_PARAM_TYPE_UINT8:
208 paramSet.param_value = paramUnion.param_uint8;
210 case MAV_PARAM_TYPE_INT8:
211 paramSet.param_value = paramUnion.param_int8;
213 case MAV_PARAM_TYPE_UINT16:
214 paramSet.param_value = paramUnion.param_uint16;
216 case MAV_PARAM_TYPE_INT16:
217 paramSet.param_value = paramUnion.param_int16;
219 case MAV_PARAM_TYPE_UINT32:
220 paramSet.param_value = paramUnion.param_uint32;
222 case MAV_PARAM_TYPE_INT32:
223 paramSet.param_value = paramUnion.param_int32;
225 case MAV_PARAM_TYPE_REAL32:
229 qCCritical(APMFirmwarePluginLog) <<
"Invalid/Unsupported data type used in parameter:" << paramSet.param_type;
232 _adjustOutgoingMavlinkMutex.lock();
233 mavlink_msg_param_set_encode_chan(
240 _adjustOutgoingMavlinkMutex.unlock();
249 if (messageText.contains(
"Place vehicle") || messageText.contains(
"Calibration successful")) {
250 _adjustCalibrationMessageSeverity(message);
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);
267 mavlink_heartbeat_t heartbeat{};
268 mavlink_msg_heartbeat_decode(message, &heartbeat);
270 if (message->compid == MAV_COMP_ID_AUTOPILOT1) {
274 if (vehicle->
armed() && ((heartbeat.system_status == MAV_STATE_ACTIVE) || (heartbeat.system_status == MAV_STATE_CRITICAL) || (heartbeat.system_status == MAV_STATE_EMERGENCY))) {
282 _ardupilotComponentMap[message->sysid][message->compid] = heartbeat.autopilot == MAV_AUTOPILOT_ARDUPILOTMEGA;
285 _ardupilotComponentMap[message->sysid][MAV_COMP_ID_UDP_BRIDGE] =
false;
293 if (message->msgid == MAVLINK_MSG_ID_HEARTBEAT) {
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();
302 if (_ardupilotComponentMap[vehicle->
id()][message->compid]) {
303 switch (message->msgid) {
304 case MAVLINK_MSG_ID_PARAM_VALUE:
305 _handleIncomingParamValue(vehicle, message);
307 case MAVLINK_MSG_ID_STATUSTEXT:
308 return _handleIncomingStatusText(vehicle, message);
309 case MAVLINK_MSG_ID_RC_CHANNELS:
310 _handleRCChannels(vehicle, message);
312 case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
313 _handleRCChannelsRaw(vehicle, message);
320 const int reinitStreamsTimeoutSecs = 10;
321 if (instanceData && ((instanceData->lastBatteryStatusTime.secsTo(QTime::currentTime()) > reinitStreamsTimeoutSecs) || (instanceData->lastHomePositionTime.secsTo(QTime::currentTime()) > reinitStreamsTimeoutSecs))) {
330 switch (message->msgid) {
331 case MAVLINK_MSG_ID_PARAM_SET:
332 _handleOutgoingParamSetThreadSafe(vehicle, outgoingLink, message);
342 const uint8_t channel = _reencodeMavlinkChannel();
343 QMutexLocker reencode_lock{&_reencodeMavlinkChannelMutex()};
345 mavlinkStatusReEncode->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
347 mavlink_statustext_t statusText{};
348 mavlink_msg_statustext_decode(message, &statusText);
350 statusText.severity = MAV_SEVERITY_INFO;
352 Q_ASSERT(
qgcApp()->thread() == QThread::currentThread());
353 (void) mavlink_msg_statustext_encode_chan(
362void APMFirmwarePlugin::_adjustCalibrationMessageSeverity(
mavlink_message_t *message)
const
364 mavlink_statustext_t statusText{};
365 mavlink_msg_statustext_decode(message, &statusText);
368 const uint8_t channel = _reencodeMavlinkChannel();
369 QMutexLocker reencode_lock{&_reencodeMavlinkChannelMutex()};
372 mavlinkStatusReEncode->flags |= MAVLINK_STATUS_FLAG_IN_MAVLINK1;
373 statusText.severity = MAV_SEVERITY_INFO;
375 Q_ASSERT(
qgcApp()->thread() == QThread::currentThread());
376 (void) mavlink_msg_statustext_encode_chan(
391 instanceData->lastBatteryStatusTime = instanceData->lastHomePositionTime = QTime::currentTime();
399 struct StreamInfo_s {
400 MAV_DATA_STREAM mavStream;
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() },
414 for (
size_t i = 0; i < std::size(rgStreamInfo); i++) {
415 const StreamInfo_s &streamInfo = rgStreamInfo[i];
417 if (streamInfo.streamRate >= 0) {
418 vehicle->
requestDataStream(streamInfo.mavStream,
static_cast<uint16_t
>(streamInfo.streamRate));
429 vehicle->
sendMavCommand(MAV_COMP_ID_AUTOPILOT1, MAV_CMD_SET_MESSAGE_INTERVAL,
false , MAVLINK_MSG_ID_HOME_POSITION, 1000000 );
433 vehicle->
sendMavCommand(MAV_COMP_ID_AUTOPILOT1, MAV_CMD_SET_MESSAGE_INTERVAL,
false , MAVLINK_MSG_ID_EXTENDED_SYS_STATE, 1000000 );
435 instanceData->lastBatteryStatusTime = instanceData->lastHomePositionTime = QTime::currentTime();
438APMFirmwarePlugin::FirmwareParameterHeader APMFirmwarePlugin::_parseParamsHeader(
const QString &filePath)
440 APMFirmwarePlugin::FirmwareParameterHeader data{};
442 QFile file(filePath);
443 if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
447 QTextStream stream(&file);
448 while (!stream.atEnd()) {
449 const QString line = stream.readLine();
452 if (!line.startsWith(
'#')) {
456 using namespace Qt::StringLiterals;
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();
463 data.firmwareType = firmwareType;
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();
472 data.vehicleType = vehicleType;
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);
482 const QString versionType = match.captured(2).trimmed();
483 if (versionType.isEmpty()) {
484 data.versionType = FIRMWARE_VERSION_TYPE_OFFICIAL;
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();
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());
515 _soloVideoHandshake();
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,
530 MAV_CMD_CONDITION_DELAY, MAV_CMD_CONDITION_DISTANCE, MAV_CMD_CONDITION_YAW,
533 MAV_CMD_DO_CHANGE_SPEED,
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,
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,
548 MAV_CMD_DO_GUIDED_LIMITS,
549 MAV_CMD_DO_AUTOTUNE_ENABLE,
552 QList<MAV_CMD> vtolCommands = {
553 MAV_CMD_NAV_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_LAND, MAV_CMD_DO_VTOL_TRANSITION,
556 QList<MAV_CMD> flightCommands = {
557 MAV_CMD_NAV_LAND, MAV_CMD_NAV_TAKEOFF,
561 supportedCommands += vtolCommands;
562 supportedCommands += flightCommands;
565 supportedCommands += vtolCommands;
566 supportedCommands += flightCommands;
568 supportedCommands += flightCommands;
572 supportedCommands.append(MAV_CMD_CONDITION_GATE);
575 return supportedCommands;
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");
594 qCWarning(APMFirmwarePluginLog) <<
"APMFirmwarePlugin::missionCommandOverrides called with bad VehicleClass_t:" << vehicleClass;
606 uint64_t hobbsTimeSeconds = 0;
610 hobbsTimeSeconds =
static_cast<uint64_t
>(factFltTime->
rawValue().toUInt());
611 qCDebug(APMFirmwarePluginLog) <<
"Hobbs Meter raw Ardupilot(s):" <<
"(" << hobbsTimeSeconds <<
")";
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;
633 if (_toolIndicatorList.isEmpty()) {
638 _toolIndicatorList.append(QVariant::fromValue(QUrl::fromUserInput(
"qrc:/qml/QGroundControl/FirmwarePlugin/APM/APMSupportForwardingIndicator.qml")));
641 return _toolIndicatorList;
669void APMFirmwarePlugin::_soloVideoHandshake()
671 QTcpSocket *
const socket =
new QTcpSocket(
this);
673 (void) QObject::connect(socket, &QAbstractSocket::errorOccurred,
this, &APMFirmwarePlugin::_artooSocketError);
674 socket->connectToHost(_artooIP, _artooVideoHandshakePort);
677void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketError)
684 switch (vehicleClass) {
686 return QStringLiteral(
"Copter");
689 return QStringLiteral(
"Plane");
691 return QStringLiteral(
"Rover");
693 return QStringLiteral(
"Sub");
695 qCWarning(APMFirmwarePluginLog) << Q_FUNC_INFO <<
"called with bad VehicleClass_t:" << vehicleClass;
704 const QString vehicleName = _vehicleClassToString(vehicleClass);
705 if (vehicleName.isEmpty()) {
706 qCWarning(APMFirmwarePluginLog) << Q_FUNC_INFO <<
"called with bad VehicleClass_t:" << vehicleClass;
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)) {
720 if (currMinor == 0) {
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)) {
734 qCWarning(APMFirmwarePluginLog) << Q_FUNC_INFO <<
"Meta Data File Not Found";
759 auto *vehicle = data->vehicle;
762 if (instanceData->MAV_CMD_DO_REPOSITION_supported ||
763 instanceData->MAV_CMD_DO_REPOSITION_unsupported) {
768 instanceData->MAV_CMD_DO_REPOSITION_supported = (ack.result == MAV_RESULT_ACCEPTED);
769 instanceData->MAV_CMD_DO_REPOSITION_unsupported = (ack.result == MAV_RESULT_UNSUPPORTED);
778 QGC::showAppMessage(QStringLiteral(
"Unable to go to location, vehicle position not known."));
790 if (instanceData->MAV_CMD_DO_REPOSITION_supported || !instanceData->MAV_CMD_DO_REPOSITION_unsupported) {
805 float yawParam = NAN;
806 if (forwardFlightLoiterRadius > 0) {
808 }
else if (forwardFlightLoiterRadius < 0) {
815 MAV_CMD_DO_REPOSITION,
818 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
819 static_cast<float>(abs(forwardFlightLoiterRadius)),
821 gotoCoord.latitude(),
822 gotoCoord.longitude(),
826 if (instanceData->MAV_CMD_DO_REPOSITION_supported) {
834 QGeoCoordinate coordWithAltitude = gotoCoord;
858 if (abs(altitudeChange) < 0.01) {
868 mavlink_set_position_target_local_ned_t cmd{};
870 (void) memset(&cmd, 0,
sizeof(cmd));
872 cmd.target_system =
static_cast<uint8_t
>(vehicle->
id());
874 cmd.coordinate_frame = MAV_FRAME_LOCAL_OFFSET_NED;
875 cmd.type_mask = 0xFFF8;
878 cmd.z =
static_cast<float>(-(altitudeChange));
880 mavlink_msg_set_position_target_local_ned_encode_chan(
883 sharedLink->mavlinkChannel(),
922 MAV_CMD_DO_CHANGE_SPEED,
925 static_cast<float>(groundspeed),
934 _guidedModeTakeoff(vehicle, altitudeRel);
944 const float degrees = vehicle->
coordinate().azimuthTo(headingCoord);
947 float diff = degrees - currentHeading;
950 }
else if (diff > 180) {
954 const int8_t direction = (diff > 0) ? 1 : -1;
957 float maxYawRate = 0.f;
958 static const QString maxYawRateParam = QStringLiteral(
"ATC_RATE_Y_MAX");
965 MAV_CMD_CONDITION_YAW,
976 double minTakeoffAlt = 0;
981 if (vehicle->
vtol()) {
1001 if (minTakeoffAlt == 0) {
1005 return minTakeoffAlt;
1008bool APMFirmwarePlugin::_guidedModeTakeoff(
Vehicle *vehicle,
double altitudeRel)
const
1016 if (qIsNaN(vehicleAltitudeAMSL)) {
1022 if (!qIsNaN(altitudeRel) && altitudeRel > takeoffAltRel) {
1023 takeoffAltRel = altitudeRel;
1038 MAV_CMD_NAV_TAKEOFF,
1040 0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f,
1041 static_cast<float>(takeoffAltRel)
1054 if (!vehicle->
armed()) {
1056 QGC::showAppMessage(tr(
"Unable to start takeoff: Vehicle failed to change to Takeoff mode."));
1072 QGC::showAppMessage(tr(
"Unable to start mission: Vehicle failed to change to Auto mode."));
1077 if (!vehicle->
armed()) {
1083 QGC::showAppMessage(tr(
"Unable to start mission: Vehicle failed to change to Auto mode."));
1088 QGC::showAppMessage(tr(
"Unable to start mission: Vehicle failed to change to Guided mode."));
1105QString APMFirmwarePlugin::_getLatestVersionFileUrl(
Vehicle *vehicle)
const
1107 const static QString baseUrl(
"http://firmware.ardupilot.org/%1/stable/Pixhawk1/git-version.txt");
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");
1118 qCWarning(APMFirmwarePluginLog) <<
"APMFirmwarePlugin::_getLatestVersionFileUrl Unknown vehicle firmware type" << vehicle->
vehicleType();
1127 mavlink_rc_channels_t channels{};
1129 mavlink_msg_rc_channels_decode(message, &channels);
1132 if (channels.rssi && (channels.rssi != 255)) {
1133 channels.rssi =
static_cast<uint8_t
>((
static_cast<double>(channels.rssi) / 254.0) * 100.0);
1135 mavlink_msg_rc_channels_encode_chan(
1138 sharedLink->mavlinkChannel(),
1149 mavlink_rc_channels_raw_t channels{};
1151 mavlink_msg_rc_channels_raw_decode(message, &channels);
1153 if (channels.rssi) {
1154 channels.rssi =
static_cast<uint8_t
>((
static_cast<double>(channels.rssi) / 255.0) * 100.0);
1156 mavlink_msg_rc_channels_raw_encode_chan(
1159 sharedLink->mavlinkChannel(),
1169 static bool sentOnce =
false;
1178 static bool sentOnce =
false;
1181 qCWarning(APMFirmwarePluginLog) <<
"estimateCapabilities" << estimationCapabilities;
1182 QGC::showAppMessage(QStringLiteral(
"Follow failed: Ground station cannot provide required position information."));
1192 const mavlink_global_position_int_t globalPositionInt = {
1193 static_cast<uint32_t
>(
qgcApp()->msecsSinceBoot()),
1196 static_cast<int32_t
>(vehicle->
homePosition().altitude() * 1000),
1197 static_cast<int32_t
>(0),
1205 (void) mavlink_msg_global_position_int_encode_chan(
1208 sharedLink->mavlinkChannel(),
1215uint8_t APMFirmwarePlugin::_reencodeMavlinkChannel()
1223 static QMutex _channelMutex{};
1224 _channelMutex.lock();
1229 _channelMutex.unlock();
1233QMutex &APMFirmwarePlugin::_reencodeMavlinkChannelMutex()
1235 static QMutex _mutex{};
1241 const QString airspeedMax(
"AIRSPEED_MAX");
1252 const QString airspeedMin(
"AIRSPEED_MIN");
1271 MAV_CMD_DO_CHANGE_SPEED,
1274 static_cast<float>(airspeed_equiv),
1280void APMFirmwarePlugin::_setBaroGndTemp(
Vehicle* vehicle, qreal temp)
1286 const QString bareGndTemp(
"BARO_GND_TEMP");
1294void APMFirmwarePlugin::_setBaroAltOffset(
Vehicle* vehicle, qreal offset)
1300 const QString baroAltOffset(
"BARO_ALT_OFFSET");
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)
1317 const qreal alt1 = ALT_OFFSET_PT(atmospheric1, temperature1);
1318 const qreal alt2 = ALT_OFFSET_PT(atmospheric2, temperature2);
1319 const qreal offset = alt1 - alt2;
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;
1335 if (!vehicle || !vehicle->
flying()) {
1339 if (qFuzzyIsNull(pressure)) {
1344 if (qFuzzyIsNull(initialPressure)) {
1351 if (!qFuzzyIsNull(temperature) && !qFuzzyIsNull(initialTemperature)) {
1357 APMFirmwarePlugin::_setBaroAltOffset(vehicle, offset);
1361 if (!vehicle || !vehicle->
flying()) {
1365 if (qFuzzyIsNull(temperature)) {
1369 APMFirmwarePlugin::_setBaroGndTemp(vehicle, temperature);
1372 return QPair<QMetaObject::Connection,QMetaObject::Connection>(baroPressureUpdater, baroTempUpdater);
1382 bool result =
false;
1384 if (updaters.first) {
1385 result |= QObject::disconnect(updaters.first);
1388 if (updaters.second) {
1389 result |= QObject::disconnect(updaters.second);
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"));
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)
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.
virtual ~APMFirmwarePlugin()
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.
void setRawValue(const QVariant &value)
QVariant rawValue() const
Value after translation.
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
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()
void writeArduPilotGuidedMissionItem(const QGeoCoordinate &gotoCoord, bool altChangeOnly)
bool parameterExists(int componentId, const QString ¶mName) const
Fact * getParameter(int componentId, const QString ¶mName)
static constexpr int defaultComponentId
static VehicleClass_t vehicleClass(MAV_TYPE mavType)
static MAV_AUTOPILOT firmwareTypeFromString(const QString &firmwareTypeStr)
static constexpr const VehicleClass_t VehicleClassSub
static constexpr const VehicleClass_t VehicleClassFixedWing
static constexpr const VehicleClass_t VehicleClassMultiRotor
static MAV_TYPE vehicleTypeFromString(const QString &vehicleStr)
static constexpr const VehicleClass_t VehicleClassRoverBoat
static constexpr const VehicleClass_t VehicleClassVTOL
static FIRMWARE_VERSION_TYPE firmwareVersionTypeFromString(const QString &typeStr)
static QGCAmbientTemperature * instance()
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)
Fact * altitudeRelative()
WeakLinkInterfacePtr primaryLink() const
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)
qreal getInitialGCSPressure() const
QString flightMode() const
void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple=true)
QGeoCoordinate homePosition()
void setFirmwarePluginInstanceData(FirmwarePluginInstanceData *firmwarePluginInstanceData)
MAV_TYPE vehicleType() const
VehicleLinkManager * vehicleLinkManager()
FirmwarePlugin * firmwarePlugin()
Provides access to the Firmware Plugin for this Vehicle.
qreal getInitialGCSTemperature() const
int firmwareMinorVersion() const
bool isOfflineEditingVehicle() const
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
int defaultComponentId() const
ParameterManager * parameterManager()
void _setFlying(bool flying)
void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType=FIRMWARE_VERSION_TYPE_OFFICIAL)
QGeoCoordinate coordinate()
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)
class FirmwarePluginInstanceData * firmwarePluginInstanceData()
int firmwareMajorVersion() const
MissionManager * missionManager()
static constexpr const char * videoSource3DRSolo
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
static constexpr VehicleClass_t VehicleClassGeneric
Callback info bundle for sendMavCommandWithHandler.
MavCmdResultHandler resultHandler
nullptr for no handler
MavCmdResultFailureCode_t