|
QGroundControl
Ground Control Station for MAVLink Drones
|
#include <ArduSubFirmwarePlugin.h>
Inheritance diagram for ArduSubFirmwarePlugin:
Collaboration diagram for ArduSubFirmwarePlugin:Public Member Functions | |
| ArduSubFirmwarePlugin (QObject *parent=nullptr) | |
| ~ArduSubFirmwarePlugin () | |
| int | defaultJoystickTXMode () const override |
| void | initializeStreamRates (Vehicle *vehicle) override |
| bool | isCapable (const Vehicle *vehicle, FirmwareCapabilities capabilities) const override |
| bool | supportsThrottleModeCenterZero () const override |
| bool | supportsRadio () const override |
| bool | supportsJSButton () const override |
| bool | supportsMotorInterference () const override |
| QString | vehicleImageOpaque (const Vehicle *) const override |
| Return the resource file which contains the vehicle icon used in the flight view when the view is dark (Satellite for instance) | |
| QString | vehicleImageOutline (const Vehicle *vehicle) const override |
| Return the resource file which contains the vehicle icon used in the flight view when the view is light (Map for instance) | |
| QString | brandImageIndoor (const Vehicle *vehicle) const override |
| Return the resource file which contains the brand image for the vehicle for Indoor theme. | |
| QString | brandImageOutdoor (const Vehicle *vehicle) const override |
| Return the resource file which contains the brand image for the vehicle for Outdoor theme. | |
| const FirmwarePlugin::remapParamNameMajorVersionMap_t & | paramNameRemapMajorVersionMap () const override |
| Returns the mapping structure which is used to map from one parameter name to another based on firmware version. | |
| int | remapParamNameHigestMinorVersionNumber (int majorVersionNumber) const override |
| Returns the highest major version number that is known to the remap for this specified major version. | |
| bool | adjustIncomingMavlinkMessage (Vehicle *vehicle, mavlink_message_t *message) override |
| QMap< QString, FactGroup * > * | factGroups () override |
| Returns a pointer to a dictionary of firmware-specific FactGroups. | |
| void | adjustMetaData (MAV_TYPE vehicleType, FactMetaData *metaData) override |
| QString | stabilizedFlightMode () const override |
| Returns the flight mode for Stabilized. | |
| QString | motorDetectionFlightMode () const override |
| Returns the flight mode for Motor Detection. | |
| void | updateAvailableFlightModes (FlightModeList &modeList) override |
| Update Available flight modes recieved from vehicle. | |
| QString | offlineEditingParamFile (Vehicle *vehicle) const override |
| Return the resource file which contains the set of params loaded for offline editing. | |
Public Member Functions inherited from APMFirmwarePlugin | |
| QList< MAV_CMD > | supportedMissionCommands (QGCMAVLink::VehicleClass_t vehicleClass) const override |
| List of supported mission commands. Empty list for all commands supported. | |
| AutoPilotPlugin * | autopilotPlugin (Vehicle *vehicle) const override |
| void | setGuidedMode (Vehicle *vehicle, bool guidedMode) const override |
| Set guided flight mode. | |
| void | guidedModeTakeoff (Vehicle *vehicle, double altitudeRel) const override |
| Command vehicle to takeoff from current location to the specified height. | |
| void | guidedModeGotoLocation (Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius) const override |
| Command vehicle to move to specified location (altitude is included and relative) | |
| double | minimumTakeoffAltitudeMeters (Vehicle *vehicle) const override |
| void | startTakeoff (Vehicle *vehicle) const override |
| Command the vehicle to start a takeoff. | |
| void | startMission (Vehicle *vehicle) const override |
| Command the vehicle to start the mission. | |
| QStringList | flightModes (Vehicle *vehicle) const override |
| QString | flightMode (uint8_t base_mode, uint32_t custom_mode) const override |
| bool | setFlightMode (const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const override |
| bool | MAV_CMD_DO_SET_MODE_is_supported () const override |
| returns true if this flight stack supports MAV_CMD_DO_SET_MODE | |
| bool | isGuidedMode (const Vehicle *vehicle) const override |
| Returns whether the vehicle is in guided mode or not. | |
| QString | gotoFlightMode () const override |
| Returns the flight mode which the vehicle will be in if it is performing a goto location. | |
| QString | rtlFlightMode () const override |
| Returns the flight mode for RTL. | |
| QString | smartRTLFlightMode () const override |
| Returns the flight mode for Smart RTL. | |
| QString | missionFlightMode () const override |
| Returns the flight mode for running missions. | |
| virtual QString | guidedFlightMode () const |
| void | pauseVehicle (Vehicle *vehicle) const override |
| void | guidedModeRTL (Vehicle *vehicle, bool smartRTL) const override |
| Command vehicle to return to launch. | |
| void | guidedModeChangeAltitude (Vehicle *vehicle, double altitudeChange, bool pauseVehicle) override |
| void | guidedModeChangeHeading (Vehicle *vehicle, const QGeoCoordinate &headingCoord) const override |
| Command vehicle to rotate towards specified location. | |
| void | adjustOutgoingMavlinkMessageThreadSafe (Vehicle *vehicle, LinkInterface *outgoingLink, mavlink_message_t *message) override |
| void | initializeVehicle (Vehicle *vehicle) override |
| Called when Vehicle is first created to perform any firmware specific setup. | |
| bool | sendHomePositionToVehicle () const override |
| QString | missionCommandOverrides (QGCMAVLink::VehicleClass_t vehicleClass) const override |
| QString | _internalParameterMetaDataFile (const Vehicle *vehicle) const override |
| FactMetaData * | _getMetaDataForFact (QObject *parameterMetaData, const QString &name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) const override |
| void | _getParameterMetaDataVersionInfo (const QString &metaDataFile, int &majorVersion, int &minorVersion) const override |
| QObject * | _loadParameterMetaData (const QString &metaDataFile) override |
| QString | getHobbsMeter (Vehicle *vehicle) const override |
| gets hobbs meter from autopilot. This should be reimplmeented for each firmware | |
| bool | hasGripper (const Vehicle *vehicle) const override |
| const QVariantList & | toolIndicators (const Vehicle *vehicle) override |
| double | maximumEquivalentAirspeed (Vehicle *vehicle) const override |
| double | minimumEquivalentAirspeed (Vehicle *vehicle) const override |
| bool | fixedWingAirSpeedLimitsAvailable (Vehicle *vehicle) const override |
| void | guidedModeChangeEquivalentAirspeedMetersSecond (Vehicle *vehicle, double airspeed_equiv) const override |
| void | sendGCSMotionReport (Vehicle *vehicle, const FollowMe::GCSMotionReport &motionReport, uint8_t estimatationCapabilities) const override |
| Sends the appropriate mavlink message for follow me support. | |
| QVariant | expandedToolbarIndicatorSource (const Vehicle *vehicle, const QString &indicatorName) const override |
| bool | mulirotorSpeedLimitsAvailable (Vehicle *vehicle) const override |
| double | maximumHorizontalSpeedMultirotor (Vehicle *vehicle) const override |
| void | guidedModeChangeGroundSpeedMetersSecond (Vehicle *vehicle, double speed) const override |
Public Member Functions inherited from FirmwarePlugin | |
| FirmwarePlugin (QObject *parent=nullptr) | |
| virtual | ~FirmwarePlugin () |
| virtual QString | pauseFlightMode () const |
| Returns The flight mode which indicates the vehicle is paused. | |
| virtual bool | supportsSmartRTL () const |
| virtual QString | landFlightMode () const |
| Returns the flight mode for Land. | |
| virtual QString | takeOffFlightMode () const |
| Returns the flight mode for TakeOff. | |
| virtual QString | takeControlFlightMode () const |
| Returns the flight mode to use when the operator wants to take back control from autonomouse flight. | |
| virtual QString | followFlightMode () const |
| Returns the flight mode which the vehicle will be for follow me. | |
| virtual void | guidedModeLand (Vehicle *vehicle) const |
| Command vehicle to land at current location. | |
| virtual bool | supportsNegativeThrust (Vehicle *) const |
| virtual bool | multiRotorCoaxialMotors (Vehicle *) const |
| virtual bool | multiRotorXConfig (Vehicle *) const |
| virtual QGCCameraManager * | createCameraManager (Vehicle *vehicle) const |
| Creates vehicle camera manager. | |
| virtual MavlinkCameraControl * | createCameraControl (const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject *parent=nullptr) const |
| Camera control. | |
| virtual void | batteryConsumptionData (Vehicle *vehicle, int &mAhBattery, double &hoverAmps, double &cruiseAmps) const |
| virtual QString | autoDisarmParameter (Vehicle *) const |
| virtual bool | hasGimbal (Vehicle *vehicle, bool &rollSupported, bool &pitchSupported, bool &yawSupported) const |
| virtual uint32_t | highLatencyCustomModeTo32Bits (uint16_t hlCustomMode) const |
| Convert from HIGH_LATENCY2.custom_mode value to correct 32 bit value. | |
| virtual void | checkIfIsLatestStable (Vehicle *vehicle) const |
| Used to check if running firmware is latest stable version. | |
| int | versionCompare (const Vehicle *vehicle, const QString &compare) const |
| int | versionCompare (const Vehicle *vehicle, int major, int minor, int patch) const |
| virtual Autotune * | createAutotune (Vehicle *vehicle) const |
| Creates Autotune object. | |
Protected Member Functions | |
| uint32_t | _convertToCustomFlightModeEnum (uint32_t val) const override |
Protected Member Functions inherited from APMFirmwarePlugin | |
| APMFirmwarePlugin (QObject *parent=nullptr) | |
| All access to singleton is through stack specific implementation. | |
| virtual | ~APMFirmwarePlugin () |
| void | setSupportedModes (QList< APMCustomMode > supportedModes) |
Protected Member Functions inherited from FirmwarePlugin | |
| bool | _armVehicleAndValidate (Vehicle *vehicle) const |
| bool | _setFlightModeAndValidate (Vehicle *vehicle, const QString &flightMode) const |
| virtual void | _versionFileDownloadFinished (const QString &remoteFile, const QString &localFile, const Vehicle *vehicle) const |
| Callback to process file with latest release information. | |
| void | _setModeEnumToModeStringMapping (FlightModeCustomModeMap enumToString) |
| void | _updateFlightModeList (FlightModeList &flightModeList) |
| void | _addNewFlightMode (FirmwareFlightMode &flightMode) |
Protected Attributes | |
| const QString | _manualFlightMode = tr("Manual") |
| const QString | _stabilizeFlightMode = tr("Stabilize") |
| const QString | _acroFlightMode = tr("Acro") |
| const QString | _altHoldFlightMode = tr("Depth Hold") |
| const QString | _autoFlightMode = tr("Auto") |
| const QString | _guidedFlightMode = tr("Guided") |
| const QString | _circleFlightMode = tr("Circle") |
| const QString | _surfaceFlightMode = tr("Surface") |
| const QString | _posHoldFlightMode =tr("Position Hold") |
| const QString | _motorDetectionFlightMode = tr("Motor Detection") |
| const QString | _surftrakFlightMode = tr("Surftrak") |
Protected Attributes inherited from APMFirmwarePlugin | |
| bool | _coaxialMotors = false |
| const QString | _guidedFlightMode = tr("Guided") |
| const QString | _rtlFlightMode = tr("RTL") |
| const QString | _smartRtlFlightMode = tr("Smart RTL") |
| const QString | _autoFlightMode = tr("Auto") |
Protected Attributes inherited from FirmwarePlugin | |
| FlightModeList | _flightModeList |
| FlightModeCustomModeMap | _modeEnumToString |
| QVariantList | _toolIndicatorList |
| QVariantList | _modeIndicatorList |
Additional Inherited Members | |
Public Types inherited from FirmwarePlugin | |
| enum | FirmwareCapabilities { SetFlightModeCapability = 1 << 0 , PauseVehicleCapability = 1 << 1 , GuidedModeCapability = 1 << 2 , OrbitModeCapability = 1 << 3 , TakeoffVehicleCapability = 1 << 4 , ROIModeCapability = 1 << 5 , ChangeHeadingCapability = 1 << 6 , GuidedTakeoffCapability = 1 << 7 } |
| Set of optional capabilites which firmware may support. More... | |
| typedef QMap< QString, QString > | remapParamNameMap_t |
| typedef QMap< int, remapParamNameMap_t > | remapParamNameMinorVersionRemapMap_t |
| typedef QMap< int, remapParamNameMinorVersionRemapMap_t > | remapParamNameMajorVersionMap_t |
Signals inherited from FirmwarePlugin | |
| void | toolIndicatorsChanged () |
Static Public Member Functions inherited from APMFirmwarePlugin | |
| static QPair< QMetaObject::Connection, QMetaObject::Connection > | startCompensatingBaro (Vehicle *vehicle) |
| static bool | stopCompensatingBaro (const Vehicle *vehicle, QPair< QMetaObject::Connection, QMetaObject::Connection > updaters) |
| static qreal | calcAltOffsetPT (uint32_t atmospheric1, qreal temperature1, uint32_t atmospheric2, qreal temperature2) |
| static qreal | calcAltOffsetP (uint32_t atmospheric1, uint32_t atmospheric2) |
Definition at line 77 of file ArduSubFirmwarePlugin.h.
|
explicit |
Definition at line 93 of file ArduSubFirmwarePlugin.cc.
References _acroFlightMode, _altHoldFlightMode, _autoFlightMode, _circleFlightMode, _guidedFlightMode, _manualFlightMode, _motorDetectionFlightMode, _posHoldFlightMode, FirmwarePlugin::_setModeEnumToModeStringMapping(), _stabilizeFlightMode, _surfaceFlightMode, _surftrakFlightMode, APMSubMode::ACRO, APMSubMode::ALT_HOLD, APMSubMode::AUTO, APMSubMode::CIRCLE, APMSubMode::GUIDED, APMSubMode::MANUAL, APMSubMode::MOTORDETECTION, APMSubMode::POSHOLD, APMSubMode::STABILIZE, APMSubMode::SURFACE, APMSubMode::SURFTRAK, and updateAvailableFlightModes().
| ArduSubFirmwarePlugin::~ArduSubFirmwarePlugin | ( | ) |
Definition at line 140 of file ArduSubFirmwarePlugin.cc.
|
overrideprotectedvirtual |
Reimplemented from FirmwarePlugin.
Definition at line 76 of file ArduSubFirmwarePlugin.cc.
References APMCustomMode::AUTO, APMSubMode::AUTO, APMCustomMode::GUIDED, and APMSubMode::GUIDED.
|
overridevirtual |
Called before any mavlink message is processed by Vehicle such that the firmwre plugin can adjust any message characteristics. This is handy to adjust or differences in mavlink spec implementations such that the base code can remain mavlink generic.
| vehicle | Vehicle message came from |
| message[in,out] | Mavlink message to adjust if needed. |
Reimplemented from APMFirmwarePlugin.
Definition at line 213 of file ArduSubFirmwarePlugin.cc.
References APMFirmwarePlugin::adjustIncomingMavlinkMessage().
|
overridevirtual |
Allows the Firmware plugin to override the facts meta data.
| vehicleType | - Type of current vehicle |
| metaData | - MetaData for fact |
Reimplemented from FirmwarePlugin.
Definition at line 43 of file ArduSubFirmwarePlugin.cc.
References FactMetaData::name(), and FactMetaData::setShortDescription().
|
inlineoverridevirtual |
Return the resource file which contains the brand image for the vehicle for Indoor theme.
Reimplemented from APMFirmwarePlugin.
Definition at line 99 of file ArduSubFirmwarePlugin.h.
|
inlineoverridevirtual |
Return the resource file which contains the brand image for the vehicle for Outdoor theme.
Reimplemented from APMFirmwarePlugin.
Definition at line 100 of file ArduSubFirmwarePlugin.h.
|
inlineoverridevirtual |
Default tx mode to apply to joystick axes TX modes are as outlined here: http://www.rc-airplane-world.com/rc-transmitter-modes.html
Reimplemented from FirmwarePlugin.
Definition at line 85 of file ArduSubFirmwarePlugin.h.
|
overridevirtual |
Returns a pointer to a dictionary of firmware-specific FactGroups.
Reimplemented from FirmwarePlugin.
Definition at line 219 of file ArduSubFirmwarePlugin.cc.
|
overridevirtual |
Reimplemented from APMFirmwarePlugin.
Definition at line 151 of file ArduSubFirmwarePlugin.cc.
References Vehicle::requestDataStream().
|
overridevirtual |
Reimplemented from APMFirmwarePlugin.
Definition at line 162 of file ArduSubFirmwarePlugin.cc.
References FirmwarePlugin::GuidedModeCapability, FirmwarePlugin::PauseVehicleCapability, and FirmwarePlugin::SetFlightModeCapability.
|
overridevirtual |
Returns the flight mode for Motor Detection.
Reimplemented from FirmwarePlugin.
Definition at line 61 of file ArduSubFirmwarePlugin.cc.
References FirmwarePlugin::_modeEnumToString, _motorDetectionFlightMode, and APMSubMode::MOTORDETECTION.
|
inlineoverridevirtual |
Return the resource file which contains the set of params loaded for offline editing.
Reimplemented from FirmwarePlugin.
Definition at line 111 of file ArduSubFirmwarePlugin.h.
|
inlineoverridevirtual |
Returns the mapping structure which is used to map from one parameter name to another based on firmware version.
Reimplemented from FirmwarePlugin.
Definition at line 101 of file ArduSubFirmwarePlugin.h.
|
overridevirtual |
Returns the highest major version number that is known to the remap for this specified major version.
Reimplemented from FirmwarePlugin.
Definition at line 145 of file ArduSubFirmwarePlugin.cc.
References Vehicle::versionNotSetValue.
|
overridevirtual |
Returns the flight mode for Stabilized.
Reimplemented from FirmwarePlugin.
Definition at line 56 of file ArduSubFirmwarePlugin.cc.
References FirmwarePlugin::_modeEnumToString, _stabilizeFlightMode, and APMSubMode::STABILIZE.
|
inlineoverridevirtual |
Returns true if the firmware supports the AP_JSButton library, which allows joystick buttons to be assigned via parameters in firmware. Default is false.
Reimplemented from FirmwarePlugin.
Definition at line 90 of file ArduSubFirmwarePlugin.h.
|
inlineoverridevirtual |
Returns true if the firmware supports calibrating motor interference offsets for the compass (CompassMot). Default is true.
Reimplemented from FirmwarePlugin.
Definition at line 91 of file ArduSubFirmwarePlugin.h.
|
inlineoverridevirtual |
Returns true if the firmware supports the use of the RC radio and requires the RC radio setup page. Returns true by default.
Reimplemented from FirmwarePlugin.
Definition at line 89 of file ArduSubFirmwarePlugin.h.
|
inlineoverridevirtual |
Returns true if the vehicle and firmware supports the use of a throttle joystick that is zero when centered. Typically not supported on vehicles that have bidirectional throttle.
Reimplemented from FirmwarePlugin.
Definition at line 88 of file ArduSubFirmwarePlugin.h.
|
overridevirtual |
Update Available flight modes recieved from vehicle.
Reimplemented from FirmwarePlugin.
Definition at line 66 of file ArduSubFirmwarePlugin.cc.
References FirmwarePlugin::_updateFlightModeList().
Referenced by ArduSubFirmwarePlugin().
|
inlineoverridevirtual |
Return the resource file which contains the vehicle icon used in the flight view when the view is dark (Satellite for instance)
Reimplemented from FirmwarePlugin.
Definition at line 94 of file ArduSubFirmwarePlugin.h.
Referenced by vehicleImageOutline().
|
overridevirtual |
Return the resource file which contains the vehicle icon used in the flight view when the view is light (Map for instance)
Reimplemented from FirmwarePlugin.
Definition at line 38 of file ArduSubFirmwarePlugin.cc.
References vehicleImageOpaque().
|
protected |
Definition at line 118 of file ArduSubFirmwarePlugin.h.
Referenced by ArduSubFirmwarePlugin().
|
protected |
Definition at line 119 of file ArduSubFirmwarePlugin.h.
Referenced by ArduSubFirmwarePlugin().
|
protected |
Definition at line 120 of file ArduSubFirmwarePlugin.h.
Referenced by ArduSubFirmwarePlugin().
|
protected |
Definition at line 122 of file ArduSubFirmwarePlugin.h.
Referenced by ArduSubFirmwarePlugin().
|
protected |
Definition at line 121 of file ArduSubFirmwarePlugin.h.
Referenced by ArduSubFirmwarePlugin().
|
protected |
Definition at line 116 of file ArduSubFirmwarePlugin.h.
Referenced by ArduSubFirmwarePlugin().
|
protected |
Definition at line 125 of file ArduSubFirmwarePlugin.h.
Referenced by ArduSubFirmwarePlugin(), and motorDetectionFlightMode().
|
protected |
Definition at line 124 of file ArduSubFirmwarePlugin.h.
Referenced by ArduSubFirmwarePlugin().
|
protected |
Definition at line 117 of file ArduSubFirmwarePlugin.h.
Referenced by ArduSubFirmwarePlugin(), and stabilizedFlightMode().
|
protected |
Definition at line 123 of file ArduSubFirmwarePlugin.h.
Referenced by ArduSubFirmwarePlugin().
|
protected |
Definition at line 126 of file ArduSubFirmwarePlugin.h.
Referenced by ArduSubFirmwarePlugin().