19 , versionNotified(false)
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");
100 QStringList flightModesList;
104 bool fw = (vehicle->
fixedWing() && mode.fixedWing);
105 bool mc = (vehicle->
multiRotor() && mode.multiRotor);
109 if (fw || mc || other) {
110 flightModesList += mode.mode_name;
115 return flightModesList;
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));
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;
146 qCWarning(PX4FirmwarePluginLog) <<
"Unknown flight Mode" <<
flightMode;
165 return (capabilities & available) == capabilities;
187 qCWarning(PX4FirmwarePluginLog) <<
"Internal error: pointer passed to PX4FirmwarePlugin::getMetaDataForFact not PX4ParameterMetaData";
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,
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,
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,
218 MAV_CMD_CONDITION_YAW,
219 MAV_CMD_NAV_LOITER_TO_ALT,
223 QList<MAV_CMD> vtolCommands = {
224 MAV_CMD_DO_VTOL_TRANSITION, MAV_CMD_NAV_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_LAND,
227 QList<MAV_CMD> flightCommands = {
228 MAV_CMD_NAV_LAND, MAV_CMD_NAV_TAKEOFF,
232 supportedCommands += vtolCommands;
233 supportedCommands += flightCommands;
236 supportedCommands += vtolCommands;
237 supportedCommands += flightCommands;
239 supportedCommands += flightCommands;
242 if (SettingsManager::instance()->planViewSettings()->useConditionGate()->rawValue().toBool()) {
243 supportedCommands.append(MAV_CMD_CONDITION_GATE);
246 return supportedCommands;
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");
265 qCWarning(PX4FirmwarePluginLog) <<
"PX4FirmwarePlugin::missionCommandOverrides called with bad VehicleClass_t:" << vehicleClass;
273 if (!metaDataFile.isEmpty()) {
282 MAV_CMD_DO_REPOSITION,
285 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
304void PX4FirmwarePlugin::_mavCommandResult(
int vehicleId,
int component,
int command,
int result,
int failureCode)
306 Q_UNUSED(vehicleId); Q_UNUSED(component); Q_UNUSED(failureCode);
308 auto* vehicle = qobject_cast<Vehicle*>(sender());
310 qCWarning(PX4FirmwarePluginLog) <<
"Dynamic cast failed!";
314 if (command == MAV_CMD_NAV_TAKEOFF && result == MAV_RESULT_ACCEPTED) {
319 if (!vehicle->armed()) {
320 vehicle->setArmedShowError(
true);
327 double vehicleAltitudeAMSL = vehicle->altitudeAMSL()->rawValue().toDouble();
328 if (qIsNaN(vehicleAltitudeAMSL)) {
329 qgcApp()->showAppMessage(tr(
"Unable to takeoff, vehicle position not known."));
333 double takeoffAltAMSL = takeoffAltRel + vehicleAltitudeAMSL;
343 static_cast<float>(takeoffAltAMSL));
348 QString speedParam(
"MPC_XY_VEL_MAX");
359 QString airspeedMax(
"FW_AIRSPD_MAX");
370 QString airspeedMin(
"FW_AIRSPD_MIN");
394 Q_UNUSED(forwardFlightLoiterRadius)
396 if (qIsNaN(vehicle->altitudeAMSL()->rawValue().toDouble())) {
397 qgcApp()->showAppMessage(tr(
"Unable to go to location, vehicle position not known."));
401 if (vehicle->
capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
403 MAV_CMD_DO_REPOSITION,
407 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
410 gotoCoord.latitude(),
411 gotoCoord.longitude(),
412 vehicle->altitudeAMSL()->rawValue().toFloat());
415 MAV_CMD_DO_REPOSITION,
418 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
421 static_cast<float>(gotoCoord.latitude()),
422 static_cast<float>(gotoCoord.longitude()),
423 vehicle->altitudeAMSL()->rawValue().toFloat());
435 if (ack.result != MAV_RESULT_ACCEPTED) {
436 switch (failureCode) {
438 qCDebug(PX4FirmwarePluginLog) << QStringLiteral(
"MAV_CMD_DO_REPOSITION error(%1)").arg(ack.result);
441 qCDebug(PX4FirmwarePluginLog) <<
"MAV_CMD_DO_REPOSITION no response from vehicle";
444 qCDebug(PX4FirmwarePluginLog) <<
"Internal Error: MAV_CMD_DO_REPOSITION could not be sent due to duplicate command";
457 if (pauseSucceeded) {
460 MAV_CMD_DO_REPOSITION,
463 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
465 qQNaN(), qQNaN(), qQNaN(),
468 qgcApp()->showAppMessage(tr(
"Unable to pause vehicle."));
477 qgcApp()->showAppMessage(tr(
"Unable to change altitude, home position unknown."));
481 qgcApp()->showAppMessage(tr(
"Unable to change altitude, home position altitude unknown."));
485 double currentAltRel = vehicle->altitudeRelative()->rawValue().toDouble();
486 double newAltRel = currentAltRel + altitudeChange;
489 resultData->
plugin =
this;
501 MAV_CMD_DO_REPOSITION,
503 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
505 qQNaN(), qQNaN(), qQNaN(), qQNaN());
516 MAV_CMD_DO_CHANGE_SPEED,
519 static_cast<float>(groundspeed),
530 MAV_CMD_DO_CHANGE_SPEED,
533 static_cast<float>(airspeed_equiv),
542 qgcApp()->showAppMessage(tr(
"Vehicle does not support guided rotate"));
546 const float radians = qDegreesToRadians(vehicle->
coordinate().azimuthTo(headingCoord));
550 MAV_CMD_DO_REPOSITION,
553 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
564 qgcApp()->showAppMessage(tr(
"Unable to start takeoff: Vehicle rejected arming."));
568 qgcApp()->showAppMessage(tr(
"Unable to start takeoff: Vehicle not changing to %1 flight mode.").arg(
takeOffFlightMode()));
576 qgcApp()->showAppMessage(tr(
"Unable to start mission: Vehicle rejected arming."));
580 qgcApp()->showAppMessage(tr(
"Unable to start mission: Vehicle not changing to %1 flight mode.").arg(
missionFlightMode()));
647 if (message->compid == MAV_COMP_ID_UDP_BRIDGE) {
651 switch (message->msgid) {
652 case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
653 _handleAutopilotVersion(vehicle, message);
665 if (!instanceData->versionNotified) {
666 bool notifyUser =
false;
667 int supportedMajorVersion = 1;
668 int supportedMinorVersion = 4;
669 int supportedPatchVersion = 1;
671 mavlink_autopilot_version_t version;
672 mavlink_msg_autopilot_version_decode(message, &version);
674 if (version.flight_sw_version != 0) {
675 int majorVersion, minorVersion, patchVersion;
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;
681 if (majorVersion < supportedMajorVersion) {
683 }
else if (majorVersion == supportedMajorVersion) {
684 if (minorVersion < supportedMinorVersion) {
686 }
else if (minorVersion == supportedMinorVersion) {
687 notifyUser = patchVersion < supportedPatchVersion;
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));
710QString PX4FirmwarePlugin::_getLatestVersionFileUrl(
Vehicle* vehicle)
const
713 return QStringLiteral(
"https://api.github.com/repos/PX4/Firmware/releases");
716QString PX4FirmwarePlugin::_versionRegex()
const
718 return QStringLiteral(
"v([0-9,\\.]*) Stable");
723 return ((vehicle->
vehicleType() == MAV_TYPE_GROUND_ROVER) || (vehicle->
vehicleType() == MAV_TYPE_SUBMARINE));
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;
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() <<
")";
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;
759 for(
auto &mode: modeList){
781 mode.multiRotor =
true;
784 mode.multiRotor =
false;
795 mode.fixedWing =
false;
810 mode.fixedWing =
true;
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"));
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)
A Fact is used to hold a single value within the system.
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
virtual ~PX4FirmwarePlugin()
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.
bool parameterExists(int componentId, const QString ¶mName) const
Fact * getParameter(int componentId, const QString ¶mName)
static constexpr int defaultComponentId
static constexpr const VehicleClass_t VehicleClassSub
static constexpr const VehicleClass_t VehicleClassFixedWing
static constexpr const VehicleClass_t VehicleClassMultiRotor
static constexpr const VehicleClass_t VehicleClassRoverBoat
static constexpr const VehicleClass_t VehicleClassVTOL
static constexpr const VehicleClass_t VehicleClassGeneric
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)
QString flightMode() const
QGeoCoordinate homePosition()
void setFirmwarePluginInstanceData(FirmwarePluginInstanceData *firmwarePluginInstanceData)
uint64_t capabilityBits() const
MAV_TYPE vehicleType() const
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)
MavCmdResultFailureCode_t
@ MavCmdResultFailureNoResponseToCommand
No response from vehicle to command.
@ MavCmdResultCommandResultOnly
commandResult specifies full success/fail info
@ MavCmdResultFailureDuplicateCommand
Unable to send command since duplicate is already being waited on for response.
int defaultComponentId() const
ParameterManager * parameterManager()
QGeoCoordinate coordinate()
void mavCommandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
class FirmwarePluginInstanceData * firmwarePluginInstanceData()
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.
PX4FirmwarePlugin * plugin
MavCmdResultHandler resultHandler
void * resultHandlerData
‍nullptr for no handler