QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
PX4FirmwarePlugin.cc
Go to the documentation of this file.
1#include "PX4FirmwarePlugin.h"
3#include "QGCApplication.h"
6#include "SettingsManager.h"
7#include "PlanViewSettings.h"
8#include "ParameterManager.h"
9#include "Vehicle.h"
10
11#include <QString>
12
13#include "px4_custom_mode.h"
14
15QGC_LOGGING_CATEGORY(PX4FirmwarePluginLog, "FirmwarePlugin.PX4FirmwarePlugin")
16
19 , versionNotified(false)
20{
21
22}
23
25{
26 const QString manualFlightModeName = tr("Manual");
27 const QString acroFlightModeName = tr("Acro");
28 const QString stabilizedFlightModeName = tr("Stabilized");
29 const QString rattitudeFlightModeName = tr("Rattitude");
30 const QString altCtlFlightModeName = tr("Altitude");
31 const QString posCtlFlightModeName = tr("Position");
32 const QString offboardFlightModeName = tr("Offboard");
33 const QString readyFlightModeName = tr("Ready");
34 const QString takeoffFlightModeName = tr("Takeoff");
35 const QString holdFlightModeName = tr("Hold");
36 const QString missionFlightModeName = tr("Mission");
37 const QString rtlFlightModeName = tr("Return");
38 const QString landingFlightModeName = tr("Land");
39 const QString preclandFlightModeName = tr("Precision Land");
40 const QString rtgsFlightModeName = tr("Return to Groundstation");
41 const QString followMeFlightModeName = tr("Follow Me");
42 const QString simpleFlightModeName = tr("Simple");
43 const QString orbitFlightModeName = tr("Orbit");
44
46 { PX4CustomMode::MANUAL, manualFlightModeName },
47 { PX4CustomMode::STABILIZED, stabilizedFlightModeName },
48 { PX4CustomMode::ACRO, acroFlightModeName },
49 { PX4CustomMode::RATTITUDE, rattitudeFlightModeName },
50 { PX4CustomMode::ALTCTL, altCtlFlightModeName },
51 { PX4CustomMode::OFFBOARD, offboardFlightModeName },
52 { PX4CustomMode::SIMPLE, simpleFlightModeName },
53 { PX4CustomMode::POSCTL_POSCTL, posCtlFlightModeName },
54 { PX4CustomMode::POSCTL_ORBIT, orbitFlightModeName },
55 { PX4CustomMode::AUTO_LOITER, holdFlightModeName },
56 { PX4CustomMode::AUTO_MISSION, missionFlightModeName },
57 { PX4CustomMode::AUTO_RTL, rtlFlightModeName },
58 { PX4CustomMode::AUTO_LAND, landingFlightModeName },
59 { PX4CustomMode::AUTO_PRECLAND, preclandFlightModeName },
60 { PX4CustomMode::AUTO_READY, readyFlightModeName },
61 { PX4CustomMode::AUTO_RTGS, rtgsFlightModeName },
62 { PX4CustomMode::AUTO_TAKEOFF, takeoffFlightModeName },
63 });
64
65 static FlightModeList availableFlightModes = {
66 // Mode Name Custom Mode CanBeSet adv
67 { manualFlightModeName, PX4CustomMode::MANUAL, true, true },
68 { stabilizedFlightModeName, PX4CustomMode::STABILIZED, true, true },
69 { acroFlightModeName, PX4CustomMode::ACRO, true, true },
70 { rattitudeFlightModeName, PX4CustomMode::RATTITUDE, true, false},
71 { altCtlFlightModeName, PX4CustomMode::ALTCTL, true, false},
72 { offboardFlightModeName, PX4CustomMode::OFFBOARD, true, true },
73 { simpleFlightModeName, PX4CustomMode::SIMPLE, false, false},
74 { posCtlFlightModeName, PX4CustomMode::POSCTL_POSCTL, true, false},
75 { orbitFlightModeName, PX4CustomMode::POSCTL_ORBIT, false, true },
76 { holdFlightModeName, PX4CustomMode::AUTO_LOITER, true, true },
77 { missionFlightModeName, PX4CustomMode::AUTO_MISSION, true, true },
78 { rtlFlightModeName, PX4CustomMode::AUTO_RTL, true, true },
79 { landingFlightModeName, PX4CustomMode::AUTO_LAND, false, true },
80 { preclandFlightModeName, PX4CustomMode::AUTO_PRECLAND, true, true },
81 { readyFlightModeName, PX4CustomMode::AUTO_READY, false, false},
82 { rtgsFlightModeName, PX4CustomMode::AUTO_RTGS, false, false},
83 { takeoffFlightModeName, PX4CustomMode::AUTO_TAKEOFF, false, false},
84 };
85
86 updateAvailableFlightModes(availableFlightModes);
87}
88
92
94{
95 return new PX4AutoPilotPlugin(vehicle, vehicle);
96}
97
98QStringList PX4FirmwarePlugin::flightModes(Vehicle* vehicle) const
99{
100 QStringList flightModesList;
101
102 for (auto &mode : _flightModeList) {
103 if (mode.canBeSet){
104 bool fw = (vehicle->fixedWing() && mode.fixedWing);
105 bool mc = (vehicle->multiRotor() && mode.multiRotor);
106
107 // show all modes for generic, vtol, etc
108 bool other = !vehicle->fixedWing() && !vehicle->multiRotor();
109 if (fw || mc || other) {
110 flightModesList += mode.mode_name;
111 }
112 }
113 }
114
115 return flightModesList;
116}
117
118QString PX4FirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode) const
119{
120 QString flightMode = "Unknown";
121
122 if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
123 return _modeEnumToString.value(custom_mode, tr("Unknown %1:%2").arg(base_mode).arg(custom_mode));
124 }
125
126 return flightMode;
127}
128
129bool PX4FirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) const
130{
131 *base_mode = 0;
132 *custom_mode = 0;
133
134 bool found = false;
135
136 for (auto &mode: _flightModeList){
137 if(flightMode.compare(mode.mode_name, Qt::CaseInsensitive) == 0){
138 *base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
139 *custom_mode = mode.custom_mode;
140 found = true;
141 break;
142 }
143 }
144
145 if (!found) {
146 qCWarning(PX4FirmwarePluginLog) << "Unknown flight Mode" << flightMode;
147 }
148
149 return found;
150}
151
152bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) const
153{
155 //-- This is arbitrary until I find how to really tell if ROI is avaiable
156 if (vehicle->multiRotor()) {
158 }
159 if (vehicle->multiRotor() || vehicle->vtol()) {
161 }
162 if (vehicle->fixedWing()) {
164 }
165 return (capabilities & available) == capabilities;
166}
167
172
174{
175 // PX4 stack does not want home position sent in the first position.
176 // Subsequent sequence numbers must be adjusted.
177 return false;
178}
179
180FactMetaData* PX4FirmwarePlugin::_getMetaDataForFact(QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) const
181{
182 PX4ParameterMetaData* px4MetaData = qobject_cast<PX4ParameterMetaData*>(parameterMetaData);
183
184 if (px4MetaData) {
185 return px4MetaData->getMetaDataForFact(name, vehicleType, type);
186 } else {
187 qCWarning(PX4FirmwarePluginLog) << "Internal error: pointer passed to PX4FirmwarePlugin::getMetaDataForFact not PX4ParameterMetaData";
188 }
189
190 return nullptr;
191}
192
193void PX4FirmwarePlugin::_getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) const
194{
195 return PX4ParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion);
196}
197
199{
200 QList<MAV_CMD> supportedCommands = {
201 MAV_CMD_NAV_WAYPOINT,
202 MAV_CMD_NAV_LOITER_UNLIM, MAV_CMD_NAV_LOITER_TIME,
203 MAV_CMD_NAV_RETURN_TO_LAUNCH,
204 MAV_CMD_DO_JUMP,
205 MAV_CMD_DO_DIGICAM_CONTROL,
206 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
207 MAV_CMD_DO_SET_SERVO,
208 MAV_CMD_DO_SET_ACTUATOR,
209 MAV_CMD_DO_CHANGE_SPEED,
210 MAV_CMD_DO_SET_HOME,
211 MAV_CMD_DO_LAND_START,
212 MAV_CMD_DO_SET_ROI_LOCATION, MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET, MAV_CMD_DO_SET_ROI_NONE,
213 MAV_CMD_DO_MOUNT_CONFIGURE,
214 MAV_CMD_DO_MOUNT_CONTROL,
215 MAV_CMD_SET_CAMERA_MODE,
216 MAV_CMD_IMAGE_START_CAPTURE, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_CMD_VIDEO_START_CAPTURE, MAV_CMD_VIDEO_STOP_CAPTURE,
217 MAV_CMD_NAV_DELAY,
218 MAV_CMD_CONDITION_YAW,
219 MAV_CMD_NAV_LOITER_TO_ALT,
220 MAV_CMD_DO_GRIPPER
221 };
222
223 QList<MAV_CMD> vtolCommands = {
224 MAV_CMD_DO_VTOL_TRANSITION, MAV_CMD_NAV_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_LAND,
225 };
226
227 QList<MAV_CMD> flightCommands = {
228 MAV_CMD_NAV_LAND, MAV_CMD_NAV_TAKEOFF,
229 };
230
231 if (vehicleClass == QGCMAVLink::VehicleClassGeneric) {
232 supportedCommands += vtolCommands;
233 supportedCommands += flightCommands;
234 }
235 if (vehicleClass == QGCMAVLink::VehicleClassVTOL) {
236 supportedCommands += vtolCommands;
237 supportedCommands += flightCommands;
238 } else if (vehicleClass == QGCMAVLink::VehicleClassFixedWing || vehicleClass == QGCMAVLink::VehicleClassMultiRotor) {
239 supportedCommands += flightCommands;
240 }
241
242 if (SettingsManager::instance()->planViewSettings()->useConditionGate()->rawValue().toBool()) {
243 supportedCommands.append(MAV_CMD_CONDITION_GATE);
244 }
245
246 return supportedCommands;
247}
248
250{
251 switch (vehicleClass) {
253 return QStringLiteral(":/json/PX4-MavCmdInfoCommon.json");
255 return QStringLiteral(":/json/PX4-MavCmdInfoFixedWing.json");
257 return QStringLiteral(":/json/PX4-MavCmdInfoMultiRotor.json");
259 return QStringLiteral(":/json/PX4-MavCmdInfoVTOL.json");
261 return QStringLiteral(":/json/PX4-MavCmdInfoSub.json");
263 return QStringLiteral(":/json/PX4-MavCmdInfoRover.json");
264 default:
265 qCWarning(PX4FirmwarePluginLog) << "PX4FirmwarePlugin::missionCommandOverrides called with bad VehicleClass_t:" << vehicleClass;
266 return QString();
267 }
268}
269
270QObject* PX4FirmwarePlugin::_loadParameterMetaData(const QString& metaDataFile)
271{
272 PX4ParameterMetaData* metaData = new PX4ParameterMetaData(this);
273 if (!metaDataFile.isEmpty()) {
274 metaData->loadParameterFactMetaDataFile(metaDataFile);
275 }
276 return metaData;
277}
278
280{
281 vehicle->sendMavCommand(vehicle->defaultComponentId(),
282 MAV_CMD_DO_REPOSITION,
283 true, // show error if failed
284 -1.0f,
285 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
286 0.0f,
287 NAN,
288 NAN,
289 NAN,
290 NAN);
291}
292
293void PX4FirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL) const
294{
295 Q_UNUSED(smartRTL);
297}
298
303
304void PX4FirmwarePlugin::_mavCommandResult(int vehicleId, int component, int command, int result, int failureCode)
305{
306 Q_UNUSED(vehicleId); Q_UNUSED(component); Q_UNUSED(failureCode);
307
308 auto* vehicle = qobject_cast<Vehicle*>(sender());
309 if (!vehicle) {
310 qCWarning(PX4FirmwarePluginLog) << "Dynamic cast failed!";
311 return;
312 }
313
314 if (command == MAV_CMD_NAV_TAKEOFF && result == MAV_RESULT_ACCEPTED) {
315 // Now that we are in takeoff mode we can arm the vehicle which will cause it to takeoff.
316 // We specifically don't retry arming if it fails. This way we don't fight with the user if
317 // They are trying to disarm.
318 disconnect(vehicle, &Vehicle::mavCommandResult, this, &PX4FirmwarePlugin::_mavCommandResult);
319 if (!vehicle->armed()) {
320 vehicle->setArmedShowError(true);
321 }
322 }
323}
324
325void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel) const
326{
327 double vehicleAltitudeAMSL = vehicle->altitudeAMSL()->rawValue().toDouble();
328 if (qIsNaN(vehicleAltitudeAMSL)) {
329 qgcApp()->showAppMessage(tr("Unable to takeoff, vehicle position not known."));
330 return;
331 }
332
333 double takeoffAltAMSL = takeoffAltRel + vehicleAltitudeAMSL;
334
335 connect(vehicle, &Vehicle::mavCommandResult, this, &PX4FirmwarePlugin::_mavCommandResult);
336 vehicle->sendMavCommand(
337 vehicle->defaultComponentId(),
338 MAV_CMD_NAV_TAKEOFF,
339 true, // show error is fails
340 -1, // No pitch requested
341 0, 0, // param 2-4 unused
342 NAN, NAN, NAN, // No yaw, lat, lon
343 static_cast<float>(takeoffAltAMSL)); // AMSL altitude
344}
345
347{
348 QString speedParam("MPC_XY_VEL_MAX");
349
351 return vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, speedParam)->rawValue().toDouble();
352 }
353
355}
356
358{
359 QString airspeedMax("FW_AIRSPD_MAX");
360
362 return vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, airspeedMax)->rawValue().toDouble();
363 }
364
366}
367
369{
370 QString airspeedMin("FW_AIRSPD_MIN");
371
373 return vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, airspeedMin)->rawValue().toDouble();
374 }
375
377}
378
383
389
390void PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord, double forwardFlightLoiterRadius) const
391{
392 // PX4 doesn't support setting the forward flight loiter radius of
393 // MAV_CMD_DO_REPOSITION
394 Q_UNUSED(forwardFlightLoiterRadius)
395
396 if (qIsNaN(vehicle->altitudeAMSL()->rawValue().toDouble())) {
397 qgcApp()->showAppMessage(tr("Unable to go to location, vehicle position not known."));
398 return;
399 }
400
401 if (vehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
402 vehicle->sendMavCommandInt(vehicle->defaultComponentId(),
403 MAV_CMD_DO_REPOSITION,
404 MAV_FRAME_GLOBAL,
405 true, // show error is fails
406 -1.0f,
407 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
408 0.0f,
409 NAN,
410 gotoCoord.latitude(),
411 gotoCoord.longitude(),
412 vehicle->altitudeAMSL()->rawValue().toFloat());
413 } else {
414 vehicle->sendMavCommand(vehicle->defaultComponentId(),
415 MAV_CMD_DO_REPOSITION,
416 true, // show error is fails
417 -1.0f,
418 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
419 0.0f,
420 NAN,
421 static_cast<float>(gotoCoord.latitude()),
422 static_cast<float>(gotoCoord.longitude()),
423 vehicle->altitudeAMSL()->rawValue().toFloat());
424 }
425}
426
432
433static void _pauseVehicleThenChangeAltResultHandler(void* resultHandlerData, int /*compId*/, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode)
434{
435 if (ack.result != MAV_RESULT_ACCEPTED) {
436 switch (failureCode) {
438 qCDebug(PX4FirmwarePluginLog) << QStringLiteral("MAV_CMD_DO_REPOSITION error(%1)").arg(ack.result);
439 break;
441 qCDebug(PX4FirmwarePluginLog) << "MAV_CMD_DO_REPOSITION no response from vehicle";
442 break;
444 qCDebug(PX4FirmwarePluginLog) << "Internal Error: MAV_CMD_DO_REPOSITION could not be sent due to duplicate command";
445 break;
446 }
447 }
448
449 PauseVehicleThenChangeAltData_t* pData = static_cast<PauseVehicleThenChangeAltData_t*>(resultHandlerData);
450 pData->plugin->_changeAltAfterPause(resultHandlerData, ack.result == MAV_RESULT_ACCEPTED /* pauseSucceeded */);
451}
452
453void PX4FirmwarePlugin::_changeAltAfterPause(void* resultHandlerData, bool pauseSucceeded)
454{
455 PauseVehicleThenChangeAltData_t* pData = static_cast<PauseVehicleThenChangeAltData_t*>(resultHandlerData);
456
457 if (pauseSucceeded) {
458 pData->vehicle->sendMavCommand(
459 pData->vehicle->defaultComponentId(),
460 MAV_CMD_DO_REPOSITION,
461 true, // show error is fails
462 -1.0f, // Don't change groundspeed
463 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
464 0.0f, // Reserved
465 qQNaN(), qQNaN(), qQNaN(), // No change to yaw, lat, lon
466 static_cast<float>(pData->newAMSLAlt));
467 } else {
468 qgcApp()->showAppMessage(tr("Unable to pause vehicle."));
469 }
470
471 delete pData;
472}
473
474void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange, bool pauseVehicle)
475{
476 if (!vehicle->homePosition().isValid()) {
477 qgcApp()->showAppMessage(tr("Unable to change altitude, home position unknown."));
478 return;
479 }
480 if (qIsNaN(vehicle->homePosition().altitude())) {
481 qgcApp()->showAppMessage(tr("Unable to change altitude, home position altitude unknown."));
482 return;
483 }
484
485 double currentAltRel = vehicle->altitudeRelative()->rawValue().toDouble();
486 double newAltRel = currentAltRel + altitudeChange;
487
489 resultData->plugin = this;
490 resultData->vehicle = vehicle;
491 resultData->newAMSLAlt = vehicle->homePosition().altitude() + newAltRel;
492
493 if (pauseVehicle) {
494 Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {};
496 handlerInfo.resultHandlerData = resultData;
497
499 &handlerInfo,
500 vehicle->defaultComponentId(),
501 MAV_CMD_DO_REPOSITION,
502 -1.0f, // Don't change groundspeed
503 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
504 0.0f, // Reserved
505 qQNaN(), qQNaN(), qQNaN(), qQNaN()); // No change to yaw, lat, lon, alt
506 } else {
507 _changeAltAfterPause(resultData, true /* pauseSucceeded */);
508 }
509}
510
512{
513
514 vehicle->sendMavCommand(
515 vehicle->defaultComponentId(),
516 MAV_CMD_DO_CHANGE_SPEED,
517 true, // show error is fails
518 1, // 0: airspeed, 1: groundspeed
519 static_cast<float>(groundspeed), // groundspeed setpoint
520 -1, // throttle
521 0, // 0: absolute speed, 1: relative to current
522 NAN, NAN,NAN); // param 5-7 unused
523}
524
526{
527
528 vehicle->sendMavCommand(
529 vehicle->defaultComponentId(),
530 MAV_CMD_DO_CHANGE_SPEED,
531 true, // show error is fails
532 0, // 0: airspeed, 1: groundspeed
533 static_cast<float>(airspeed_equiv), // groundspeed setpoint
534 -1, // throttle
535 0, // 0: absolute speed, 1: relative to current
536 NAN, NAN,NAN); // param 5-7 unused
537}
538
539void PX4FirmwarePlugin::guidedModeChangeHeading(Vehicle* vehicle, const QGeoCoordinate &headingCoord) const
540{
542 qgcApp()->showAppMessage(tr("Vehicle does not support guided rotate"));
543 return;
544 }
545
546 const float radians = qDegreesToRadians(vehicle->coordinate().azimuthTo(headingCoord));
547
548 vehicle->sendMavCommand(
549 vehicle->defaultComponentId(),
550 MAV_CMD_DO_REPOSITION,
551 true,
552 -1.0f, // no change in ground speed
553 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE, // switch to guided mode
554 0.0f, // reserved
555 radians, // change heading
556 NAN, NAN, NAN // no change lat, lon, alt
557 );
558}
559
561{
563 if (!_armVehicleAndValidate(vehicle)) {
564 qgcApp()->showAppMessage(tr("Unable to start takeoff: Vehicle rejected arming."));
565 return;
566 }
567 } else {
568 qgcApp()->showAppMessage(tr("Unable to start takeoff: Vehicle not changing to %1 flight mode.").arg(takeOffFlightMode()));
569 }
570}
571
573{
575 if (!_armVehicleAndValidate(vehicle)) {
576 qgcApp()->showAppMessage(tr("Unable to start mission: Vehicle rejected arming."));
577 return;
578 }
579 } else {
580 qgcApp()->showAppMessage(tr("Unable to start mission: Vehicle not changing to %1 flight mode.").arg(missionFlightMode()));
581 }
582}
583
584void PX4FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode) const
585{
586 if (guidedMode) {
588 } else {
589 pauseVehicle(vehicle);
590 }
591}
592
597
602
607
612
617
622
627
632
637
638bool PX4FirmwarePlugin::isGuidedMode(const Vehicle* vehicle) const
639{
640 // Not supported by generic vehicle
641 return (vehicle->flightMode() == pauseFlightMode() || vehicle->flightMode() == takeOffFlightMode() || vehicle->flightMode() == landFlightMode());
642}
643
645{
646 //-- Don't process messages to/from UDP Bridge. It doesn't suffer from these issues
647 if (message->compid == MAV_COMP_ID_UDP_BRIDGE) {
648 return true;
649 }
650
651 switch (message->msgid) {
652 case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
653 _handleAutopilotVersion(vehicle, message);
654 break;
655 }
656
657 return true;
658}
659
660void PX4FirmwarePlugin::_handleAutopilotVersion(Vehicle* vehicle, mavlink_message_t* message)
661{
662 Q_UNUSED(vehicle);
663
664 auto* instanceData = qobject_cast<PX4FirmwarePluginInstanceData*>(vehicle->firmwarePluginInstanceData());
665 if (!instanceData->versionNotified) {
666 bool notifyUser = false;
667 int supportedMajorVersion = 1;
668 int supportedMinorVersion = 4;
669 int supportedPatchVersion = 1;
670
671 mavlink_autopilot_version_t version;
672 mavlink_msg_autopilot_version_decode(message, &version);
673
674 if (version.flight_sw_version != 0) {
675 int majorVersion, minorVersion, patchVersion;
676
677 majorVersion = (version.flight_sw_version >> (8*3)) & 0xFF;
678 minorVersion = (version.flight_sw_version >> (8*2)) & 0xFF;
679 patchVersion = (version.flight_sw_version >> (8*1)) & 0xFF;
680
681 if (majorVersion < supportedMajorVersion) {
682 notifyUser = true;
683 } else if (majorVersion == supportedMajorVersion) {
684 if (minorVersion < supportedMinorVersion) {
685 notifyUser = true;
686 } else if (minorVersion == supportedMinorVersion) {
687 notifyUser = patchVersion < supportedPatchVersion;
688 }
689 }
690 } else {
691 notifyUser = true;
692 }
693
694 if (notifyUser) {
695 instanceData->versionNotified = true;
696 qgcApp()->showAppMessage(tr("QGroundControl supports PX4 Pro firmware Version %1.%2.%3 and above. You are using a version prior to that which will lead to unpredictable results. Please upgrade your firmware.").arg(supportedMajorVersion).arg(supportedMinorVersion).arg(supportedPatchVersion));
697 }
698 }
699}
700
701uint32_t PX4FirmwarePlugin::highLatencyCustomModeTo32Bits(uint16_t hlCustomMode) const
702{
703 union px4_custom_mode px4_cm;
704 px4_cm.data = 0;
705 px4_cm.custom_mode_hl = hlCustomMode;
706
707 return px4_cm.data;
708}
709
710QString PX4FirmwarePlugin::_getLatestVersionFileUrl(Vehicle* vehicle) const
711{
712 Q_UNUSED(vehicle);
713 return QStringLiteral("https://api.github.com/repos/PX4/Firmware/releases");
714}
715
716QString PX4FirmwarePlugin::_versionRegex() const
717{
718 return QStringLiteral("v([0-9,\\.]*) Stable");
719}
720
722{
723 return ((vehicle->vehicleType() == MAV_TYPE_GROUND_ROVER) || (vehicle->vehicleType() == MAV_TYPE_SUBMARINE));
724}
725
727{
728 static const char* HOOBS_HI = "LND_FLIGHT_T_HI";
729 static const char* HOOBS_LO = "LND_FLIGHT_T_LO";
730 uint64_t hobbsTimeSeconds = 0;
731
736 hobbsTimeSeconds = ((uint64_t)factHi->rawValue().toUInt() << 32 | (uint64_t)factLo->rawValue().toUInt()) / 1000000;
737 qCDebug(VehicleLog) << "Hobbs Meter raw PX4:" << "(" << factHi->rawValue().toUInt() << factLo->rawValue().toUInt() << ")";
738 }
739
740 int hours = hobbsTimeSeconds / 3600;
741 int minutes = (hobbsTimeSeconds % 3600) / 60;
742 int seconds = hobbsTimeSeconds % 60;
743 QString timeStr = QString::asprintf("%04d:%02d:%02d", hours, minutes, seconds);
744 qCDebug(VehicleLog) << "Hobbs Meter string:" << timeStr;
745 return timeStr;
746}
747
748bool PX4FirmwarePlugin::hasGripper(const Vehicle* vehicle) const
749{
750 if(vehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, QStringLiteral("PD_GRIPPER_EN"))) {
751 bool _hasGripper = (vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, QStringLiteral("PD_GRIPPER_EN"))->rawValue().toInt()) != 0 ? true : false;
752 return _hasGripper;
753 }
754 return false;
755}
756
758{
759 for(auto &mode: modeList){
760 PX4CustomMode::Mode cMode = static_cast<PX4CustomMode::Mode>(mode.custom_mode);
761
762 // Update Multi Rotor
763 switch (cMode) {
781 mode.multiRotor = true;
782 break;
784 mode.multiRotor = false;
785 break;
786 }
787
788 // Update Fixed Wing
789 switch (cMode){
795 mode.fixedWing = false;
796 break;
810 mode.fixedWing = true;
811 break;
812 }
813 }
814 _updateFlightModeList(modeList);
815}
816
817QVariant PX4FirmwarePlugin::expandedToolbarIndicatorSource(const Vehicle* /*vehicle*/, const QString& indicatorName) const
818{
819 if (indicatorName == "Battery") {
820 return QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/FirmwarePlugin/PX4/PX4BatteryIndicator.qml"));
821 } else if (indicatorName == "FlightMode") {
822 return QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/FirmwarePlugin/PX4/PX4FlightModeIndicator.qml"));
823 } else if (indicatorName == "MainStatus") {
824 return QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/FirmwarePlugin/PX4/PX4MainStatusIndicator.qml"));
825 }
826
827 return QVariant();
828}
QList< FirmwareFlightMode > FlightModeList
static void _pauseVehicleThenChangeAltResultHandler(void *resultHandlerData, int, const mavlink_command_ack_t &ack, Vehicle::MavCmdResultFailureCode_t failureCode)
#define qgcApp()
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
A Fact is used to hold a single value within the system.
Definition Fact.h:19
void _setModeEnumToModeStringMapping(FlightModeCustomModeMap enumToString)
virtual double maximumHorizontalSpeedMultirotor(Vehicle *) const
FlightModeList _flightModeList
virtual double minimumEquivalentAirspeed(Vehicle *) const
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.
@ OrbitModeCapability
Vehicle supports orbit mode.
@ 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
void _updateFlightModeList(FlightModeList &flightModeList)
bool _armVehicleAndValidate(Vehicle *vehicle) const
FlightModeCustomModeMap _modeEnumToString
void initializeVehicle(Vehicle *vehicle) override
Called when Vehicle is first created to perform any firmware specific setup.
bool isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) const override
bool adjustIncomingMavlinkMessage(Vehicle *vehicle, mavlink_message_t *message) override
QObject * _loadParameterMetaData(const QString &metaDataFile) final
void setGuidedMode(Vehicle *vehicle, bool guidedMode) const override
Set guided flight mode.
void _getParameterMetaDataVersionInfo(const QString &metaDataFile, int &majorVersion, int &minorVersion) const override
QString gotoFlightMode(void) const override
Returns the flight mode which the vehicle will be in if it is performing a goto location.
QList< MAV_CMD > supportedMissionCommands(QGCMAVLink::VehicleClass_t vehicleClass) const override
List of supported mission commands. Empty list for all commands supported.
QString flightMode(uint8_t base_mode, uint32_t custom_mode) const override
QString takeOffFlightMode(void) const override
Returns the flight mode for TakeOff.
QString pauseFlightMode(void) const override
Returns The flight mode which indicates the vehicle is paused.
FactMetaData * _getMetaDataForFact(QObject *parameterMetaData, const QString &name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) const override
bool sendHomePositionToVehicle(void) const override
bool setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const override
void startMission(Vehicle *vehicle) const override
Command the vehicle to start the mission.
void updateAvailableFlightModes(FlightModeList &modeList) override
Update Available flight modes recieved from vehicle.
QString takeControlFlightMode(void) const override
Returns the flight mode to use when the operator wants to take back control from autonomouse flight.
bool fixedWingAirSpeedLimitsAvailable(Vehicle *vehicle) const override
QString missionFlightMode(void) const override
Returns the flight mode for running missions.
void pauseVehicle(Vehicle *vehicle) const override
QString landFlightMode(void) const override
Returns the flight mode for Land.
QString rtlFlightMode(void) const override
Returns the flight mode for RTL.
void guidedModeRTL(Vehicle *vehicle, bool smartRTL) const override
Command vehicle to return to launch.
void guidedModeChangeHeading(Vehicle *vehicle, const QGeoCoordinate &headingCoord) const override
Command vehicle to rotate towards specified location.
uint32_t highLatencyCustomModeTo32Bits(uint16_t hlCustomMode) const override
Convert from HIGH_LATENCY2.custom_mode value to correct 32 bit value.
void startTakeoff(Vehicle *vehicle) const override
Command the vehicle to start a takeoff.
QStringList flightModes(Vehicle *vehicle) const override
QString getHobbsMeter(Vehicle *vehicle) const override
gets hobbs meter from autopilot. This should be reimplmeented for each firmware
bool isGuidedMode(const Vehicle *vehicle) const override
Returns whether the vehicle is in guided mode or not.
void guidedModeTakeoff(Vehicle *vehicle, double takeoffAltRel) const override
Command vehicle to takeoff from current location to the specified height.
QVariant expandedToolbarIndicatorSource(const Vehicle *vehicle, const QString &indicatorName) const override
double minimumEquivalentAirspeed(Vehicle *vehicle) const override
QString followFlightMode(void) const override
Returns the flight mode which the vehicle will be for follow me.
void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle *vehicle, double airspeed_equiv) const override
bool supportsNegativeThrust(Vehicle *vehicle) const override
bool mulirotorSpeedLimitsAvailable(Vehicle *vehicle) const override
QString missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const override
double maximumEquivalentAirspeed(Vehicle *vehicle) const override
void guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius) const override
Command vehicle to move to specified location (altitude is included and relative)
void guidedModeChangeAltitude(Vehicle *vehicle, double altitudeRel, bool pauseVehicle) override
QString stabilizedFlightMode(void) const override
Returns the flight mode for Stabilized.
void _changeAltAfterPause(void *resultHandlerData, bool pauseSucceeded)
AutoPilotPlugin * autopilotPlugin(Vehicle *vehicle) const override
double maximumHorizontalSpeedMultirotor(Vehicle *vehicle) const override
bool hasGripper(const Vehicle *vehicle) const override
void guidedModeChangeGroundSpeedMetersSecond(Vehicle *vehicle, double groundspeed) const override
void guidedModeLand(Vehicle *vehicle) const override
Command vehicle to land at current location.
Loads and holds parameter fact meta data for PX4 stack.
static void getParameterMetaDataVersionInfo(const QString &metaDataFile, int &majorVersion, int &minorVersion)
void loadParameterFactMetaDataFile(const QString &metaDataFile)
FactMetaData * getMetaDataForFact(const QString &name, MAV_TYPE vehicleType, FactMetaData::ValueType_t type)
bool parameterExists(int componentId, const QString &paramName) const
Fact * getParameter(int componentId, const QString &paramName)
static constexpr int defaultComponentId
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:2309
QString flightMode() const
Definition Vehicle.cc:1549
bool vtol() const
Definition Vehicle.cc:1869
QGeoCoordinate homePosition()
Definition Vehicle.cc:1515
bool multiRotor() const
Definition Vehicle.cc:1864
void setFirmwarePluginInstanceData(FirmwarePluginInstanceData *firmwarePluginInstanceData)
Definition Vehicle.cc:3430
uint64_t capabilityBits() const
Definition Vehicle.h:738
MAV_TYPE vehicleType() const
Definition Vehicle.h:428
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:2350
MavCmdResultFailureCode_t
Definition Vehicle.h:618
@ MavCmdResultFailureNoResponseToCommand
No response from vehicle to command.
Definition Vehicle.h:620
@ MavCmdResultCommandResultOnly
commandResult specifies full success/fail info
Definition Vehicle.h:619
@ MavCmdResultFailureDuplicateCommand
Unable to send command since duplicate is already being waited on for response.
Definition Vehicle.h:621
int defaultComponentId() const
Definition Vehicle.h:711
ParameterManager * parameterManager()
Definition Vehicle.h:578
bool fixedWing() const
Definition Vehicle.cc:1844
QGeoCoordinate coordinate()
Definition Vehicle.h:412
void mavCommandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
class FirmwarePluginInstanceData * firmwarePluginInstanceData()
Definition Vehicle.h:726
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:2339
MavCmdResultHandler resultHandler
Definition Vehicle.h:639
void * resultHandlerData
‍nullptr for no handler
Definition Vehicle.h:640
uint16_t custom_mode_hl