24 QString
flightMode (uint8_t base_mode, uint32_t custom_mode)
const override;
61 QString
offlineEditingParamFile (
Vehicle* vehicle)
const override { Q_UNUSED(vehicle);
return QStringLiteral(
":/FirmwarePlugin/PX4/PX4.OfflineEditing.params"); }
62 QString
brandImageIndoor (
const Vehicle* vehicle)
const override { Q_UNUSED(vehicle);
return QStringLiteral(
"/qmlimages/PX4/BrandImage"); }
63 QString
brandImageOutdoor (
const Vehicle* vehicle)
const override { Q_UNUSED(vehicle);
return QStringLiteral(
"/qmlimages/PX4/BrandImage"); }
74 void _mavCommandResult(
int vehicleId,
int component,
int command,
int result,
int failureCode);
79 QString _getLatestVersionFileUrl (
Vehicle* vehicle)
const override;
80 QString _versionRegex ()
const override;
100 case MAV_CMD_DO_SET_MISSION_CURRENT:
QList< FirmwareFlightMode > FlightModeList
struct __mavlink_message mavlink_message_t
FirmwareCapabilities
Set of optional capabilites which firmware may support.
bool versionNotified
true: user notified over version issue
CommandSupportedResult anyVersionSupportsCommand(MAV_CMD cmd) const override
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 _internalParameterMetaDataFile(const Vehicle *vehicle) const override
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 autoDisarmParameter(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.
QString offlineEditingParamFile(Vehicle *vehicle) const override
Return the resource file which contains the set of params loaded for offline editing.
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 brandImageIndoor(const Vehicle *vehicle) const override
Return the resource file which contains the brand image for the vehicle for Indoor theme.
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
QString brandImageOutdoor(const Vehicle *vehicle) const override
Return the resource file which contains the brand image for the vehicle for Outdoor theme.
void guidedModeLand(Vehicle *vehicle) const override
Command vehicle to land at current location.