12#include <QtCore/QString>
20 , versionNotified(false)
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");
101 QStringList flightModesList;
105 bool fw = (vehicle->
fixedWing() && mode.fixedWing);
106 bool mc = (vehicle->
multiRotor() && mode.multiRotor);
110 if (fw || mc || other) {
111 flightModesList += mode.mode_name;
116 return flightModesList;
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));
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;
147 qCWarning(PX4FirmwarePluginLog) <<
"Unknown flight Mode" <<
flightMode;
166 return (capabilities & available) == capabilities;
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,
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,
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,
201 MAV_CMD_CONDITION_YAW,
202 MAV_CMD_NAV_LOITER_TO_ALT,
206 QList<MAV_CMD> vtolCommands = {
207 MAV_CMD_DO_VTOL_TRANSITION, MAV_CMD_NAV_VTOL_TAKEOFF, MAV_CMD_NAV_VTOL_LAND,
210 QList<MAV_CMD> flightCommands = {
211 MAV_CMD_NAV_LAND, MAV_CMD_NAV_TAKEOFF,
215 supportedCommands += vtolCommands;
216 supportedCommands += flightCommands;
219 supportedCommands += vtolCommands;
220 supportedCommands += flightCommands;
222 supportedCommands += flightCommands;
226 supportedCommands.append(MAV_CMD_CONDITION_GATE);
229 return supportedCommands;
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");
248 qCWarning(PX4FirmwarePluginLog) <<
"PX4FirmwarePlugin::missionCommandOverrides called with bad VehicleClass_t:" << vehicleClass;
261 MAV_CMD_DO_REPOSITION,
264 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
283void PX4FirmwarePlugin::_mavCommandResult(
int vehicleId,
int component,
int command,
int result,
int failureCode)
285 Q_UNUSED(vehicleId); Q_UNUSED(component); Q_UNUSED(failureCode);
287 auto* vehicle = qobject_cast<Vehicle*>(sender());
289 qCWarning(PX4FirmwarePluginLog) <<
"Dynamic cast failed!";
293 if (command == MAV_CMD_NAV_TAKEOFF && result == MAV_RESULT_ACCEPTED) {
298 if (!vehicle->armed()) {
299 vehicle->setArmedShowError(
true);
307 if (qIsNaN(vehicleAltitudeAMSL)) {
312 double takeoffAltAMSL = takeoffAltRel + vehicleAltitudeAMSL;
322 static_cast<float>(takeoffAltAMSL));
327 QString speedParam(
"MPC_XY_VEL_MAX");
338 QString airspeedMax(
"FW_AIRSPD_MAX");
349 QString airspeedMin(
"FW_AIRSPD_MIN");
373 Q_UNUSED(forwardFlightLoiterRadius)
380 if (vehicle->
capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
382 MAV_CMD_DO_REPOSITION,
386 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
389 gotoCoord.latitude(),
390 gotoCoord.longitude(),
394 MAV_CMD_DO_REPOSITION,
397 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
400 static_cast<float>(gotoCoord.latitude()),
401 static_cast<float>(gotoCoord.longitude()),
416 if (ack.result != MAV_RESULT_ACCEPTED) {
417 switch (failureCode) {
419 qCDebug(PX4FirmwarePluginLog) << QStringLiteral(
"MAV_CMD_DO_REPOSITION error(%1)").arg(ack.result);
422 qCDebug(PX4FirmwarePluginLog) <<
"MAV_CMD_DO_REPOSITION no response from vehicle";
425 qCDebug(PX4FirmwarePluginLog) <<
"Internal Error: MAV_CMD_DO_REPOSITION could not be sent due to duplicate command";
438 if (pauseSucceeded) {
441 MAV_CMD_DO_REPOSITION,
444 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
446 qQNaN(), qQNaN(), qQNaN(),
467 double newAltRel = currentAltRel + altitudeChange;
470 resultData->
plugin =
this;
482 MAV_CMD_DO_REPOSITION,
484 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
486 qQNaN(), qQNaN(), qQNaN(), qQNaN());
497 MAV_CMD_DO_CHANGE_SPEED,
500 static_cast<float>(groundspeed),
511 MAV_CMD_DO_CHANGE_SPEED,
514 static_cast<float>(airspeed_equiv),
527 const float radians = qDegreesToRadians(vehicle->
coordinate().azimuthTo(headingCoord));
531 MAV_CMD_DO_REPOSITION,
534 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE,
628 if (message->compid == MAV_COMP_ID_UDP_BRIDGE) {
632 switch (message->msgid) {
633 case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
634 _handleAutopilotVersion(vehicle, message);
646 if (!instanceData->versionNotified) {
647 bool notifyUser =
false;
648 int supportedMajorVersion = 1;
649 int supportedMinorVersion = 4;
650 int supportedPatchVersion = 1;
652 mavlink_autopilot_version_t version;
653 mavlink_msg_autopilot_version_decode(message, &version);
655 if (version.flight_sw_version != 0) {
656 int majorVersion, minorVersion, patchVersion;
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;
662 if (majorVersion < supportedMajorVersion) {
664 }
else if (majorVersion == supportedMajorVersion) {
665 if (minorVersion < supportedMinorVersion) {
667 }
else if (minorVersion == supportedMinorVersion) {
668 notifyUser = patchVersion < supportedPatchVersion;
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));
691QString PX4FirmwarePlugin::_getLatestVersionFileUrl(
Vehicle* vehicle)
const
694 return QStringLiteral(
"https://api.github.com/repos/PX4/Firmware/releases");
697QString PX4FirmwarePlugin::_versionRegex()
const
699 return QStringLiteral(
"v([0-9,\\.]*) Stable");
704 return ((vehicle->
vehicleType() == MAV_TYPE_GROUND_ROVER) || (vehicle->
vehicleType() == MAV_TYPE_SUBMARINE));
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;
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() <<
")";
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;
740 for(
auto &mode: modeList){
762 mode.multiRotor =
true;
765 mode.multiRotor =
false;
776 mode.fixedWing =
false;
791 mode.fixedWing =
true;
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"));
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.
QVariant rawValue() const
Value after translation.
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.
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.
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 ¶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 SettingsManager * instance()
Fact * altitudeRelative()
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)
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.
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
PX4FirmwarePlugin * plugin
static constexpr VehicleClass_t VehicleClassGeneric
Callback info bundle for sendMavCommandWithHandler.
MavCmdResultHandler resultHandler
nullptr for no handler
MavCmdResultFailureCode_t
@ 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.