|
QGroundControl
Ground Control Station for MAVLink Drones
|
The FirmwarePlugin class represents the methods and objects which are specific to a certain Firmware flight stack. More...
#include <FirmwarePlugin.h>
Inheritance diagram for FirmwarePlugin:
Collaboration diagram for FirmwarePlugin:Public Types | |
| 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 | |
| void | toolIndicatorsChanged () |
Public Member Functions | |
| FirmwarePlugin (QObject *parent=nullptr) | |
| virtual | ~FirmwarePlugin () |
| virtual AutoPilotPlugin * | autopilotPlugin (Vehicle *vehicle) const |
| virtual void | initializeVehicle (Vehicle *) |
| Called when Vehicle is first created to perform any firmware specific setup. | |
| virtual bool | isCapable (const Vehicle *, FirmwareCapabilities) const |
| virtual QStringList | flightModes (Vehicle *) const |
| virtual QString | flightMode (uint8_t base_mode, uint32_t custom_mode) const |
| virtual bool | setFlightMode (const QString &flightMode, uint8_t *base_mode, uint32_t *custom_mode) const |
| virtual bool | MAV_CMD_DO_SET_MODE_is_supported () const |
| returns true if this flight stack supports MAV_CMD_DO_SET_MODE | |
| virtual QString | pauseFlightMode () const |
| Returns The flight mode which indicates the vehicle is paused. | |
| virtual QString | missionFlightMode () const |
| Returns the flight mode for running missions. | |
| virtual QString | rtlFlightMode () const |
| Returns the flight mode for RTL. | |
| virtual QString | smartRTLFlightMode () const |
| Returns the flight mode for Smart RTL. | |
| 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 | motorDetectionFlightMode () const |
| Returns the flight mode for Motor Detection. | |
| virtual QString | stabilizedFlightMode () const |
| Returns the flight mode for Stabilized. | |
| virtual QString | takeControlFlightMode () const |
| Returns the flight mode to use when the operator wants to take back control from autonomouse flight. | |
| virtual bool | isGuidedMode (const Vehicle *) const |
| Returns whether the vehicle is in guided mode or not. | |
| virtual QString | gotoFlightMode () const |
| Returns the flight mode which the vehicle will be in if it is performing a goto location. | |
| virtual QString | followFlightMode () const |
| Returns the flight mode which the vehicle will be for follow me. | |
| virtual void | setGuidedMode (Vehicle *vehicle, bool guidedMode) const |
| Set guided flight mode. | |
| virtual void | pauseVehicle (Vehicle *vehicle) const |
| virtual void | guidedModeRTL (Vehicle *vehicle, bool smartRTL) const |
| Command vehicle to return to launch. | |
| virtual void | guidedModeLand (Vehicle *vehicle) const |
| Command vehicle to land at current location. | |
| virtual void | guidedModeTakeoff (Vehicle *vehicle, double takeoffAltRel) const |
| Command vehicle to takeoff from current location to the specified height. | |
| virtual void | guidedModeChangeHeading (Vehicle *vehicle, const QGeoCoordinate &headingCoord) const |
| Command vehicle to rotate towards specified location. | |
| virtual double | minimumTakeoffAltitudeMeters (Vehicle *) const |
| virtual double | maximumHorizontalSpeedMultirotorMetersSecond (Vehicle *) const |
| virtual double | maximumEquivalentAirspeed (Vehicle *) const |
| virtual double | minimumEquivalentAirspeed (Vehicle *) const |
| virtual bool | hasGripper (const Vehicle *) const |
| virtual bool | mulirotorSpeedLimitsAvailable (Vehicle *) const |
| virtual bool | fixedWingAirSpeedLimitsAvailable (Vehicle *) const |
| virtual void | startTakeoff (Vehicle *vehicle) const |
| Command the vehicle to start a takeoff. | |
| virtual void | startMission (Vehicle *vehicle) const |
| Command the vehicle to start the mission. | |
| virtual bool | guidedModeGotoLocation (Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius=0.0) const |
| virtual void | guidedModeChangeAltitude (Vehicle *vehicle, double altitudeChange, bool pauseVehicle) |
| virtual void | guidedModeChangeGroundSpeedMetersSecond (Vehicle *vehicle, double groundspeed) const |
| virtual void | guidedModeChangeEquivalentAirspeedMetersSecond (Vehicle *vehicle, double airspeed_equiv) const |
| virtual int | defaultJoystickTXMode () const |
| virtual bool | supportsThrottleModeCenterZero () const |
| virtual bool | supportsNegativeThrust (Vehicle *) const |
| virtual bool | supportsRadio () const |
| virtual bool | supportsJSButton () const |
| virtual bool | supportsMotorInterference () const |
| virtual bool | adjustIncomingMavlinkMessage (Vehicle *, mavlink_message_t *) |
| virtual void | adjustOutgoingMavlinkMessageThreadSafe (Vehicle *, LinkInterface *, mavlink_message_t *) |
| virtual bool | sendHomePositionToVehicle () const |
| virtual QList< MAV_CMD > | supportedMissionCommands (QGCMAVLinkTypes::VehicleClass_t) const |
| List of supported mission commands. Empty list for all commands supported. | |
| virtual QString | missionCommandOverrides (QGCMAVLinkTypes::VehicleClass_t vehicleClass) const |
| virtual const remapParamNameMajorVersionMap_t & | paramNameRemapMajorVersionMap () const |
| virtual int | remapParamNameHigestMinorVersionNumber (int) const |
| virtual bool | multiRotorCoaxialMotors (Vehicle *) const |
| virtual bool | multiRotorXConfig (Vehicle *) const |
| virtual QString | offlineEditingParamFile (Vehicle *) const |
| Return the resource file which contains the set of params loaded for offline editing. | |
| virtual QString | vehicleImageOpaque (const Vehicle *) const |
| Return the resource file which contains the vehicle icon used in the flight view when the view is dark (Satellite for instance) | |
| virtual QString | vehicleImageOutline (const Vehicle *) const |
| Return the resource file which contains the vehicle icon used in the flight view when the view is light (Map for instance) | |
| virtual QVariant | expandedToolbarIndicatorSource (const Vehicle *, const QString &) const |
| virtual const QVariantList & | toolIndicators (const Vehicle *vehicle) |
| virtual QGCCameraManager * | createCameraManager (Vehicle *vehicle) const |
| Creates vehicle camera manager. | |
| virtual MavlinkCameraControlInterface * | createCameraControl (const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject *parent=nullptr) const |
| Camera control. | |
| virtual QMap< QString, FactGroup * > * | factGroups () |
| Returns a pointer to a dictionary of firmware-specific FactGroups. | |
| 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 void | adjustMetaData (MAV_TYPE, FactMetaData *) |
| virtual void | sendGCSMotionReport (Vehicle *vehicle, const FollowMe::GCSMotionReport &motionReport, uint8_t estimationCapabilities) const |
| Sends the appropriate mavlink message for follow me support. | |
| virtual QString | getHobbsMeter (Vehicle *vehicle) const |
| gets hobbs meter from autopilot. This should be reimplmeented for each firmware | |
| virtual Autotune * | createAutotune (Vehicle *vehicle) const |
| Creates Autotune object. | |
| virtual void | updateAvailableFlightModes (FlightModeList &flightModeList) |
| Update Available flight modes recieved from vehicle. | |
| ParameterMetaData * | loadParameterMetaData (const Vehicle *vehicle) |
| void | cacheParameterMetaDataFile (const QString &metaDataFile) |
Protected Member Functions | |
| bool | _armVehicleAndValidate (Vehicle *vehicle) const |
| bool | _setFlightModeAndValidate (Vehicle *vehicle, const QString &flightMode) const |
| virtual QString | _internalParameterMetaDataFile (const Vehicle *) const |
| virtual MAV_AUTOPILOT | _autopilotType () const |
| virtual ParameterMetaData * | _createParameterMetaData () |
| QString | _cachedParameterMetaDataFile (const Vehicle *vehicle) const |
| virtual QString | _getLatestVersionFileUrl (Vehicle *) const |
| returns url with latest firmware release information. | |
| virtual void | _versionFileDownloadFinished (const QString &remoteFile, const QString &localFile, const Vehicle *vehicle) const |
| Callback to process file with latest release information. | |
| virtual QString | _versionRegex () const |
| Returns regex QString to extract version information from text. | |
| void | _setModeEnumToModeStringMapping (FlightModeCustomModeMap enumToString) |
| virtual uint32_t | _convertToCustomFlightModeEnum (uint32_t val) const |
| void | _updateFlightModeList (FlightModeList &flightModeList) |
| void | _addNewFlightMode (FirmwareFlightMode &flightMode) |
Protected Attributes | |
| FlightModeList | _flightModeList |
| FlightModeCustomModeMap | _modeEnumToString |
| QVariantList | _toolIndicatorList |
| QVariantList | _modeIndicatorList |
The FirmwarePlugin class represents the methods and objects which are specific to a certain Firmware flight stack.
This is the only place where flight stack specific code should reside in QGroundControl. The remainder of the QGroundControl source is generic to a common mavlink implementation. The implementation in the base class supports mavlink generic firmware. Override the base clase virtuals to create your own firmware specific plugin.
Definition at line 72 of file FirmwarePlugin.h.
| typedef QMap<int, remapParamNameMinorVersionRemapMap_t> FirmwarePlugin::remapParamNameMajorVersionMap_t |
Maps from firmware major version number to remapParamNameMinorVersionRemapMap_t entry key: firmware major version value: remapParamNameMinorVersionRemapMap_t entry
Definition at line 118 of file FirmwarePlugin.h.
| typedef QMap<QString, QString> FirmwarePlugin::remapParamNameMap_t |
Parameter name remapping support: When firmware renames a parameter across versions, callers should use the newest (current) parameter name. ParameterManager::_remapParamNameToVersion() walks the remap tables backwards from the highest known minor version down to the vehicle's actual firmware version, translating new names to old names at each step. If the name is not found in any remap table it passes through unchanged, so remapping is always safe to run.
To bypass remapping (e.g. when checking parameterExists for a specific old or new name to decide which unit conversion to apply), prefix the name with "noremap.".
Remap table entries map new_name -> old_name for the version in which the rename occurred. For example: remapV4_0["TUNE_MIN"] = "TUNE_LOW" means TUNE_LOW was renamed to TUNE_MIN in 4.0. Maps from one parameter name to another (new_name -> old_name for a given version) key: current (new) parameter name value: previous (old) parameter name
Definition at line 108 of file FirmwarePlugin.h.
| typedef QMap<int, remapParamNameMap_t> FirmwarePlugin::remapParamNameMinorVersionRemapMap_t |
Maps from firmware minor version to remapParamNameMap_t entry key: firmware minor version in which the rename(s) occurred value: remapParamNameMap_t with new->old mappings for that version
Definition at line 113 of file FirmwarePlugin.h.
Set of optional capabilites which firmware may support.
| Enumerator | |
|---|---|
| SetFlightModeCapability | FirmwarePlugin::setFlightMode method is supported. |
| PauseVehicleCapability | Vehicle supports pausing at current location. |
| GuidedModeCapability | Vehicle supports guided mode commands. |
| OrbitModeCapability | Vehicle supports orbit mode. |
| TakeoffVehicleCapability | Vehicle supports taking off. |
| ROIModeCapability | Vehicle supports ROI (both in Fly guided mode and from Plan creation) |
| ChangeHeadingCapability | Vehicle supports changing heading at current location. |
| GuidedTakeoffCapability | Vehicle supports guided takeoff. |
Definition at line 81 of file FirmwarePlugin.h.
|
explicit |
Definition at line 31 of file FirmwarePlugin.cc.
|
virtual |
Definition at line 37 of file FirmwarePlugin.cc.
|
protected |
Definition at line 452 of file FirmwarePlugin.cc.
References _flightModeList, FirmwareFlightMode::custom_mode, and FirmwareFlightMode::mode_name.
Referenced by _updateFlightModeList().
|
protected |
Arms the vehicle with validation and retries
Definition at line 222 of file FirmwarePlugin.cc.
References Vehicle::armed(), and Vehicle::setArmed().
Referenced by APMFirmwarePlugin::startMission(), PX4FirmwarePlugin::startMission(), APMFirmwarePlugin::startTakeoff(), and PX4FirmwarePlugin::startTakeoff().
|
inlineprotectedvirtual |
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 408 of file FirmwarePlugin.h.
Referenced by _cachedParameterMetaDataFile(), and cacheParameterMetaDataFile().
|
protected |
Definition at line 493 of file FirmwarePlugin.cc.
References _autopilotType(), _internalParameterMetaDataFile(), _parameterMetaDataCacheDir(), kCachedMetaDataFilePrefix, QGC::runningUnitTests(), ParameterMetaData::versionFromFileName(), and ParameterMetaData::versionFromMetaDataFile().
Referenced by loadParameterMetaData().
|
inlineprotectedvirtual |
Reimplemented in ArduCopterFirmwarePlugin, ArduPlaneFirmwarePlugin, ArduRoverFirmwarePlugin, and ArduSubFirmwarePlugin.
Definition at line 425 of file FirmwarePlugin.h.
Referenced by APMFirmwarePlugin::guidedFlightMode(), APMFirmwarePlugin::missionFlightMode(), APMFirmwarePlugin::rtlFlightMode(), and APMFirmwarePlugin::smartRTLFlightMode().
|
inlineprotectedvirtual |
Reimplemented in PX4FirmwarePlugin, and APMFirmwarePlugin.
Definition at line 409 of file FirmwarePlugin.h.
Referenced by loadParameterMetaData().
|
inlineprotectedvirtual |
returns url with latest firmware release information.
Definition at line 413 of file FirmwarePlugin.h.
Referenced by checkIfIsLatestStable().
|
inlineprotectedvirtual |
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 407 of file FirmwarePlugin.h.
Referenced by _cachedParameterMetaDataFile().
|
protected |
Sets the vehicle to the specified flight mode with validation and retries
Definition at line 246 of file FirmwarePlugin.cc.
References Vehicle::flightMode(), flightMode(), and Vehicle::setFlightMode().
Referenced by APMFirmwarePlugin::guidedModeChangeAltitude(), ArduCopterFirmwarePlugin::guidedModeLand(), PX4FirmwarePlugin::guidedModeLand(), APMFirmwarePlugin::guidedModeRTL(), PX4FirmwarePlugin::guidedModeRTL(), APMFirmwarePlugin::pauseVehicle(), APMFirmwarePlugin::setGuidedMode(), PX4FirmwarePlugin::setGuidedMode(), APMFirmwarePlugin::startMission(), PX4FirmwarePlugin::startMission(), APMFirmwarePlugin::startTakeoff(), and PX4FirmwarePlugin::startTakeoff().
|
inlineprotected |
Definition at line 422 of file FirmwarePlugin.h.
References _modeEnumToString.
Referenced by ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(), ArduPlaneFirmwarePlugin::ArduPlaneFirmwarePlugin(), ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(), ArduSubFirmwarePlugin::ArduSubFirmwarePlugin(), and PX4FirmwarePlugin::PX4FirmwarePlugin().
|
protected |
Definition at line 437 of file FirmwarePlugin.cc.
References _addNewFlightMode(), _flightModeList, _modeEnumToString, and flightMode().
Referenced by updateAvailableFlightModes(), ArduCopterFirmwarePlugin::updateAvailableFlightModes(), ArduPlaneFirmwarePlugin::updateAvailableFlightModes(), ArduRoverFirmwarePlugin::updateAvailableFlightModes(), ArduSubFirmwarePlugin::updateAvailableFlightModes(), and PX4FirmwarePlugin::updateAvailableFlightModes().
|
protectedvirtual |
Callback to process file with latest release information.
Definition at line 329 of file FirmwarePlugin.cc.
References _versionRegex(), Vehicle::firmwareMajorVersion(), Vehicle::firmwareMinorVersion(), Vehicle::firmwarePatchVersion(), Vehicle::firmwareVersionType(), QGC::showAppMessage(), and Vehicle::versionCompare().
Referenced by checkIfIsLatestStable().
|
inlineprotectedvirtual |
Returns regex QString to extract version information from text.
Definition at line 419 of file FirmwarePlugin.h.
Referenced by _versionFileDownloadFinished().
|
inlinevirtual |
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 in APMFirmwarePlugin, ArduSubFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 278 of file FirmwarePlugin.h.
|
inlinevirtual |
Allows the Firmware plugin to override the facts meta data.
| vehicleType | - Type of current vehicle |
| metaData | - MetaData for fact |
Reimplemented in ArduSubFirmwarePlugin.
Definition at line 378 of file FirmwarePlugin.h.
Referenced by Vehicle::Vehicle().
|
inlinevirtual |
Called before any mavlink message is sent to the Vehicle so 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.
This method must be thread safe.
@param vehicle Vehicle message came from @param outgoingLink Link that messae is going out on @param message[in,out] Mavlink message to adjust if needed.
Reimplemented in APMFirmwarePlugin.
Definition at line 289 of file FirmwarePlugin.h.
Referenced by Vehicle::sendMessageOnLinkThreadSafe().
|
inlinevirtual |
Reimplemented in ArduCopterFirmwarePlugin, ArduPlaneFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 355 of file FirmwarePlugin.h.
Referenced by Vehicle::autoDisarm().
|
virtual |
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 42 of file FirmwarePlugin.cc.
Referenced by Vehicle::Vehicle().
|
virtual |
Returns the data needed to do battery consumption calculations
| [out] | mAhBattery | Battery milliamp-hours rating (0 for no battery data available) |
| [out] | hoverAmps | Current draw in amps during hover |
| [out] | cruiseAmps | Current draw in amps during cruise |
Definition at line 277 of file FirmwarePlugin.cc.
Referenced by MissionFlightStatusCalculator::reset().
| void FirmwarePlugin::cacheParameterMetaDataFile | ( | const QString & | metaDataFile | ) |
Definition at line 546 of file FirmwarePlugin.cc.
References _autopilotType(), _parameterMetaDataCacheDir(), QGCFileHelper::atomicWrite(), kCachedMetaDataFilePrefix, QGCCompression::readFile(), ParameterMetaData::versionFromFileName(), and ParameterMetaData::versionFromJsonData().
|
virtual |
Used to check if running firmware is latest stable version.
Definition at line 304 of file FirmwarePlugin.cc.
References _getLatestVersionFileUrl(), _versionFileDownloadFinished(), QGCFileDownload::finished(), QGC::runningUnitTests(), and QGCFileDownload::start().
Creates Autotune object.
Definition at line 432 of file FirmwarePlugin.cc.
|
virtual |
Camera control.
Definition at line 299 of file FirmwarePlugin.cc.
|
virtual |
Creates vehicle camera manager.
Definition at line 294 of file FirmwarePlugin.cc.
|
inlinevirtual |
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 in ArduSubFirmwarePlugin.
Definition at line 249 of file FirmwarePlugin.h.
|
inlinevirtual |
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 332 of file FirmwarePlugin.h.
Referenced by Vehicle::expandedToolbarIndicatorSource().
|
inlinevirtual |
Returns a pointer to a dictionary of firmware-specific FactGroups.
Reimplemented in ArduSubFirmwarePlugin.
Definition at line 346 of file FirmwarePlugin.h.
|
inlinevirtual |
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 222 of file FirmwarePlugin.h.
|
virtual |
Returns the name for this flight mode. Flight mode names must be human readable as well as audio speakable.
| base_mode | Base mode from mavlink HEARTBEAT message |
| custom_mode | Custom mode from mavlink HEARTBEAT message |
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 47 of file FirmwarePlugin.cc.
References _modeEnumToString, and flightMode().
Referenced by _setFlightModeAndValidate(), _updateFlightModeList(), Vehicle::flightMode(), flightMode(), and setFlightMode().
|
inlinevirtual |
Returns the list of available flight modes for the Fly View dropdown. This may or may not be the full list available from the firmware. Call will be made again if advanced mode changes.
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 131 of file FirmwarePlugin.h.
Referenced by Vehicle::flightModes().
|
inlinevirtual |
Returns the flight mode which the vehicle will be for follow me.
Reimplemented in ArduCopterFirmwarePlugin, ArduRoverFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 182 of file FirmwarePlugin.h.
Referenced by Vehicle::followFlightMode().
|
inlinevirtual |
gets hobbs meter from autopilot. This should be reimplmeented for each firmware
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 384 of file FirmwarePlugin.h.
Referenced by Vehicle::hobbsMeter().
|
inlinevirtual |
Returns the flight mode which the vehicle will be in if it is performing a goto location.
Reimplemented in APMFirmwarePlugin, ArduCopterFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 179 of file FirmwarePlugin.h.
Referenced by Vehicle::gotoFlightMode().
|
virtual |
Command vehicle to change altitude
| altitudeChange | If > 0, go up by amount specified, if < 0, go down by amount specified |
| pauseVehicle | true: pause vehicle prior to altitude change |
Reimplemented in APMFirmwarePlugin, ArduRoverFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 157 of file FirmwarePlugin.cc.
References guided_mode_not_supported_by_vehicle, pauseVehicle(), and QGC::showAppMessage().
Referenced by Vehicle::guidedModeChangeAltitude().
|
virtual |
Command vehicle to change equivalent airspeed
| airspeed_equiv | Equivalent airspeed in m/s |
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 168 of file FirmwarePlugin.cc.
References guided_mode_not_supported_by_vehicle, and QGC::showAppMessage().
Referenced by Vehicle::guidedModeChangeEquivalentAirspeedMetersSecond().
|
virtual |
Command vehicle to change groundspeed
| groundspeed | Groundspeed in m/s |
Reimplemented in PX4FirmwarePlugin, and APMFirmwarePlugin.
Definition at line 163 of file FirmwarePlugin.cc.
References guided_mode_not_supported_by_vehicle, and QGC::showAppMessage().
Referenced by Vehicle::guidedModeChangeGroundSpeedMetersSecond().
|
virtual |
Command vehicle to rotate towards specified location.
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 173 of file FirmwarePlugin.cc.
References guided_mode_not_supported_by_vehicle, and QGC::showAppMessage().
Referenced by Vehicle::guidedModeChangeHeading().
|
virtual |
Command vehicle to move to specified location (altitude is ignored, vehicle uses current altitude)
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 148 of file FirmwarePlugin.cc.
References guided_mode_not_supported_by_vehicle, and QGC::showAppMessage().
Referenced by Vehicle::guidedModeGotoLocation().
|
virtual |
Command vehicle to land at current location.
Reimplemented in ArduCopterFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 135 of file FirmwarePlugin.cc.
References guided_mode_not_supported_by_vehicle, and QGC::showAppMessage().
Referenced by Vehicle::guidedModeLand().
|
virtual |
Command vehicle to return to launch.
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 128 of file FirmwarePlugin.cc.
References guided_mode_not_supported_by_vehicle, and QGC::showAppMessage().
Referenced by Vehicle::guidedModeRTL().
|
virtual |
Command vehicle to takeoff from current location to the specified height.
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 141 of file FirmwarePlugin.cc.
References guided_mode_not_supported_by_vehicle, and QGC::showAppMessage().
Referenced by Vehicle::guidedModeTakeoff().
|
virtual |
Used to determine whether a vehicle has a gimbal.
| [out] | rollSupported | Gimbal supports roll |
| [out] | pitchSupported | Gimbal supports pitch |
| [out] | yawSupported | Gimbal supports yaw |
Definition at line 285 of file FirmwarePlugin.cc.
Referenced by MissionController::removeVisualItem().
|
inlinevirtual |
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 216 of file FirmwarePlugin.h.
Referenced by Vehicle::hasGripper().
|
inlinevirtual |
Convert from HIGH_LATENCY2.custom_mode value to correct 32 bit value.
Reimplemented in PX4FirmwarePlugin.
Definition at line 365 of file FirmwarePlugin.h.
|
inlinevirtual |
Called when Vehicle is first created to perform any firmware specific setup.
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 124 of file FirmwarePlugin.h.
Referenced by Vehicle::Vehicle(), and Vehicle::Vehicle().
|
inlinevirtual |
Reimplemented in APMFirmwarePlugin, ArduSubFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 127 of file FirmwarePlugin.h.
Referenced by VehicleSupports::changeHeading(), Vehicle::flightModeSetAvailable(), VehicleSupports::guidedMode(), VehicleSupports::guidedTakeoffWithAltitude(), VehicleSupports::guidedTakeoffWithoutAltitude(), VehicleSupports::orbitMode(), VehicleSupports::pauseVehicle(), VehicleSupports::roiMode(), and VehicleSupports::takeoffMissionCommand().
|
inlinevirtual |
Returns whether the vehicle is in guided mode or not.
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 176 of file FirmwarePlugin.h.
Referenced by Vehicle::guidedMode().
|
inlinevirtual |
Returns the flight mode for Land.
Reimplemented in ArduCopterFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 161 of file FirmwarePlugin.h.
Referenced by Vehicle::landFlightMode().
| ParameterMetaData * FirmwarePlugin::loadParameterMetaData | ( | const Vehicle * | vehicle | ) |
Definition at line 478 of file FirmwarePlugin.cc.
References _cachedParameterMetaDataFile(), _createParameterMetaData(), and ParameterMetaData::loadParameterFactMetaDataFile().
|
inlinevirtual |
returns true if this flight stack supports MAV_CMD_DO_SET_MODE
Reimplemented in APMFirmwarePlugin.
Definition at line 144 of file FirmwarePlugin.h.
Referenced by Vehicle::setFlightMode().
|
inlinevirtual |
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 210 of file FirmwarePlugin.h.
Referenced by Vehicle::maximumEquivalentAirspeed(), APMFirmwarePlugin::maximumEquivalentAirspeed(), and PX4FirmwarePlugin::maximumEquivalentAirspeed().
|
inlinevirtual |
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 207 of file FirmwarePlugin.h.
Referenced by Vehicle::maximumHorizontalSpeedMultirotorMetersSecond(), APMFirmwarePlugin::maximumHorizontalSpeedMultirotorMetersSecond(), and PX4FirmwarePlugin::maximumHorizontalSpeedMultirotorMetersSecond().
|
inlinevirtual |
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 213 of file FirmwarePlugin.h.
Referenced by Vehicle::minimumEquivalentAirspeed(), APMFirmwarePlugin::minimumEquivalentAirspeed(), and PX4FirmwarePlugin::minimumEquivalentAirspeed().
|
inlinevirtual |
Reimplemented in APMFirmwarePlugin.
Definition at line 204 of file FirmwarePlugin.h.
Referenced by Vehicle::minimumTakeoffAltitudeMeters(), and APMFirmwarePlugin::minimumTakeoffAltitudeMeters().
|
virtual |
Returns the name of the mission command json override file for the specified vehicle type.
| vehicleClass | Vehicle class to return file for, VehicleClassGeneric is a request for overrides for all vehicle types |
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 94 of file FirmwarePlugin.cc.
References QGCMAVLink::VehicleClassFixedWing, QGCMAVLinkTypes::VehicleClassGeneric, QGCMAVLink::VehicleClassMultiRotor, QGCMAVLink::VehicleClassRoverBoat, QGCMAVLink::VehicleClassSub, and QGCMAVLink::VehicleClassVTOL.
Referenced by MissionCommandTree::MissionCommandTree().
|
inlinevirtual |
Returns the flight mode for running missions.
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 150 of file FirmwarePlugin.h.
Referenced by Vehicle::missionFlightMode().
|
inlinevirtual |
Returns the flight mode for Motor Detection.
Reimplemented in ArduSubFirmwarePlugin.
Definition at line 167 of file FirmwarePlugin.h.
Referenced by Vehicle::motorDetectionFlightMode().
|
inlinevirtual |
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 219 of file FirmwarePlugin.h.
|
inlinevirtual |
Reimplemented in ArduCopterFirmwarePlugin.
Definition at line 318 of file FirmwarePlugin.h.
Referenced by Vehicle::coaxialMotors().
|
inlinevirtual |
Reimplemented in ArduCopterFirmwarePlugin.
Definition at line 321 of file FirmwarePlugin.h.
Referenced by Vehicle::xConfigMotors().
|
inlinevirtual |
Return the resource file which contains the set of params loaded for offline editing.
Reimplemented in ArduCopterFirmwarePlugin, ArduPlaneFirmwarePlugin, ArduRoverFirmwarePlugin, ArduSubFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 324 of file FirmwarePlugin.h.
Referenced by APMFirmwarePlugin::initializeVehicle().
|
virtual |
Returns the mapping structure which is used to map from one parameter name to another based on firmware version. See remapParamNameMap_t for details on how remapping works.
Reimplemented in ArduCopterFirmwarePlugin, ArduPlaneFirmwarePlugin, ArduRoverFirmwarePlugin, and ArduSubFirmwarePlugin.
Definition at line 190 of file FirmwarePlugin.cc.
|
inlinevirtual |
Returns The flight mode which indicates the vehicle is paused.
Reimplemented in ArduCopterFirmwarePlugin, ArduPlaneFirmwarePlugin, ArduRoverFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 147 of file FirmwarePlugin.h.
Referenced by APMFirmwarePlugin::guidedModeChangeAltitude(), Vehicle::pauseFlightMode(), and APMFirmwarePlugin::pauseVehicle().
|
virtual |
Causes the vehicle to stop at current position. If guide mode is supported, vehicle will be let in guide mode. If not, vehicle will be left in Loiter.
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 122 of file FirmwarePlugin.cc.
References guided_mode_not_supported_by_vehicle, and QGC::showAppMessage().
Referenced by guidedModeChangeAltitude(), and Vehicle::pauseVehicle().
|
inlinevirtual |
Returns the highest minor version number that has remap entries for the specified major version. The remap logic iterates backwards from this version down to the vehicle's actual minor version. Return VehicleTypes::versionNotSetValue if remapping is not supported for the given major version.
Reimplemented in ArduCopterFirmwarePlugin, ArduPlaneFirmwarePlugin, ArduRoverFirmwarePlugin, and ArduSubFirmwarePlugin.
Definition at line 315 of file FirmwarePlugin.h.
References VehicleTypes::versionNotSetValue.
|
inlinevirtual |
Returns the flight mode for RTL.
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 153 of file FirmwarePlugin.h.
Referenced by Vehicle::rtlFlightMode().
|
virtual |
Sends the appropriate mavlink message for follow me support.
Reimplemented in APMFirmwarePlugin.
Definition at line 401 of file FirmwarePlugin.cc.
References FollowMe::GCSMotionReport::altMetersAMSL, MAVLinkProtocol::getComponentId(), MAVLinkProtocol::instance(), FollowMe::GCSMotionReport::lat_int, FollowMe::GCSMotionReport::lon_int, FollowMe::GCSMotionReport::pos_std_dev, VehicleLinkManager::primaryLink(), qgcApp, Vehicle::sendMessageOnLinkThreadSafe(), Vehicle::vehicleLinkManager(), FollowMe::GCSMotionReport::vxMetersPerSec, and FollowMe::GCSMotionReport::vyMetersPerSec.
|
inlinevirtual |
Determines how to handle the first item of the mission item list. Internally to QGC the first item is always the home position. Generic stack does not want home position sent in the first position. Subsequent sequence numbers must be adjusted. This is the mavlink spec default.
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 299 of file FirmwarePlugin.h.
Referenced by PlanManager::_handleMissionItem(), MissionController::currentMissionIndex(), MissionManager::generateResumeMission(), MissionController::resumeMission(), MissionController::resumeMissionIndex(), Vehicle::setCurrentMissionSequence(), and PlanManager::writeMissionItems().
|
virtual |
Sets base_mode and custom_mode to specified flight mode.
| [out] | base_mode | Base mode for SET_MODE mavlink message |
| [out] | custom_mode | Custom mode for SET_MODE mavlink message |
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 83 of file FirmwarePlugin.cc.
References flightMode().
Referenced by MAVLinkEventManager::setMetadata().
|
virtual |
Set guided flight mode.
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 115 of file FirmwarePlugin.cc.
References guided_mode_not_supported_by_vehicle, and QGC::showAppMessage().
Referenced by Vehicle::setGuidedMode().
|
inlinevirtual |
Returns the flight mode for Smart RTL.
Reimplemented in APMFirmwarePlugin.
Definition at line 156 of file FirmwarePlugin.h.
Referenced by Vehicle::smartRTLFlightMode().
|
inlinevirtual |
Returns the flight mode for Stabilized.
Reimplemented in ArduCopterFirmwarePlugin, ArduPlaneFirmwarePlugin, ArduRoverFirmwarePlugin, ArduSubFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 170 of file FirmwarePlugin.h.
Referenced by Vehicle::stabilizedFlightMode().
|
virtual |
Command the vehicle to start the mission.
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 185 of file FirmwarePlugin.cc.
References guided_mode_not_supported_by_vehicle, and QGC::showAppMessage().
Referenced by Vehicle::startMission().
|
virtual |
Command the vehicle to start a takeoff.
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 179 of file FirmwarePlugin.cc.
References guided_mode_not_supported_by_vehicle, and QGC::showAppMessage().
Referenced by Vehicle::startTakeoff().
|
inlinevirtual |
List of supported mission commands. Empty list for all commands supported.
Reimplemented in APMFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 302 of file FirmwarePlugin.h.
Referenced by CameraSection::cameraModeSupported(), MissionCommandTree::getCommandsForCategory(), MissionController::insertCancelROIMissionItem(), and MissionController::insertROIMissionItem().
|
inlinevirtual |
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 in ArduSubFirmwarePlugin.
Definition at line 266 of file FirmwarePlugin.h.
Referenced by VehicleSupports::jsButton().
|
inlinevirtual |
Returns true if the firmware supports calibrating motor interference offsets for the compass (CompassMot). Default is true.
Reimplemented in ArduSubFirmwarePlugin.
Definition at line 270 of file FirmwarePlugin.h.
Referenced by VehicleSupports::motorInterference().
|
inlinevirtual |
Returns true if the vehicle and firmware supports the use of negative thrust Typically supported rover.
Reimplemented in ArduRoverFirmwarePlugin, ArduSubFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 258 of file FirmwarePlugin.h.
Referenced by VehicleSupports::negativeThrust().
|
inlinevirtual |
Returns true if the firmware supports the use of the RC radio and requires the RC radio setup page. Returns true by default.
Reimplemented in ArduSubFirmwarePlugin.
Definition at line 262 of file FirmwarePlugin.h.
Referenced by VehicleSupports::radio().
|
inlinevirtual |
Reimplemented in ArduCopterFirmwarePlugin, and ArduRoverFirmwarePlugin.
Definition at line 158 of file FirmwarePlugin.h.
Referenced by VehicleSupports::smartRTL().
|
inlinevirtual |
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 in ArduSubFirmwarePlugin.
Definition at line 254 of file FirmwarePlugin.h.
Referenced by VehicleSupports::throttleModeCenterZero().
|
inlinevirtual |
Returns the flight mode to use when the operator wants to take back control from autonomouse flight.
Reimplemented in ArduCopterFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 173 of file FirmwarePlugin.h.
Referenced by Vehicle::takeControlFlightMode().
|
inlinevirtual |
Returns the flight mode for TakeOff.
Reimplemented in ArduCopterFirmwarePlugin, ArduPlaneFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 164 of file FirmwarePlugin.h.
Referenced by MAVLinkEventManager::setMetadata(), and APMFirmwarePlugin::startTakeoff().
|
virtual |
Returns the list of toolbar tool indicators associated with a vehicle signals toolIndicatorsChanged
Reimplemented in APMFirmwarePlugin.
Definition at line 197 of file FirmwarePlugin.cc.
References _toolIndicatorList.
Referenced by Vehicle::toolIndicators(), and APMFirmwarePlugin::toolIndicators().
|
signal |
|
inlinevirtual |
Update Available flight modes recieved from vehicle.
Reimplemented in ArduCopterFirmwarePlugin, ArduPlaneFirmwarePlugin, ArduRoverFirmwarePlugin, ArduSubFirmwarePlugin, and PX4FirmwarePlugin.
Definition at line 390 of file FirmwarePlugin.h.
References _updateFlightModeList().
Referenced by StandardModes::gotMessage().
|
inlinevirtual |
Return the resource file which contains the vehicle icon used in the flight view when the view is dark (Satellite for instance)
Reimplemented in ArduSubFirmwarePlugin.
Definition at line 327 of file FirmwarePlugin.h.
Referenced by Vehicle::vehicleImageOpaque().
|
inlinevirtual |
Return the resource file which contains the vehicle icon used in the flight view when the view is light (Map for instance)
Reimplemented in ArduSubFirmwarePlugin.
Definition at line 330 of file FirmwarePlugin.h.
Referenced by Vehicle::vehicleImageOutline().
| int FirmwarePlugin::versionCompare | ( | const Vehicle * | vehicle, |
| const QString & | compare | ||
| ) | const |
Used to check if running current version is equal or higher than the one being compared. returns 1 if current > compare, 0 if current == compare, -1 if current < compare
Definition at line 386 of file FirmwarePlugin.cc.
References versionCompare().
Referenced by Vehicle::versionCompare(), versionCompare(), and Vehicle::versionCompare().
| int FirmwarePlugin::versionCompare | ( | const Vehicle * | vehicle, |
| int | major, | ||
| int | minor, | ||
| int | patch | ||
| ) | const |
Definition at line 366 of file FirmwarePlugin.cc.
References Vehicle::firmwareMajorVersion(), Vehicle::firmwareMinorVersion(), and Vehicle::firmwarePatchVersion().
|
protected |
Definition at line 431 of file FirmwarePlugin.h.
Referenced by _addNewFlightMode(), _updateFlightModeList(), APMFirmwarePlugin::flightModes(), PX4FirmwarePlugin::flightModes(), APMFirmwarePlugin::setFlightMode(), and PX4FirmwarePlugin::setFlightMode().
|
protected |
Definition at line 432 of file FirmwarePlugin.h.
Referenced by _setModeEnumToModeStringMapping(), _updateFlightModeList(), flightMode(), APMFirmwarePlugin::flightMode(), PX4FirmwarePlugin::flightMode(), ArduCopterFirmwarePlugin::followFlightMode(), ArduRoverFirmwarePlugin::followFlightMode(), PX4FirmwarePlugin::followFlightMode(), PX4FirmwarePlugin::gotoFlightMode(), APMFirmwarePlugin::guidedFlightMode(), ArduCopterFirmwarePlugin::landFlightMode(), PX4FirmwarePlugin::landFlightMode(), APMFirmwarePlugin::missionFlightMode(), PX4FirmwarePlugin::missionFlightMode(), ArduSubFirmwarePlugin::motorDetectionFlightMode(), ArduCopterFirmwarePlugin::pauseFlightMode(), ArduPlaneFirmwarePlugin::pauseFlightMode(), ArduRoverFirmwarePlugin::pauseFlightMode(), PX4FirmwarePlugin::pauseFlightMode(), APMFirmwarePlugin::rtlFlightMode(), PX4FirmwarePlugin::rtlFlightMode(), APMFirmwarePlugin::smartRTLFlightMode(), ArduCopterFirmwarePlugin::stabilizedFlightMode(), ArduPlaneFirmwarePlugin::stabilizedFlightMode(), ArduRoverFirmwarePlugin::stabilizedFlightMode(), ArduSubFirmwarePlugin::stabilizedFlightMode(), PX4FirmwarePlugin::stabilizedFlightMode(), ArduCopterFirmwarePlugin::takeControlFlightMode(), PX4FirmwarePlugin::takeControlFlightMode(), ArduPlaneFirmwarePlugin::takeOffFlightMode(), and PX4FirmwarePlugin::takeOffFlightMode().
|
protected |
Definition at line 435 of file FirmwarePlugin.h.
|
protected |
Definition at line 434 of file FirmwarePlugin.h.
Referenced by toolIndicators().