|
QGroundControl
Ground Control Station for MAVLink Drones
|
#include <ArduRoverFirmwarePlugin.h>
Inheritance diagram for ArduRoverFirmwarePlugin:
Collaboration diagram for ArduRoverFirmwarePlugin:Public Member Functions | |
| ArduRoverFirmwarePlugin (QObject *parent=nullptr) | |
| ~ArduRoverFirmwarePlugin () | |
| void | guidedModeChangeAltitude (Vehicle *vehicle, double altitudeChange, bool pauseVehicle) override |
| int | remapParamNameHigestMinorVersionNumber (int majorVersionNumber) const override |
| const FirmwarePlugin::remapParamNameMajorVersionMap_t & | paramNameRemapMajorVersionMap () const override |
| bool | supportsNegativeThrust (Vehicle *) const override |
| bool | supportsSmartRTL () const override |
| QString | offlineEditingParamFile (Vehicle *vehicle) const override |
| Return the resource file which contains the set of params loaded for offline editing. | |
| QString | pauseFlightMode () const override |
| Returns The flight mode which indicates the vehicle is paused. | |
| QString | followFlightMode () const override |
| Returns the flight mode which the vehicle will be for follow me. | |
| QString | stabilizedFlightMode () const override |
| Returns the flight mode for Stabilized. | |
| void | updateAvailableFlightModes (FlightModeList &modeList) override |
| Update Available flight modes recieved from vehicle. | |
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 |
| bool | isCapable (const Vehicle *vehicle, FirmwareCapabilities capabilities) 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. | |
| bool | guidedModeGotoLocation (Vehicle *vehicle, const QGeoCoordinate &gotoCoord, double forwardFlightLoiterRadius) const override |
| 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 | guidedModeChangeHeading (Vehicle *vehicle, const QGeoCoordinate &headingCoord) const override |
| Command vehicle to rotate towards specified location. | |
| bool | adjustIncomingMavlinkMessage (Vehicle *vehicle, mavlink_message_t *message) override |
| void | adjustOutgoingMavlinkMessageThreadSafe (Vehicle *vehicle, LinkInterface *outgoingLink, mavlink_message_t *message) override |
| virtual void | initializeStreamRates (Vehicle *vehicle) |
| 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 |
| MAV_AUTOPILOT | _autopilotType () const override |
| ParameterMetaData * | _createParameterMetaData () 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 | maximumHorizontalSpeedMultirotorMetersSecond (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 | 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 | takeControlFlightMode () const |
| Returns the flight mode to use when the operator wants to take back control from autonomouse flight. | |
| virtual void | guidedModeLand (Vehicle *vehicle) const |
| Command vehicle to land at current location. | |
| virtual int | defaultJoystickTXMode () const |
| virtual bool | supportsThrottleModeCenterZero () const |
| virtual bool | supportsRadio () const |
| virtual bool | supportsJSButton () const |
| virtual bool | supportsMotorInterference () const |
| virtual bool | multiRotorCoaxialMotors (Vehicle *) const |
| virtual bool | multiRotorXConfig (Vehicle *) 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 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 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 Autotune * | createAutotune (Vehicle *vehicle) const |
| Creates Autotune object. | |
| ParameterMetaData * | loadParameterMetaData (const Vehicle *vehicle) |
| void | cacheParameterMetaDataFile (const QString &metaDataFile) |
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 |
| QString | _cachedParameterMetaDataFile (const Vehicle *vehicle) 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 | _acroFlightMode = tr("Acro") |
| const QString | _learningFlightMode = tr("Learning") |
| const QString | _steeringFlightMode = tr("Steering") |
| const QString | _holdFlightMode = tr("Hold") |
| const QString | _loiterFlightMode = tr("Loiter") |
| const QString | _followFlightMode = tr("Follow") |
| const QString | _simpleFlightMode = tr("Simple") |
| const QString | _dockFlightMode = tr("Dock") |
| const QString | _circleFlightMode = tr("Circle") |
| const QString | _autoFlightMode = tr("Auto") |
| const QString | _rtlFlightMode = tr("RTL") |
| const QString | _smartRtlFlightMode = tr("Smart RTL") |
| const QString | _guidedFlightMode = tr("Guided") |
| const QString | _initializingFlightMode = tr("Initializing") |
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 26 of file ArduRoverFirmwarePlugin.h.
|
explicit |
Definition at line 8 of file ArduRoverFirmwarePlugin.cc.
References _acroFlightMode, _autoFlightMode, _circleFlightMode, _dockFlightMode, _followFlightMode, _guidedFlightMode, _holdFlightMode, _initializingFlightMode, _learningFlightMode, _loiterFlightMode, _manualFlightMode, _rtlFlightMode, FirmwarePlugin::_setModeEnumToModeStringMapping(), _simpleFlightMode, _smartRtlFlightMode, _steeringFlightMode, APMRoverMode::ACRO, APMRoverMode::AUTO, APMRoverMode::CIRCLE, APMRoverMode::DOCK, APMRoverMode::FOLLOW, APMRoverMode::GUIDED, APMRoverMode::HOLD, APMRoverMode::INITIALIZING, APMRoverMode::LEARNING, APMRoverMode::LOITER, APMRoverMode::MANUAL, APMRoverMode::RTL, APMRoverMode::SIMPLE, APMRoverMode::SMART_RTL, APMRoverMode::STEERING, and updateAvailableFlightModes().
| ArduRoverFirmwarePlugin::~ArduRoverFirmwarePlugin | ( | ) |
Definition at line 63 of file ArduRoverFirmwarePlugin.cc.
|
overrideprotectedvirtual |
Reimplemented from FirmwarePlugin.
Definition at line 103 of file ArduRoverFirmwarePlugin.cc.
References APMCustomMode::AUTO, APMRoverMode::AUTO, APMCustomMode::GUIDED, APMRoverMode::GUIDED, APMCustomMode::RTL, APMRoverMode::RTL, APMCustomMode::SMART_RTL, and APMRoverMode::SMART_RTL.
|
overridevirtual |
Returns the flight mode which the vehicle will be for follow me.
Reimplemented from FirmwarePlugin.
Definition at line 88 of file ArduRoverFirmwarePlugin.cc.
References _followFlightMode, FirmwarePlugin::_modeEnumToString, and APMRoverMode::FOLLOW.
|
overridevirtual |
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 from APMFirmwarePlugin.
Definition at line 73 of file ArduRoverFirmwarePlugin.cc.
References QGC::showAppMessage().
|
inlineoverridevirtual |
Return the resource file which contains the set of params loaded for offline editing.
Reimplemented from FirmwarePlugin.
Definition at line 39 of file ArduRoverFirmwarePlugin.h.
|
inlineoverridevirtual |
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 from FirmwarePlugin.
Definition at line 36 of file ArduRoverFirmwarePlugin.h.
|
overridevirtual |
Returns The flight mode which indicates the vehicle is paused.
Reimplemented from FirmwarePlugin.
Definition at line 83 of file ArduRoverFirmwarePlugin.cc.
References _holdFlightMode, FirmwarePlugin::_modeEnumToString, and APMRoverMode::HOLD.
|
overridevirtual |
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 from FirmwarePlugin.
Definition at line 68 of file ArduRoverFirmwarePlugin.cc.
References VehicleTypes::versionNotSetValue.
|
overridevirtual |
Returns the flight mode for Stabilized.
Reimplemented from FirmwarePlugin.
Definition at line 78 of file ArduRoverFirmwarePlugin.cc.
References _manualFlightMode, FirmwarePlugin::_modeEnumToString, and APMRoverMode::MANUAL.
|
inlineoverridevirtual |
Returns true if the vehicle and firmware supports the use of negative thrust Typically supported rover.
Reimplemented from FirmwarePlugin.
Definition at line 37 of file ArduRoverFirmwarePlugin.h.
|
inlineoverridevirtual |
Reimplemented from FirmwarePlugin.
Definition at line 38 of file ArduRoverFirmwarePlugin.h.
|
overridevirtual |
Update Available flight modes recieved from vehicle.
Reimplemented from FirmwarePlugin.
Definition at line 93 of file ArduRoverFirmwarePlugin.cc.
References FirmwarePlugin::_updateFlightModeList().
Referenced by ArduRoverFirmwarePlugin().
|
protected |
Definition at line 50 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin().
|
protected |
Definition at line 59 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin().
|
protected |
Definition at line 58 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin().
|
protected |
Definition at line 57 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin().
|
protected |
Definition at line 55 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin(), and followFlightMode().
|
protected |
Definition at line 62 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin().
|
protected |
Definition at line 53 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin(), and pauseFlightMode().
|
protected |
Definition at line 63 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin().
|
protected |
Definition at line 51 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin().
|
protected |
Definition at line 54 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin().
|
protected |
Definition at line 49 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin(), and stabilizedFlightMode().
|
protected |
Definition at line 60 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin().
|
protected |
Definition at line 56 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin().
|
protected |
Definition at line 61 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin().
|
protected |
Definition at line 52 of file ArduRoverFirmwarePlugin.h.
Referenced by ArduRoverFirmwarePlugin().