4#include <QtCore/QString>
5#include <QtCore/QVariantList>
6#include <QtPositioning/QGeoCoordinate>
33 bool cbs =
false,
bool adv =
false,
34 bool fWing =
false,
bool mRotor =
true
116 virtual QString
flightMode(uint8_t base_mode, uint32_t custom_mode)
const;
348 virtual QMap<QString, FactGroup*> *
factGroups() {
return nullptr; }
364 virtual bool hasGimbal(
Vehicle *vehicle,
bool &rollSupported,
bool &pitchSupported,
bool &yawSupported)
const;
386 virtual QString
getHobbsMeter(
Vehicle *vehicle)
const { Q_UNUSED(vehicle);
return QStringLiteral(
"Not Supported"); }
439 using QObject::QObject;
460 QMap<MAV_CMD, CommandSupportedResult> MAV_CMD_supported;
QMap< uint32_t, QString > FlightModeCustomModeMap
QList< FirmwareFlightMode > FlightModeList
struct __mavlink_message mavlink_message_t
Used to group Facts together into an object hierarachy.
virtual CommandSupportedResult anyVersionSupportsCommand(MAV_CMD) const
CommandSupportedResult getCommandSupported(MAV_CMD cmd) const
void setCommandSupported(MAV_CMD cmd, CommandSupportedResult status)
virtual bool supportsNegativeThrust(Vehicle *) const
void _setModeEnumToModeStringMapping(FlightModeCustomModeMap enumToString)
virtual QString motorDetectionFlightMode() const
Returns the flight mode for Motor Detection.
virtual QString pauseFlightMode() const
Returns The flight mode which indicates the vehicle is paused.
virtual QString brandImageOutdoor(const Vehicle *) const
Return the resource file which contains the brand image for the vehicle for Outdoor theme.
virtual void guidedModeChangeEquivalentAirspeedMetersSecond(Vehicle *vehicle, double airspeed_equiv) const
virtual void guidedModeChangeAltitude(Vehicle *vehicle, double altitudeChange, bool pauseVehicle)
virtual bool supportsThrottleModeCenterZero() const
virtual void startMission(Vehicle *vehicle) const
Command the vehicle to start the mission.
virtual void checkIfIsLatestStable(Vehicle *vehicle) const
Used to check if running firmware is latest stable version.
virtual double maximumHorizontalSpeedMultirotor(Vehicle *) const
FlightModeList _flightModeList
virtual bool multiRotorCoaxialMotors(Vehicle *) const
virtual double minimumEquivalentAirspeed(Vehicle *) const
virtual const QVariantList & toolIndicators(const Vehicle *vehicle)
virtual void guidedModeChangeGroundSpeedMetersSecond(Vehicle *vehicle, double groundspeed) const
virtual bool supportsMotorInterference() const
virtual bool setFlightMode(const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const
virtual ~FirmwarePlugin()
virtual bool supportsJSButton() 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 QString vehicleImageOutline(const Vehicle *) const
Return the resource file which contains the vehicle icon used in the flight view when the view is lig...
virtual void guidedModeTakeoff(Vehicle *vehicle, double takeoffAltRel) const
Command vehicle to takeoff from current location to the specified height.
virtual bool isCapable(const Vehicle *, FirmwareCapabilities) const
virtual double maximumEquivalentAirspeed(Vehicle *) const
virtual QString missionFlightMode() const
Returns the flight mode for running missions.
bool _setFlightModeAndValidate(Vehicle *vehicle, const QString &flightMode) const
virtual QString _internalParameterMetaDataFile(const Vehicle *) const
virtual uint32_t _convertToCustomFlightModeEnum(uint32_t val) const
QMap< int, remapParamNameMap_t > remapParamNameMinorVersionRemapMap_t
virtual QString _getLatestVersionFileUrl(Vehicle *) const
returns url with latest firmware release information.
void _updateFlightModeList(FlightModeList &flightModeList)
virtual void adjustMetaData(MAV_TYPE, FactMetaData *)
virtual bool adjustIncomingMavlinkMessage(Vehicle *, mavlink_message_t *)
virtual bool fixedWingAirSpeedLimitsAvailable(Vehicle *) const
virtual void guidedModeChangeHeading(Vehicle *vehicle, const QGeoCoordinate &headingCoord) const
Command vehicle to rotate towards specified location.
virtual QString smartRTLFlightMode() const
Returns the flight mode for Smart RTL.
virtual bool multiRotorXConfig(Vehicle *) const
virtual QString takeControlFlightMode() const
Returns the flight mode to use when the operator wants to take back control from autonomouse flight.
virtual int remapParamNameHigestMinorVersionNumber(int) const
Returns the highest major version number that is known to the remap for this specified major version.
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode) const
virtual QString vehicleImageOpaque(const Vehicle *) const
Return the resource file which contains the vehicle icon used in the flight view when the view is dar...
virtual void startTakeoff(Vehicle *vehicle) const
Command the vehicle to start a takeoff.
virtual QList< MAV_CMD > supportedMissionCommands(QGCMAVLink::VehicleClass_t) const
List of supported mission commands. Empty list for all commands supported.
void _addNewFlightMode(FirmwareFlightMode &flightMode)
virtual void pauseVehicle(Vehicle *vehicle) const
virtual QVariant expandedToolbarIndicatorSource(const Vehicle *, const QString &) const
virtual bool mulirotorSpeedLimitsAvailable(Vehicle *) const
virtual FactMetaData * _getMetaDataForFact(QObject *, const QString &, FactMetaData::ValueType_t, MAV_TYPE) const
int versionCompare(const Vehicle *vehicle, const QString &compare) const
virtual bool hasGripper(const Vehicle *) const
virtual QString landFlightMode() const
Returns the flight mode for Land.
virtual QString gotoFlightMode() const
Returns the flight mode which the vehicle will be in if it is performing a goto location.
virtual Autotune * createAutotune(Vehicle *vehicle) const
Creates Autotune object.
virtual QStringList flightModes(Vehicle *) const
virtual AutoPilotPlugin * autopilotPlugin(Vehicle *vehicle) const
virtual void guidedModeRTL(Vehicle *vehicle, bool smartRTL) const
Command vehicle to return to launch.
QVariantList _modeIndicatorList
virtual QString _versionRegex() const
Returns regex QString to extract version information from text.
virtual void _getParameterMetaDataVersionInfo(const QString &metaDataFile, int &majorVersion, int &minorVersion) const
virtual MavlinkCameraControl * createCameraControl(const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject *parent=nullptr) const
Camera control.
virtual QString autoDisarmParameter(Vehicle *) const
virtual QString stabilizedFlightMode() const
Returns the flight mode for Stabilized.
virtual QString brandImageIndoor(const Vehicle *) const
Return the resource file which contains the brand image for the vehicle for Indoor theme.
virtual void adjustOutgoingMavlinkMessageThreadSafe(Vehicle *, LinkInterface *, mavlink_message_t *)
bool _armVehicleAndValidate(Vehicle *vehicle) const
QVariantList _toolIndicatorList
void toolIndicatorsChanged()
virtual bool supportsRadio() const
virtual void updateAvailableFlightModes(FlightModeList &flightModeList)
Update Available flight modes recieved from vehicle.
virtual void setGuidedMode(Vehicle *vehicle, bool guidedMode) const
Set guided flight mode.
QMap< QString, QString > remapParamNameMap_t
virtual QString takeOffFlightMode() const
Returns the flight mode for TakeOff.
virtual void guidedModeGotoLocation(Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius=0.0) const
Command vehicle to move to specified location (altitude is included and relative)
FlightModeCustomModeMap _modeEnumToString
virtual QString followFlightMode() const
Returns the flight mode which the vehicle will be for follow me.
virtual uint32_t highLatencyCustomModeTo32Bits(uint16_t hlCustomMode) const
Convert from HIGH_LATENCY2.custom_mode value to correct 32 bit value.
virtual int defaultJoystickTXMode() const
virtual QString missionCommandOverrides(QGCMAVLink::VehicleClass_t vehicleClass) const
virtual void batteryConsumptionData(Vehicle *vehicle, int &mAhBattery, double &hoverAmps, double &cruiseAmps) const
virtual QGCCameraManager * createCameraManager(Vehicle *vehicle) const
Creates vehicle camera manager.
virtual QString offlineEditingParamFile(Vehicle *) const
Return the resource file which contains the set of params loaded for offline editing.
virtual void sendGCSMotionReport(Vehicle *vehicle, const FollowMe::GCSMotionReport &motionReport, uint8_t estimationCapabilities) const
Sends the appropriate mavlink message for follow me support.
QMap< int, remapParamNameMinorVersionRemapMap_t > remapParamNameMajorVersionMap_t
virtual QMap< QString, FactGroup * > * factGroups()
Returns a pointer to a dictionary of firmware-specific FactGroups.
virtual void initializeVehicle(Vehicle *)
Called when Vehicle is first created to perform any firmware specific setup.
virtual bool MAV_CMD_DO_SET_MODE_is_supported() const
returns true if this flight stack supports MAV_CMD_DO_SET_MODE
virtual QString rtlFlightMode() const
Returns the flight mode for RTL.
virtual QObject * _loadParameterMetaData(const QString &)
virtual const remapParamNameMajorVersionMap_t & paramNameRemapMajorVersionMap() const
Returns the mapping structure which is used to map from one parameter name to another based on firmwa...
virtual bool supportsSmartRTL() const
virtual void guidedModeLand(Vehicle *vehicle) const
Command vehicle to land at current location.
virtual bool sendHomePositionToVehicle() const
virtual bool isGuidedMode(const Vehicle *) const
Returns whether the vehicle is in guided mode or not.
virtual bool hasGimbal(Vehicle *vehicle, bool &rollSupported, bool &pitchSupported, bool &yawSupported) const
virtual double minimumTakeoffAltitudeMeters(Vehicle *) const
virtual void _versionFileDownloadFinished(const QString &remoteFile, const QString &localFile, const Vehicle *vehicle) const
Callback to process file with latest release information.
virtual QString getHobbsMeter(Vehicle *vehicle) const
gets hobbs meter from autopilot. This should be reimplmeented for each firmware
The link interface defines the interface for all links used to communicate with the ground station ap...
Abstract base class for all camera controls: real and simulated.
FirmwareFlightMode(const QString &mName, uint8_t sMode, uint32_t cMode, bool cbs=false, bool adv=false, bool fWing=false, bool mRotor=true)
FirmwareFlightMode(const QString &mName, uint32_t cMode, bool cbs=false, bool adv=false)