QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
PX4FirmwarePlugin.cc
Go to the documentation of this file.
1#include "PX4FirmwarePlugin.h"
2#include "ParameterMetaData.h"
4#include "AppMessages.h"
7#include "SettingsManager.h"
8#include "PlanViewSettings.h"
9#include "ParameterManager.h"
10#include "Vehicle.h"
11
12#include <QtCore/QString>
13
14#include "px4_custom_mode.h"
15
16QGC_LOGGING_CATEGORY(PX4FirmwarePluginLog, "FirmwarePlugin.PX4FirmwarePlugin")
17
20 , versionNotified(false)
21{
22
23}
24
26{
27 const QString manualFlightModeName = tr("Manual");
28 const QString acroFlightModeName = tr("Acro");
29 const QString stabilizedFlightModeName = tr("Stabilized");
30 const QString rattitudeFlightModeName = tr("Rattitude");
31 const QString altCtlFlightModeName = tr("Altitude");
32 const QString posCtlFlightModeName = tr("Position");
33 const QString offboardFlightModeName = tr("Offboard");
34 const QString readyFlightModeName = tr("Ready");
35 const QString takeoffFlightModeName = tr("Takeoff");
36 const QString holdFlightModeName = tr("Hold");
37 const QString missionFlightModeName = tr("Mission");
38 const QString rtlFlightModeName = tr("Return");
39 const QString landingFlightModeName = tr("Land");
40 const QString preclandFlightModeName = tr("Precision Land");
41 const QString rtgsFlightModeName = tr("Return to Groundstation");
42 const QString followMeFlightModeName = tr("Follow Me");
43 const QString simpleFlightModeName = tr("Simple");
44 const QString orbitFlightModeName = tr("Orbit");
45
47 { PX4CustomMode::MANUAL, manualFlightModeName },
48 { PX4CustomMode::STABILIZED, stabilizedFlightModeName },
49 { PX4CustomMode::ACRO, acroFlightModeName },
50 { PX4CustomMode::RATTITUDE, rattitudeFlightModeName },
51 { PX4CustomMode::ALTCTL, altCtlFlightModeName },
52 { PX4CustomMode::OFFBOARD, offboardFlightModeName },
53 { PX4CustomMode::SIMPLE, simpleFlightModeName },
54 { PX4CustomMode::POSCTL_POSCTL, posCtlFlightModeName },
55 { PX4CustomMode::POSCTL_ORBIT, orbitFlightModeName },
56 { PX4CustomMode::AUTO_LOITER, holdFlightModeName },
57 { PX4CustomMode::AUTO_MISSION, missionFlightModeName },
58 { PX4CustomMode::AUTO_RTL, rtlFlightModeName },
59 { PX4CustomMode::AUTO_LAND, landingFlightModeName },
60 { PX4CustomMode::AUTO_PRECLAND, preclandFlightModeName },
61 { PX4CustomMode::AUTO_READY, readyFlightModeName },
62 { PX4CustomMode::AUTO_RTGS, rtgsFlightModeName },
63 { PX4CustomMode::AUTO_TAKEOFF, takeoffFlightModeName },
64 });
65
66 static FlightModeList availableFlightModes = {
67 // Mode Name Custom Mode CanBeSet adv
68 { manualFlightModeName, PX4CustomMode::MANUAL, true, true },
69 { stabilizedFlightModeName, PX4CustomMode::STABILIZED, true, true },
70 { acroFlightModeName, PX4CustomMode::ACRO, true, true },
71 { rattitudeFlightModeName, PX4CustomMode::RATTITUDE, true, false},
72 { altCtlFlightModeName, PX4CustomMode::ALTCTL, true, false},
73 { offboardFlightModeName, PX4CustomMode::OFFBOARD, true, true },
74 { simpleFlightModeName, PX4CustomMode::SIMPLE, false, false},
75 { posCtlFlightModeName, PX4CustomMode::POSCTL_POSCTL, true, false},
76 { orbitFlightModeName, PX4CustomMode::POSCTL_ORBIT, false, true },
77 { holdFlightModeName, PX4CustomMode::AUTO_LOITER, true, true },
78 { missionFlightModeName, PX4CustomMode::AUTO_MISSION, true, true },
79 { rtlFlightModeName, PX4CustomMode::AUTO_RTL, true, true },
80 { landingFlightModeName, PX4CustomMode::AUTO_LAND, false, true },
81 { preclandFlightModeName, PX4CustomMode::AUTO_PRECLAND, true, true },
82 { readyFlightModeName, PX4CustomMode::AUTO_READY, false, false},
83 { rtgsFlightModeName, PX4CustomMode::AUTO_RTGS, false, false},
84 { takeoffFlightModeName, PX4CustomMode::AUTO_TAKEOFF, false, false},
85 };
86
87 updateAvailableFlightModes(availableFlightModes);
88}
89
93
95{
96 return new PX4AutoPilotPlugin(vehicle, vehicle);
97}
98
99QStringList PX4FirmwarePlugin::flightModes(Vehicle* vehicle) const
100{
101 QStringList flightModesList;
102
103 for (auto &mode : _flightModeList) {
104 if (mode.canBeSet){
105 bool fw = (vehicle->fixedWing() && mode.fixedWing);
106 bool mc = (vehicle->multiRotor() && mode.multiRotor);
107
108 // show all modes for generic, vtol, etc
109 bool other = !vehicle->fixedWing() && !vehicle->multiRotor();
110 if (fw || mc || other) {
111 flightModesList += mode.mode_name;
112 }
113 }
114 }
115
116 return flightModesList;
117}
118
119QString PX4FirmwarePlugin::flightMode(uint8_t base_mode, uint32_t custom_mode) const
120{
121 QString flightMode = "Unknown";
122
123 if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) {
124 return _modeEnumToString.value(custom_mode, tr("Unknown %1:%2").arg(base_mode).arg(custom_mode));
125 }
126
127 return flightMode;
128}
129
130bool PX4FirmwarePlugin::setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) const
131{
132 *base_mode = 0;
133 *custom_mode = 0;
134
135 bool found = false;
136
137 for (auto &mode: _flightModeList){
138 if(flightMode.compare(mode.mode_name, Qt::CaseInsensitive) == 0){
139 *base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
140 *custom_mode = mode.custom_mode;
141 found = true;
142 break;
143 }
144 }
145
146 if (!found) {
147 qCWarning(PX4FirmwarePluginLog) << "Unknown flight Mode" << flightMode;
148 }
149
150 return found;
151}
152
153bool PX4FirmwarePlugin::isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) const
154{
156 //-- This is arbitrary until I find how to really tell if ROI is avaiable
157 if (vehicle->multiRotor()) {
159 }
160 if (vehicle->multiRotor() || vehicle->vtol()) {
162 }
163 if (vehicle->fixedWing()) {
165 }
166 return (capabilities & available) == capabilities;
167}
168
173
175{
176 // PX4 stack does not want home position sent in the first position.
177 // Subsequent sequence numbers must be adjusted.
178 return false;
179}
180
182{
183 QList<MAV_CMD> supportedCommands = {
184 MAV_CMD_NAV_WAYPOINT,
185 MAV_CMD_NAV_LOITER_UNLIM, MAV_CMD_NAV_LOITER_TIME,
186 MAV_CMD_NAV_RETURN_TO_LAUNCH,
187 MAV_CMD_DO_JUMP,
188 MAV_CMD_DO_DIGICAM_CONTROL,
189 MAV_CMD_DO_SET_CAM_TRIGG_DIST,
190 MAV_CMD_DO_SET_SERVO,
191 MAV_CMD_DO_SET_ACTUATOR,
192 MAV_CMD_DO_CHANGE_SPEED,
193 MAV_CMD_DO_SET_HOME,
194 MAV_CMD_DO_LAND_START,
195 MAV_CMD_DO_SET_ROI_LOCATION, MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET, MAV_CMD_DO_SET_ROI_NONE,
196 MAV_CMD_DO_MOUNT_CONFIGURE,
197 MAV_CMD_DO_MOUNT_CONTROL,
198 MAV_CMD_SET_CAMERA_MODE,
199 MAV_CMD_IMAGE_START_CAPTURE, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_CMD_VIDEO_START_CAPTURE, MAV_CMD_VIDEO_STOP_CAPTURE,
200 MAV_CMD_NAV_DELAY,
201 MAV_CMD_CONDITION_YAW,
202 MAV_CMD_NAV_LOITER_TO_ALT,
203 MAV_CMD_DO_GRIPPER
204 };
205
206 QList<MAV_CMD> vtolCommands = {
207 MAV_CMD_DO_VTOL_TRANSITION, MAV_CMD_NAV_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_LAND,
208 };
209
210 QList<MAV_CMD> flightCommands = {
211 MAV_CMD_NAV_LAND, MAV_CMD_NAV_TAKEOFF,
212 };
213
214 if (vehicleClass == QGCMAVLink::VehicleClassGeneric) {
215 supportedCommands += vtolCommands;
216 supportedCommands += flightCommands;
217 }
218 if (vehicleClass == QGCMAVLink::VehicleClassVTOL) {
219 supportedCommands += vtolCommands;
220 supportedCommands += flightCommands;
221 } else if (vehicleClass == QGCMAVLink::VehicleClassFixedWing || vehicleClass == QGCMAVLink::VehicleClassMultiRotor) {
222 supportedCommands += flightCommands;
223 }
224
225 if (SettingsManager::instance()->planViewSettings()->useConditionGate()->rawValue().toBool()) {
226 supportedCommands.append(MAV_CMD_CONDITION_GATE);
227 }
228
229 return supportedCommands;
230}
231
233{
234 switch (vehicleClass) {
236 return QStringLiteral(":/json/PX4-MavCmdInfoCommon.json");
238 return QStringLiteral(":/json/PX4-MavCmdInfoFixedWing.json");
240 return QStringLiteral(":/json/PX4-MavCmdInfoMultiRotor.json");
242 return QStringLiteral(":/json/PX4-MavCmdInfoVTOL.json");
244 return QStringLiteral(":/json/PX4-MavCmdInfoSub.json");
246 return QStringLiteral(":/json/PX4-MavCmdInfoRover.json");
247 default:
248 qCWarning(PX4FirmwarePluginLog) << "PX4FirmwarePlugin::missionCommandOverrides called with bad VehicleClass_t:" << vehicleClass;
249 return QString();
250 }
251}
252
257
259{
260 vehicle->sendMavCommand(vehicle->defaultComponentId(),
261 MAV_CMD_DO_REPOSITION,
262 true, // show error if failed
263 -1.0f,
264 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
265 0.0f,
266 NAN,
267 NAN,
268 NAN,
269 NAN);
270}
271
272void PX4FirmwarePlugin::guidedModeRTL(Vehicle* vehicle, bool smartRTL) const
273{
274 Q_UNUSED(smartRTL);
276}
277
282
283void PX4FirmwarePlugin::_mavCommandResult(int vehicleId, int component, int command, int result, int failureCode)
284{
285 Q_UNUSED(vehicleId); Q_UNUSED(component); Q_UNUSED(failureCode);
286
287 auto* vehicle = qobject_cast<Vehicle*>(sender());
288 if (!vehicle) {
289 qCWarning(PX4FirmwarePluginLog) << "Dynamic cast failed!";
290 return;
291 }
292
293 if (command == MAV_CMD_NAV_TAKEOFF && result == MAV_RESULT_ACCEPTED) {
294 // Now that we are in takeoff mode we can arm the vehicle which will cause it to takeoff.
295 // We specifically don't retry arming if it fails. This way we don't fight with the user if
296 // They are trying to disarm.
297 disconnect(vehicle, &Vehicle::mavCommandResult, this, &PX4FirmwarePlugin::_mavCommandResult);
298 if (!vehicle->armed()) {
299 vehicle->setArmedShowError(true);
300 }
301 }
302}
303
304void PX4FirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle, double takeoffAltRel) const
305{
306 double vehicleAltitudeAMSL = vehicle->altitudeAMSL()->rawValue().toDouble();
307 if (qIsNaN(vehicleAltitudeAMSL)) {
308 QGC::showAppMessage(tr("Unable to takeoff, vehicle position not known."));
309 return;
310 }
311
312 double takeoffAltAMSL = takeoffAltRel + vehicleAltitudeAMSL;
313
314 connect(vehicle, &Vehicle::mavCommandResult, this, &PX4FirmwarePlugin::_mavCommandResult);
315 vehicle->sendMavCommand(
316 vehicle->defaultComponentId(),
317 MAV_CMD_NAV_TAKEOFF,
318 true, // show error is fails
319 -1, // No pitch requested
320 0, 0, // param 2-4 unused
321 NAN, NAN, NAN, // No yaw, lat, lon
322 static_cast<float>(takeoffAltAMSL)); // AMSL altitude
323}
324
326{
327 QString speedParam("MPC_XY_VEL_MAX");
328
330 return vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, speedParam)->rawValue().toDouble();
331 }
332
334}
335
337{
338 QString airspeedMax("FW_AIRSPD_MAX");
339
341 return vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, airspeedMax)->rawValue().toDouble();
342 }
343
345}
346
348{
349 QString airspeedMin("FW_AIRSPD_MIN");
350
352 return vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, airspeedMin)->rawValue().toDouble();
353 }
354
356}
357
362
368
369bool PX4FirmwarePlugin::guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord, double forwardFlightLoiterRadius) const
370{
371 // PX4 doesn't support setting the forward flight loiter radius of
372 // MAV_CMD_DO_REPOSITION
373 Q_UNUSED(forwardFlightLoiterRadius)
374
375 if (qIsNaN(vehicle->altitudeAMSL()->rawValue().toDouble())) {
376 QGC::showAppMessage(tr("Unable to go to location, vehicle position not known."));
377 return false;
378 }
379
380 if (vehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
381 vehicle->sendMavCommandInt(vehicle->defaultComponentId(),
382 MAV_CMD_DO_REPOSITION,
383 MAV_FRAME_GLOBAL,
384 true, // show error is fails
385 -1.0f,
386 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
387 0.0f,
388 NAN,
389 gotoCoord.latitude(),
390 gotoCoord.longitude(),
391 vehicle->altitudeAMSL()->rawValue().toFloat());
392 } else {
393 vehicle->sendMavCommand(vehicle->defaultComponentId(),
394 MAV_CMD_DO_REPOSITION,
395 true, // show error is fails
396 -1.0f,
397 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
398 0.0f,
399 NAN,
400 static_cast<float>(gotoCoord.latitude()),
401 static_cast<float>(gotoCoord.longitude()),
402 vehicle->altitudeAMSL()->rawValue().toFloat());
403 }
404
405 return true;
406}
407
413
414static void _pauseVehicleThenChangeAltResultHandler(void* resultHandlerData, int /*compId*/, const mavlink_command_ack_t& ack, Vehicle::MavCmdResultFailureCode_t failureCode)
415{
416 if (ack.result != MAV_RESULT_ACCEPTED) {
417 switch (failureCode) {
419 qCDebug(PX4FirmwarePluginLog) << QStringLiteral("MAV_CMD_DO_REPOSITION error(%1)").arg(ack.result);
420 break;
422 qCDebug(PX4FirmwarePluginLog) << "MAV_CMD_DO_REPOSITION no response from vehicle";
423 break;
425 qCDebug(PX4FirmwarePluginLog) << "Internal Error: MAV_CMD_DO_REPOSITION could not be sent due to duplicate command";
426 break;
427 }
428 }
429
430 PauseVehicleThenChangeAltData_t* pData = static_cast<PauseVehicleThenChangeAltData_t*>(resultHandlerData);
431 pData->plugin->_changeAltAfterPause(resultHandlerData, ack.result == MAV_RESULT_ACCEPTED /* pauseSucceeded */);
432}
433
434void PX4FirmwarePlugin::_changeAltAfterPause(void* resultHandlerData, bool pauseSucceeded)
435{
436 PauseVehicleThenChangeAltData_t* pData = static_cast<PauseVehicleThenChangeAltData_t*>(resultHandlerData);
437
438 if (pauseSucceeded) {
439 pData->vehicle->sendMavCommand(
440 pData->vehicle->defaultComponentId(),
441 MAV_CMD_DO_REPOSITION,
442 true, // show error is fails
443 -1.0f, // Don't change groundspeed
444 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
445 0.0f, // Reserved
446 qQNaN(), qQNaN(), qQNaN(), // No change to yaw, lat, lon
447 static_cast<float>(pData->newAMSLAlt));
448 } else {
449 QGC::showAppMessage(tr("Unable to pause vehicle."));
450 }
451
452 delete pData;
453}
454
455void PX4FirmwarePlugin::guidedModeChangeAltitude(Vehicle* vehicle, double altitudeChange, bool pauseVehicle)
456{
457 if (!vehicle->homePosition().isValid()) {
458 QGC::showAppMessage(tr("Unable to change altitude, home position unknown."));
459 return;
460 }
461 if (qIsNaN(vehicle->homePosition().altitude())) {
462 QGC::showAppMessage(tr("Unable to change altitude, home position altitude unknown."));
463 return;
464 }
465
466 double currentAltRel = vehicle->altitudeRelative()->rawValue().toDouble();
467 double newAltRel = currentAltRel + altitudeChange;
468
470 resultData->plugin = this;
471 resultData->vehicle = vehicle;
472 resultData->newAMSLAlt = vehicle->homePosition().altitude() + newAltRel;
473
474 if (pauseVehicle) {
475 Vehicle::MavCmdAckHandlerInfo_t handlerInfo = {};
477 handlerInfo.resultHandlerData = resultData;
478
480 &handlerInfo,
481 vehicle->defaultComponentId(),
482 MAV_CMD_DO_REPOSITION,
483 -1.0f, // Don't change groundspeed
484 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
485 0.0f, // Reserved
486 qQNaN(), qQNaN(), qQNaN(), qQNaN()); // No change to yaw, lat, lon, alt
487 } else {
488 _changeAltAfterPause(resultData, true /* pauseSucceeded */);
489 }
490}
491
493{
494
495 vehicle->sendMavCommand(
496 vehicle->defaultComponentId(),
497 MAV_CMD_DO_CHANGE_SPEED,
498 true, // show error is fails
499 1, // 0: airspeed, 1: groundspeed
500 static_cast<float>(groundspeed), // groundspeed setpoint
501 -1, // throttle
502 0, // 0: absolute speed, 1: relative to current
503 NAN, NAN,NAN); // param 5-7 unused
504}
505
507{
508
509 vehicle->sendMavCommand(
510 vehicle->defaultComponentId(),
511 MAV_CMD_DO_CHANGE_SPEED,
512 true, // show error is fails
513 0, // 0: airspeed, 1: groundspeed
514 static_cast<float>(airspeed_equiv), // groundspeed setpoint
515 -1, // throttle
516 0, // 0: absolute speed, 1: relative to current
517 NAN, NAN,NAN); // param 5-7 unused
518}
519
520void PX4FirmwarePlugin::guidedModeChangeHeading(Vehicle* vehicle, const QGeoCoordinate &headingCoord) const
521{
523 QGC::showAppMessage(tr("Vehicle does not support guided rotate"));
524 return;
525 }
526
527 const float radians = qDegreesToRadians(vehicle->coordinate().azimuthTo(headingCoord));
528
529 vehicle->sendMavCommand(
530 vehicle->defaultComponentId(),
531 MAV_CMD_DO_REPOSITION,
532 true,
533 -1.0f, // no change in ground speed
534 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE, // switch to guided mode
535 0.0f, // reserved
536 radians, // change heading
537 NAN, NAN, NAN // no change lat, lon, alt
538 );
539}
540
542{
544 if (!_armVehicleAndValidate(vehicle)) {
545 QGC::showAppMessage(tr("Unable to start takeoff: Vehicle rejected arming."));
546 return;
547 }
548 } else {
549 QGC::showAppMessage(tr("Unable to start takeoff: Vehicle not changing to %1 flight mode.").arg(takeOffFlightMode()));
550 }
551}
552
554{
556 if (!_armVehicleAndValidate(vehicle)) {
557 QGC::showAppMessage(tr("Unable to start mission: Vehicle rejected arming."));
558 return;
559 }
560 } else {
561 QGC::showAppMessage(tr("Unable to start mission: Vehicle not changing to %1 flight mode.").arg(missionFlightMode()));
562 }
563}
564
565void PX4FirmwarePlugin::setGuidedMode(Vehicle* vehicle, bool guidedMode) const
566{
567 if (guidedMode) {
569 } else {
570 pauseVehicle(vehicle);
571 }
572}
573
578
583
588
593
598
603
608
613
618
619bool PX4FirmwarePlugin::isGuidedMode(const Vehicle* vehicle) const
620{
621 // Not supported by generic vehicle
622 return (vehicle->flightMode() == pauseFlightMode() || vehicle->flightMode() == takeOffFlightMode() || vehicle->flightMode() == landFlightMode());
623}
624
626{
627 //-- Don't process messages to/from UDP Bridge. It doesn't suffer from these issues
628 if (message->compid == MAV_COMP_ID_UDP_BRIDGE) {
629 return true;
630 }
631
632 switch (message->msgid) {
633 case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
634 _handleAutopilotVersion(vehicle, message);
635 break;
636 }
637
638 return true;
639}
640
641void PX4FirmwarePlugin::_handleAutopilotVersion(Vehicle* vehicle, mavlink_message_t* message)
642{
643 Q_UNUSED(vehicle);
644
645 auto* instanceData = qobject_cast<PX4FirmwarePluginInstanceData*>(vehicle->firmwarePluginInstanceData());
646 if (!instanceData->versionNotified) {
647 bool notifyUser = false;
648 int supportedMajorVersion = 1;
649 int supportedMinorVersion = 4;
650 int supportedPatchVersion = 1;
651
652 mavlink_autopilot_version_t version;
653 mavlink_msg_autopilot_version_decode(message, &version);
654
655 if (version.flight_sw_version != 0) {
656 int majorVersion, minorVersion, patchVersion;
657
658 majorVersion = (version.flight_sw_version >> (8*3)) & 0xFF;
659 minorVersion = (version.flight_sw_version >> (8*2)) & 0xFF;
660 patchVersion = (version.flight_sw_version >> (8*1)) & 0xFF;
661
662 if (majorVersion < supportedMajorVersion) {
663 notifyUser = true;
664 } else if (majorVersion == supportedMajorVersion) {
665 if (minorVersion < supportedMinorVersion) {
666 notifyUser = true;
667 } else if (minorVersion == supportedMinorVersion) {
668 notifyUser = patchVersion < supportedPatchVersion;
669 }
670 }
671 } else {
672 notifyUser = true;
673 }
674
675 if (notifyUser) {
676 instanceData->versionNotified = true;
677 QGC::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));
678 }
679 }
680}
681
682uint32_t PX4FirmwarePlugin::highLatencyCustomModeTo32Bits(uint16_t hlCustomMode) const
683{
684 union px4_custom_mode px4_cm;
685 px4_cm.data = 0;
686 px4_cm.custom_mode_hl = hlCustomMode;
687
688 return px4_cm.data;
689}
690
691QString PX4FirmwarePlugin::_getLatestVersionFileUrl(Vehicle* vehicle) const
692{
693 Q_UNUSED(vehicle);
694 return QStringLiteral("https://api.github.com/repos/PX4/Firmware/releases");
695}
696
697QString PX4FirmwarePlugin::_versionRegex() const
698{
699 return QStringLiteral("v([0-9,\\.]*) Stable");
700}
701
703{
704 return ((vehicle->vehicleType() == MAV_TYPE_GROUND_ROVER) || (vehicle->vehicleType() == MAV_TYPE_SUBMARINE));
705}
706
708{
709 static const char* HOOBS_HI = "LND_FLIGHT_T_HI";
710 static const char* HOOBS_LO = "LND_FLIGHT_T_LO";
711 uint64_t hobbsTimeSeconds = 0;
712
717 hobbsTimeSeconds = ((uint64_t)factHi->rawValue().toUInt() << 32 | (uint64_t)factLo->rawValue().toUInt()) / 1000000;
718 qCDebug(PX4FirmwarePluginLog) << "Hobbs Meter raw PX4:" << "(" << factHi->rawValue().toUInt() << factLo->rawValue().toUInt() << ")";
719 }
720
721 int hours = hobbsTimeSeconds / 3600;
722 int minutes = (hobbsTimeSeconds % 3600) / 60;
723 int seconds = hobbsTimeSeconds % 60;
724 QString timeStr = QString::asprintf("%04d:%02d:%02d", hours, minutes, seconds);
725 qCDebug(PX4FirmwarePluginLog) << "Hobbs Meter string:" << timeStr;
726 return timeStr;
727}
728
729bool PX4FirmwarePlugin::hasGripper(const Vehicle* vehicle) const
730{
731 if(vehicle->parameterManager()->parameterExists(ParameterManager::defaultComponentId, QStringLiteral("PD_GRIPPER_EN"))) {
732 bool _hasGripper = (vehicle->parameterManager()->getParameter(ParameterManager::defaultComponentId, QStringLiteral("PD_GRIPPER_EN"))->rawValue().toInt()) != 0 ? true : false;
733 return _hasGripper;
734 }
735 return false;
736}
737
739{
740 for(auto &mode: modeList){
741 PX4CustomMode::Mode cMode = static_cast<PX4CustomMode::Mode>(mode.custom_mode);
742
743 // Update Multi Rotor
744 switch (cMode) {
762 mode.multiRotor = true;
763 break;
765 mode.multiRotor = false;
766 break;
767 }
768
769 // Update Fixed Wing
770 switch (cMode){
776 mode.fixedWing = false;
777 break;
791 mode.fixedWing = true;
792 break;
793 }
794 }
795 _updateFlightModeList(modeList);
796}
797
798QVariant PX4FirmwarePlugin::expandedToolbarIndicatorSource(const Vehicle* /*vehicle*/, const QString& indicatorName) const
799{
800 if (indicatorName == "Battery") {
801 return QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/FirmwarePlugin/PX4/PX4BatteryIndicator.qml"));
802 } else if (indicatorName == "FlightMode") {
803 return QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/FirmwarePlugin/PX4/PX4FlightModeIndicator.qml"));
804 } else if (indicatorName == "MainStatus") {
805 return QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/FirmwarePlugin/PX4/PX4MainStatusIndicator.qml"));
806 }
807
808 return QVariant();
809}
QList< FirmwareFlightMode > FlightModeList
static void _pauseVehicleThenChangeAltResultHandler(void *resultHandlerData, int, const mavlink_command_ack_t &ack, Vehicle::MavCmdResultFailureCode_t failureCode)
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
struct __mavlink_command_ack_t mavlink_command_ack_t
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
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
void _setModeEnumToModeStringMapping(FlightModeCustomModeMap enumToString)
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
virtual double maximumHorizontalSpeedMultirotorMetersSecond(Vehicle *) const
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
void setGuidedMode(Vehicle *vehicle, bool guidedMode) const override
Set guided flight mode.
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.
bool guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius) const override
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.
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.
ParameterMetaData * _createParameterMetaData() final
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.
double maximumHorizontalSpeedMultirotorMetersSecond(Vehicle *vehicle) const override
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 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
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.
bool parameterExists(int componentId, const QString &paramName) const
Fact * getParameter(int componentId, const QString &paramName)
static constexpr int defaultComponentId
static SettingsManager * instance()
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
QString flightMode() const
Definition Vehicle.cc:1468
bool vtol() const
Definition Vehicle.cc:1763
QGeoCoordinate homePosition()
Definition Vehicle.cc:1434
bool multiRotor() const
Definition Vehicle.cc:1758
void setFirmwarePluginInstanceData(FirmwarePluginInstanceData *firmwarePluginInstanceData)
Definition Vehicle.cc:2527
uint64_t capabilityBits() const
Definition Vehicle.h:697
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:2175
int defaultComponentId() const
Definition Vehicle.h:670
ParameterManager * parameterManager()
Definition Vehicle.h:573
bool fixedWing() const
Definition Vehicle.cc:1738
QGeoCoordinate coordinate()
Definition Vehicle.h:409
void mavCommandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
class FirmwarePluginInstanceData * firmwarePluginInstanceData()
Definition Vehicle.h:685
void sendMavCommandWithHandler(const MavCmdAckHandlerInfo_t *ackHandlerInfo, int compId, MAV_CMD command, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Sends the command and calls the callback with the result.
Definition Vehicle.cc:2170
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
@ MavCmdResultFailureDuplicateCommand
Unable to send command since duplicate is already being waited on for response.
@ MavCmdResultCommandResultOnly
commandResult specifies full success/fail info
@ MavCmdResultFailureNoResponseToCommand
No response from vehicle to command.
uint16_t custom_mode_hl