diff --git a/qgcresources.qrc b/qgcresources.qrc index a1085bbb816fbf7239aa610748b25a97ca330a12..e638acf3f5657dfed59c061092206a25c64b76cc 100644 --- a/qgcresources.qrc +++ b/qgcresources.qrc @@ -109,6 +109,7 @@ src/FlightMap/Images/compassInstrumentDial.svg src/FlightMap/Images/crossHair.svg src/FlightMap/Images/PiP.svg + src/FlightMap/Images/pipResize.svg src/FlightMap/Images/rollDialWhite.svg src/FlightMap/Images/rollPointerWhite.svg src/FlightMap/Images/scale.png diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index b58f74743421c806074101ab5cab5e6ff9a41c0f..54d58cf70a8acaee6f9148e47d71202b54f8bf31 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -527,6 +527,7 @@ HEADERS += \ src/MissionManager/SimpleMissionItem.h \ src/MissionManager/Section.h \ src/MissionManager/SpeedSection.h \ + src/MissionManager/StructureScanComplexItem.h \ src/MissionManager/SurveyMissionItem.h \ src/MissionManager/VisualMissionItem.h \ src/PositionManager/PositionManager.h \ @@ -713,6 +714,7 @@ SOURCES += \ src/MissionManager/RallyPointManager.cc \ src/MissionManager/SimpleMissionItem.cc \ src/MissionManager/SpeedSection.cc \ + src/MissionManager/StructureScanComplexItem.cc \ src/MissionManager/SurveyMissionItem.cc \ src/MissionManager/VisualMissionItem.cc \ src/PositionManager/PositionManager.cpp \ diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc index ce13d5a07c6f47b1338cb42d0acc832678dce46b..e603cdff6a128a6670a46effd6ef23ea91587a62 100644 --- a/qgroundcontrol.qrc +++ b/qgroundcontrol.qrc @@ -115,6 +115,7 @@ src/ui/toolbar/SignalStrength.qml src/PlanView/SimpleItemMapVisual.qml src/QmlControls/SliderSwitch.qml + src/PlanView/StructureScanMapVisual.qml src/QmlControls/SubMenuButton.qml src/PlanView/SurveyMapVisual.qml src/QmlControls/VehicleRotationCal.qml @@ -179,7 +180,7 @@ src/VehicleSetup/SetupParameterEditor.qml src/VehicleSetup/SetupView.qml src/PlanView/SimpleItemEditor.qml - src/PlanView/SurveyItemEditor.qml + src/PlanView/StructureScanEditor.qml src/PlanView/FWLandingPatternEditor.qml src/PlanView/MissionSettingsEditor.qml src/ui/preferences/TcpSettings.qml @@ -206,6 +207,7 @@ src/MissionManager/QGCMapCircle.Facts.json src/Settings/RTK.SettingsGroup.json src/MissionManager/Survey.SettingsGroup.json + src/MissionManager/StructureScan.SettingsGroup.json src/Settings/Units.SettingsGroup.json src/Settings/Video.SettingsGroup.json src/MissionManager/RallyPoint.FactMetaData.json diff --git a/src/AnalyzeView/LogDownloadController.cc b/src/AnalyzeView/LogDownloadController.cc index 611d102bafa0ffcaad2bef4c4d06c003b66fcd50..ed912a4217cf2408790899e0b517b258403020f1 100644 --- a/src/AnalyzeView/LogDownloadController.cc +++ b/src/AnalyzeView/LogDownloadController.cc @@ -173,7 +173,7 @@ LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t //-- Update this log record if(num_logs > 0) { //-- Skip if empty (APM first packet) - if(size) { + if(size || _vehicle->firmwareType() != MAV_AUTOPILOT_ARDUPILOTMEGA) { id -= _apmOneBased; if(id < _logEntriesModel.count()) { QGCLogEntry* entry = _logEntriesModel[id]; diff --git a/src/AnalyzeView/ULogParser.cc b/src/AnalyzeView/ULogParser.cc index 8399c65f73607b897048965616151e69402e6b95..17c08fa85013a2837f9b2d12b7a42e4d20192c91 100644 --- a/src/AnalyzeView/ULogParser.cc +++ b/src/AnalyzeView/ULogParser.cc @@ -36,7 +36,7 @@ int ULogParser::sizeOfType(QString& typeName) return 1; } - qWarning() << "Unkown type in ULog : " << typeName; + qWarning() << "Unknown type in ULog : " << typeName; return 0; } diff --git a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml index e9add7e3486ed97c3e1753e61c96dcd0250d5b16..f5f460bc8ea658be1304bfb3e2b27bc615766cd7 100644 --- a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml +++ b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml @@ -14,7 +14,7 @@ Lower rotor (CW) - + Copter William Peale <develop707@gmail.com> @@ -192,7 +192,7 @@ feed-through of RC AUX3 channel feed-through of RC FLAPS channel - + Copter Lorenz Meier <lorenz@px4.io> Quadrotor Wide @@ -200,12 +200,14 @@ motor 2 motor 3 motor 4 + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel feed-through of RC FLAPS channel - + Copter Lorenz Meier <lorenz@px4.io> Quadrotor Wide @@ -213,8 +215,6 @@ motor 2 motor 3 motor 4 - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel @@ -256,25 +256,30 @@ Lorenz Meier <lorenz@px4.io> Quadrotor x - + Copter - Leon Mueller <thedevleon> + Blankered Quadrotor x - + + Copter + Pavel Kirienko <pavel.kirienko@gmail.com> + Quadrotor x + + + Copter + James Goppert <james.goppert@gmail.com> + Quadrotor x + + + Copter + Lorenz Meier <lorenz@px4.io> + Quadrotor x + + Copter Lorenz Meier <lorenz@px4.io> Quadrotor x - motor 1 - motor 2 - motor 3 - motor 4 - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX1 channel - feed-through of RC AUX2 channel - feed-through of RC AUX3 channel - feed-through of RC FLAPS channel Copter @@ -291,50 +296,50 @@ Mount yaw Mount retract - - Copter - James Goppert <james.goppert@gmail.com> - Quadrotor x - - - Copter - Lorenz Meier <lorenz@px4.io> - Quadrotor x - - + Copter Lorenz Meier <lorenz@px4.io> Quadrotor x - + Copter - Lorenz Meier <lorenz@px4.io> + Leon Mueller <thedevleon> Quadrotor x - + Copter - Pavel Kirienko <pavel.kirienko@gmail.com> + Anton Matosov <anton.matosov@gmail.com> Quadrotor x - + Copter - Blankered + James Goppert <james.goppert@gmail.com> Quadrotor x - + Copter Lorenz Meier <lorenz@px4.io> Quadrotor x - + Copter - James Goppert <james.goppert@gmail.com> + Andreas Antener <andreas@uaventure.com> Quadrotor x - + Copter - Anton Matosov <anton.matosov@gmail.com> + Lorenz Meier <lorenz@px4.io> Quadrotor x + motor 1 + motor 2 + motor 3 + motor 4 + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + feed-through of RC FLAPS channel @@ -367,11 +372,28 @@ - + Plane Simon Wilks <simon@uaventure.com> Flying Wing - https://pixhawk.org/platforms/planes/bormatec_camflyer_q + + + Plane + Lorenz Meier <lorenz@px4.io> + Flying Wing + https://docs.px4.io/en/framebuild_plane/wing_wing_z84.html + left aileron + right aileron + throttle + feed-through of RC AUX1 channel + feed-through of RC AUX2 channel + feed-through of RC AUX3 channel + + + Plane + Jan Liphardt <JTLiphardt@gmail.com> + Flying Wing + left aileron right aileron throttle @@ -391,11 +413,11 @@ feed-through of RC AUX2 channel feed-through of RC AUX3 channel - + Plane - Julian Oes <julian@px4.io> + Simon Wilks <simon@uaventure.com> Flying Wing - https://pixhawk.org/platforms/planes/skywalker_x5 + http://www.sparkletech.hk/ left aileron right aileron throttle @@ -403,11 +425,11 @@ feed-through of RC AUX2 channel feed-through of RC AUX3 channel - + Plane - Lorenz Meier <lorenz@px4.io> + Julian Oes <julian@px4.io> Flying Wing - https://docs.px4.io/en/framebuild_plane/wing_wing_z84.html + https://pixhawk.org/platforms/planes/skywalker_x5 left aileron right aileron throttle @@ -415,9 +437,9 @@ feed-through of RC AUX2 channel feed-through of RC AUX3 channel - + Plane - Simon Wilks <simon@uaventure.com> + Lorenz Meier <lorenz@px4.io> Flying Wing @@ -425,11 +447,11 @@ Simon Wilks <simon@uaventure.com> Flying Wing - + Plane Simon Wilks <simon@uaventure.com> Flying Wing - http://www.sparkletech.hk/ + https://pixhawk.org/platforms/planes/bormatec_camflyer_q left aileron right aileron throttle @@ -437,11 +459,6 @@ feed-through of RC AUX2 channel feed-through of RC AUX3 channel - - Plane - Lorenz Meier <lorenz@px4.io> - Flying Wing - @@ -475,37 +492,45 @@ - + Plane - Lorenz Meier <lorenz@px4.io> + Andreas Antener <andreas@uaventure.com> Standard Plane aileron - elevator - throttle + aileron + elevator rudder - flaps - gear + throttle + wheel + flaps feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel - + Plane - Andreas Antener <andreas@uaventure.com> + Lorenz Meier <lorenz@px4.io> Standard Plane aileron - aileron - elevator + elevator + throttle rudder - throttle - wheel - flaps + flaps + gear feed-through of RC AUX1 channel feed-through of RC AUX2 channel feed-through of RC AUX3 channel + + Rover + Marco Zorzi + Rover + https://traxxas.com/products/models/electric/stampede-vxl-tsm + steering + throttle + Rover Rover @@ -518,25 +543,32 @@ pass-through of control group 0, channel 6 pass-through of control group 0, channel 7 - - Rover - Marco Zorzi - Rover - https://traxxas.com/products/models/electric/stampede-vxl-tsm - steering - throttle - - - - - Tool - Julian Oes <julian@oes.ch> -This startup can be used on Pixhawk/Pixfalcon/Pixracer for the -passthrough of RC input and PWM output. - custom - + + + VTOL + Sander Smeets <sander@droneslab.com> + Standard VTOL + + + VTOL + Sander Smeets <sander@droneslab.com> + Standard VTOL + + + VTOL + Sander Smeets <sander@droneslab.com> + Standard VTOL + motor 1 + motor 2 + motor 3 + motor 4 + Right elevon + Left elevon + Pusher motor + Pusher reverse channel + VTOL Simon Wilks <simon@uaventure.com> @@ -563,33 +595,11 @@ passthrough of RC input and PWM output. Left elevon Motor - - VTOL - Sander Smeets <sander@droneslab.com> - Standard VTOL - - - VTOL - Sander Smeets <sander@droneslab.com> - Standard VTOL - VTOL Andreas Antener <andreas@uaventure.com> Standard VTOL - - VTOL - Sander Smeets <sander@droneslab.com> - Standard VTOL - motor 1 - motor 2 - motor 3 - motor 4 - Right elevon - Left elevon - Motor - @@ -603,11 +613,6 @@ passthrough of RC input and PWM output. - - VTOL - Roman Bapst <roman@px4.io> - VTOL Quad Tailsitter - VTOL Roman Bapst <roman@px4.io> @@ -621,8 +626,18 @@ passthrough of RC input and PWM output. canard surface rudder + + VTOL + Roman Bapst <roman@px4.io> + VTOL Quad Tailsitter + + + VTOL + Samay Siga <samay_s@icloud.com> + VTOL Tiltrotor + VTOL Roman Bapst <roman@uaventure.com> @@ -638,11 +653,6 @@ passthrough of RC input and PWM output. Elevon 2 Gear - - VTOL - Samay Siga <samay_s@icloud.com> - VTOL Tiltrotor - VTOL Andreas Antener <andreas@uaventure.com> diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc index 0c42c137aa28ad3b715187f5a07826a96f5ea64d..eff9cf1c5dfda2f8b0cf49c90c533aa284694240 100644 --- a/src/FactSystem/FactMetaData.cc +++ b/src/FactSystem/FactMetaData.cc @@ -68,6 +68,7 @@ const char* FactMetaData::_shortDescriptionJsonKey = "shortDescription"; const char* FactMetaData::_longDescriptionJsonKey = "longDescription"; const char* FactMetaData::_unitsJsonKey = "units"; const char* FactMetaData::_defaultValueJsonKey = "defaultValue"; +const char* FactMetaData::_mobileDefaultValueJsonKey = "mobileDefaultValue"; const char* FactMetaData::_minJsonKey = "min"; const char* FactMetaData::_maxJsonKey = "max"; const char* FactMetaData::_hasControlJsonKey = "control"; @@ -971,9 +972,17 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QObjec if (json.contains(_unitsJsonKey)) { metaData->setRawUnits(json[_unitsJsonKey].toString()); } +#ifdef __mobile__ + if (json.contains(_mobileDefaultValueJsonKey)) { + metaData->setRawDefaultValue(json[_mobileDefaultValueJsonKey].toVariant()); + } else if (json.contains(_defaultValueJsonKey)) { + metaData->setRawDefaultValue(json[_defaultValueJsonKey].toVariant()); + } +#else if (json.contains(_defaultValueJsonKey)) { metaData->setRawDefaultValue(json[_defaultValueJsonKey].toVariant()); } +#endif if (json.contains(_minJsonKey)) { QVariant typedValue; QString errorString; diff --git a/src/FactSystem/FactMetaData.h b/src/FactSystem/FactMetaData.h index ed35db9bc662453b6cbee9864b789773578fbc48..c88ee72409e4ad7ce07678e4c040cbc1d1ae6f58 100644 --- a/src/FactSystem/FactMetaData.h +++ b/src/FactSystem/FactMetaData.h @@ -260,6 +260,7 @@ private: static const char* _longDescriptionJsonKey; static const char* _unitsJsonKey; static const char* _defaultValueJsonKey; + static const char* _mobileDefaultValueJsonKey; static const char* _minJsonKey; static const char* _maxJsonKey; static const char* _hasControlJsonKey; diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 2b280a360952f0b1e0fa47665ac44776d2ffdf31..8f7f35953253c8e86e966aa25cf4753fd64a9e62 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -162,12 +162,10 @@ bool APMFirmwarePlugin::isCapable(const Vehicle* vehicle, FirmwareCapabilities c uint32_t available = SetFlightModeCapability | PauseVehicleCapability | GuidedModeCapability; if (vehicle->multiRotor()) { available |= TakeoffVehicleCapability; - } else if (vehicle->fixedWing()) { - // Quad plane supports takeoff - if (vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("Q_ENABLE")) && - vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("Q_ENABLE"))->rawValue().toBool()) { - available |= TakeoffVehicleCapability; - } + } else if (vehicle->fixedWing() || vehicle->vtol()) { + // Due to the way ArduPilot marks a vtol aircraft, we don't know if something is a vtol at initial connection. + // So we always enabled takeoff for fixed wing. + available |= TakeoffVehicleCapability; } return (capabilities & available) == capabilities; @@ -908,6 +906,11 @@ void APMFirmwarePlugin::guidedModeTakeoff(Vehicle* vehicle) bool APMFirmwarePlugin::_guidedModeTakeoff(Vehicle* vehicle) { + if (!vehicle->multiRotor() && !vehicle->vtol()) { + qgcApp()->showMessage(tr("Vehicle does not support guided takeoff")); + return false; + } + QString takeoffAltParam(vehicle->vtol() ? QStringLiteral("Q_RTL_ALT") : QStringLiteral("PILOT_TKOFF_ALT")); float paramDivisor = vehicle->vtol() ? 1.0 : 100.0; // PILOT_TAKEOFF_ALT is in centimeters @@ -965,6 +968,8 @@ void APMFirmwarePlugin::startMission(Vehicle* vehicle) qgcApp()->showMessage(QStringLiteral("Unable to start mission. Vehicle takeoff failed.")); return; } + } else { + return; } } diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 7b9962b76a547cd850c3718e3d3a2229e335534b..29f28cac2127beda6da1744a702e1289890df612 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -592,6 +592,16 @@ velocity 0.1 modules/commander + + RC stick override threshold + If an RC stick is moved more than by this amount the system will interpret this as override request by the pilot. + 5 + 40 + % + 0 + 0.05 + modules/commander + Home set horizontal threshold The home position will be set if the estimated positioning accuracy is below the threshold. @@ -680,6 +690,132 @@ See COM_OBL_ACT and COM_OBL_RC_ACT to configure action 1 modules/commander + + First flightmode slot (1000-1160) + If the main switch channel is in this range the selected flight mode will be applied. + modules/commander + + Land + Takeoff + Follow Me + Altitude + Manual + Mission + Position + Unassigned + Hold + Offboard + Acro + Rattitude + Return + Stabilized + + + + Second flightmode slot (1160-1320) + If the main switch channel is in this range the selected flight mode will be applied. + modules/commander + + Land + Takeoff + Follow Me + Altitude + Manual + Mission + Position + Unassigned + Hold + Offboard + Acro + Rattitude + Return + Stabilized + + + + Third flightmode slot (1320-1480) + If the main switch channel is in this range the selected flight mode will be applied. + modules/commander + + Land + Takeoff + Follow Me + Altitude + Manual + Mission + Position + Unassigned + Hold + Offboard + Acro + Rattitude + Return + Stabilized + + + + Fourth flightmode slot (1480-1640) + If the main switch channel is in this range the selected flight mode will be applied. + modules/commander + + Land + Takeoff + Follow Me + Altitude + Manual + Mission + Position + Unassigned + Hold + Offboard + Acro + Rattitude + Return + Stabilized + + + + Fifth flightmode slot (1640-1800) + If the main switch channel is in this range the selected flight mode will be applied. + modules/commander + + Land + Takeoff + Follow Me + Altitude + Manual + Mission + Position + Unassigned + Hold + Offboard + Acro + Rattitude + Return + Stabilized + + + + Sixth flightmode slot (1800-2000) + If the main switch channel is in this range the selected flight mode will be applied. + modules/commander + + Land + Takeoff + Follow Me + Altitude + Manual + Mission + Position + Unassigned + Hold + Offboard + Acro + Rattitude + Return + Stabilized + + Maximum EKF position innovation test ratio that will allow arming 0.1 @@ -743,7 +879,7 @@ See COM_OBL_ACT and COM_OBL_RC_ACT to configure action 0.05 modules/commander - + Maximum rate gyro inconsistency between IMU units that will allow arming 0.02 0.3 @@ -763,6 +899,37 @@ See COM_OBL_ACT and COM_OBL_RC_ACT to configure action modules/commander + + Arm authorization parameters, this uint32_t will be splitted between starting from the LSB: +- 8bits to authorizer system id +- 16bits to authentication method parameter, this will be used to store a timeout for the first 2 methods but can be used to another parameter for other new authentication methods. +- 7bits to authentication method +- one arm = 0 +- two step arm = 1 +* the MSB bit is not used to avoid problems in the conversion between int and uint + Default value: (10 << 0 | 1000 << 8 | 0 << 24) = 256010 - authorizer system id = 10 - authentication method parameter = 10000msec of timeout - authentication method = during arm + modules/commander + + + Loss of position failsafe activation delay + This sets number of seconds that the position checks need to be failed before the failsafe will activate. The default value has been optimised for rotary wing applications. For fixed wing applications, a larger value between 5 and 10 should be used. + sec + true + modules/commander + + + Loss of position probation delay at takeoff + The probation delay is the number of seconds that the EKF innovation checks need to pass for the position to be declared good after it has been declared bad. The probation delay will be reset to this parameter value when takeoff is detected. After takeoff, if position checks are passing, the probation delay will reduce by one second for every lapsed second of valid position down to a minimum of 1 second. If position checks are failing, the probation delay will increase by COM_POS_FS_GAIN seconds for every lapsed second up to a maximum of 100 seconds. The default value has been optimised for rotary wing applications. For fixed wing applications, a value of 1 should be used. + sec + true + modules/commander + + + Loss of position probation gain factor + This sets the rate that the loss of position probation time grows when position checks are failing. The default value has been optimised for rotary wing applications. For fixed wing applications a value of 0 should be used. + true + modules/commander + @@ -1196,17 +1363,11 @@ This parameter is used when the magnetometer fusion method is set automatically 1 modules/ekf2 - - Replay mode - A value of 1 indicates that the ekf2 module will publish replay messages for logging. - - modules/ekf2 - Integer bitmask controlling data fusion and aiding methods - Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion + Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion 5 : Set to true to enable multi-rotor drag specific force fusion 0 - 28 + 63 modules/ekf2 use GPS @@ -1214,6 +1375,7 @@ This parameter is used when the magnetometer fusion method is set automatically inhibit IMU bias estimation vision position fusion vision yaw fusion + multi-rotor drag fusion @@ -1277,13 +1439,6 @@ This parameter is used when the magnetometer fusion method is set automatically 1 modules/ekf2 - - Minimum valid range for the vision estimate - 0.01 - m - 2 - modules/ekf2 - Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum 0.05 @@ -1561,6 +1716,76 @@ Smaller values make the saved mag bias learn slower from flight to flight. Large SD modules/ekf2 + + Specific drag force observation noise variance used by the multi-rotor specific drag force model. +Increasing it makes the multi-rotor wind estimates adjust more slowly + 0.5 + 10.0 + (m/sec**2)**2 + 2 + modules/ekf2 + + + X-axis ballistic coefficient used by the multi-rotor specific drag force model. +This should be adjusted to minimise variance of the X-axis drag specific force innovation sequence + 1.0 + 100.0 + kg/m**2 + 1 + modules/ekf2 + + + Y-axis ballistic coefficient used by the multi-rotor specific drag force model. +This should be adjusted to minimise variance of the Y-axis drag specific force innovation sequence + 1.0 + 100.0 + kg/m**2 + 1 + modules/ekf2 + + + Upper limit on airspeed along individual axes used to correct baro for position error effects + 5.0 + 50.0 + m/s + 1 + modules/ekf2 + + + Static pressure position error coefficient for the positive X axis +This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. +If the baro height estimate rises during forward flight, then this will be a negative number + -0.5 + 0.5 + 2 + modules/ekf2 + + + Static pressure position error coefficient for the negative X axis. +This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. +If the baro height estimate rises during backwards flight, then this will be a negative number + -0.5 + 0.5 + 2 + modules/ekf2 + + + Pressure position error coefficient for the Y axis. +This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Y body axis. +If the baro height estimate rises during sideways flight, then this will be a negative number + -0.5 + 0.5 + 2 + modules/ekf2 + + + Static pressure position error coefficient for the Z axis. +This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis + -0.5 + 0.5 + 2 + modules/ekf2 + @@ -1574,7 +1799,7 @@ Smaller values make the saved mag bias learn slower from flight to flight. Large modules/fw_att_control - Attitude Pitch Time Constant + Attitude pitch time constant This defines the latency between a pitch step input and the achieved setpoint (inverse to a P gain). Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed. 0.2 1.0 @@ -1653,7 +1878,7 @@ Smaller values make the saved mag bias learn slower from flight to flight. Large modules/fw_att_control - Roll Integrator Anti-Windup + Roll integrator anti-windup The portion of the integrator part in the control surface deflection is limited to this value. 0.0 1.0 @@ -1662,7 +1887,7 @@ Smaller values make the saved mag bias learn slower from flight to flight. Large modules/fw_att_control - Maximum Roll Rate + Maximum roll rate This limits the maximum roll rate the controller will output (in degrees per second). Setting a value of zero disables the limit. 0.0 90.0 @@ -1701,7 +1926,7 @@ Smaller values make the saved mag bias learn slower from flight to flight. Large modules/fw_att_control - Maximum Yaw Rate + Maximum yaw rate This limits the maximum yaw rate the controller will output (in degrees per second). Setting a value of zero disables the limit. 0.0 90.0 @@ -1824,7 +2049,7 @@ Smaller values make the saved mag bias learn slower from flight to flight. Large - Roll Setpoint Offset + Roll setpoint offset An airframe specific offset of the roll setpoint in degrees, the value is added to the roll setpoint and should correspond to the typical cruise speed of the airframe. -90.0 90.0 @@ -1834,7 +2059,7 @@ Smaller values make the saved mag bias learn slower from flight to flight. Large modules/fw_att_control - Pitch Setpoint Offset + Pitch setpoint offset An airframe specific offset of the pitch setpoint in degrees, the value is added to the pitch setpoint and should correspond to the typical cruise speed of the airframe. -90.0 90.0 @@ -1844,7 +2069,7 @@ Smaller values make the saved mag bias learn slower from flight to flight. Large modules/fw_att_control - Max Manual Roll + Max manual roll Max roll for manual control in attitude stabilized mode 0.0 90.0 @@ -1854,7 +2079,7 @@ Smaller values make the saved mag bias learn slower from flight to flight. Large modules/fw_att_control - Max Manual Pitch + Max manual pitch Max pitch for manual control in attitude stabilized mode 0.0 90.0 @@ -1882,16 +2107,10 @@ Smaller values make the saved mag bias learn slower from flight to flight. Large modules/fw_att_control - Airspeed mode - The param value sets the method used to publish the control state airspeed. For small wings or VTOL without airspeed sensor this parameter can be used to enable flying without an airspeed reading - 0 - 2 + Disable airspeed sensor + For small wings or VTOL without airspeed sensor this parameter can be used to enable flying without an airspeed reading + modules/fw_att_control - - use vehicle ground velocity as airspeed - use measured airspeed - declare airspeed invalid - Manual roll scale @@ -2695,9 +2914,9 @@ but also ignore less noise - + Loiter time - The amount of time in seconds the system should do open loop loiter and wait for gps recovery before it goes into flight termination. + The time in seconds the system should do open loop loiter and wait for GPS recovery before it goes into flight termination. Set to 0 to disable. 0.0 3600.0 s @@ -2706,8 +2925,8 @@ but also ignore less noise modules/navigator - Open loop loiter roll - Roll in degrees during the open loop loiter + Fixed bank angle + Roll in degrees during the loiter 0.0 30.0 deg @@ -2716,7 +2935,7 @@ but also ignore less noise modules/navigator - Open loop loiter pitch + Fixed pitch angle Pitch in degrees during the open loop loiter -30.0 30.0 @@ -2725,8 +2944,8 @@ but also ignore less noise 0.5 modules/navigator - - Open loop loiter thrust + + Thrust Thrust value which is set during the open loop loiter 0.0 1.0 @@ -2817,7 +3036,7 @@ but also ignore less noise 1 modules/land_detector - + Multicopter max horizontal velocity Maximum horizontal velocity allowed in the landed state (m/s) m/s @@ -3388,10 +3607,10 @@ by initializing the estimator to the LPE_LAT/LON parameters when global informat Maximal horizontal distance from home to first waypoint Failsafe check to prevent running mission stored from previous flight at a new takeoff location. Set a value of zero or less to disable. The mission will not be started if the current waypoint is more distant than MIS_DIS_1WP from the home position. 0 - 1000 + 10000 m 1 - 0.5 + 100 modules/navigator @@ -3416,11 +3635,12 @@ by initializing the estimator to the LPE_LAT/LON parameters when global informat Heading as set by waypoint Heading away from home Heading towards home + Heading towards ROI Time in seconds we wait on reaching target heading at a waypoint if it is forced - If set > 0 it will ignore the target heading for normal waypoint acceptance. If the waypoint forces the heading the timeout will matter. For example on VTOL forwards transiton. Mainly useful for VTOLs that have less yaw authority and might not reach target yaw in wind. Disabled by default. + If set > 0 it will ignore the target heading for normal waypoint acceptance. If the waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. Mainly useful for VTOLs that have less yaw authority and might not reach target yaw in wind. Disabled by default. -1 20 s @@ -3528,10 +3748,8 @@ by initializing the estimator to the LPE_LAT/LON parameters when global informat - Mount input mode -RC uses the AUX input channels (see MNT_MAN_* parameters), -MAVLINK_ROI uses the MAV_CMD_DO_SET_ROI Mavlink message, and MAVLINK_DO_MOUNT the -MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL messages to control a mount + Mount input mode + RC uses the AUX input channels (see MNT_MAN_* parameters), MAVLINK_ROI uses the MAV_CMD_DO_SET_ROI Mavlink message, and MAVLINK_DO_MOUNT the MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL messages to control a mount. -1 3 true @@ -3545,10 +3763,8 @@ MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL messages to control a mo - Mount output mode -AUX uses the mixer output Control Group #2. -MAVLINK uses the MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL MavLink messages -to control a mount (set MNT_MAV_SYSID & MNT_MAV_COMPID) + Mount output mode + AUX uses the mixer output Control Group #2. MAVLINK uses the MAV_CMD_DO_MOUNT_CONFIGURE and MAV_CMD_DO_MOUNT_CONTROL MavLink messages to control a mount (set MNT_MAV_SYSID & MNT_MAV_COMPID) 0 1 drivers/vmount @@ -3557,12 +3773,14 @@ to control a mount (set MNT_MAV_SYSID & MNT_MAV_COMPID) AUX - - Mavlink System ID (if MNT_MODE_OUT is MAVLINK) + + Mavlink System ID of the mount + If MNT_MODE_OUT is MAVLINK, mount configure/control commands will be sent with this target ID. drivers/vmount - - Mavlink Component ID (if MNT_MODE_OUT is MAVLINK) + + Mavlink Component ID of the mount + If MNT_MODE_OUT is MAVLINK, mount configure/control commands will be sent with this component ID. drivers/vmount @@ -4070,7 +4288,7 @@ if required for the gimbal (only in AUX output mode) modules/mc_pos_control - Nominal horizontal velocity in mission + Maximum horizontal velocity in mission Normal horizontal velocity in AUTO modes (includes also RTL / hold / etc.) and endpoint for position stabilized mode (POSCTRL). 3.0 20.0 @@ -4079,26 +4297,29 @@ if required for the gimbal (only in AUX output mode) 1 modules/mc_pos_control - - Nominal horizontal velocity for manual controlled mode - 3.0 - 20.0 + + Cruise speed when angle prev-current/current-next setpoint +is 90 degrees. It should be lower than MPC_XY_CRUISE + Applies only in AUTO modes (includes also RTL / hold / etc.) + 1.0 + m/s 2 1 modules/mc_pos_control - - Distance Threshold Horizontal Auto - The distance defines at which point the vehicle has to slow down to reach target if no direct passing to the next target is desired - 1.0 - 50.0 - m + + Maximum horizontal velocity setpoint for manual controlled mode +If velocity setpoint larger than MPC_XY_VEL_MAX is set, then +the setpoint will be capped to MPC_XY_VEL_MAX + 3.0 + 20.0 + m/s 2 1 modules/mc_pos_control - + Maximum horizontal velocity Maximum horizontal velocity in AUTO mode. If higher speeds are commanded in a mission they will be capped to this velocity. 0.0 @@ -4144,7 +4365,7 @@ if required for the gimbal (only in AUX output mode) Maximal tilt angle in manual or altitude mode 0.0 - 90.0 + 85.0 deg 1 modules/mc_pos_control @@ -4188,8 +4409,8 @@ if required for the gimbal (only in AUX output mode) 2 modules/mc_pos_control - - Maximum horizonal acceleration in velocity controlled modes + + Maximum horizontal acceleration for auto mode and maximum deceleration for manual mode 2.0 15.0 m/s/s @@ -4197,8 +4418,8 @@ if required for the gimbal (only in AUX output mode) 1 modules/mc_pos_control - - Maximum horizonal braking deceleration in velocity controlled modes + + Acceleration for auto and for manual 2.0 15.0 m/s/s @@ -4206,7 +4427,16 @@ if required for the gimbal (only in AUX output mode) 1 modules/mc_pos_control - + + Slow horizontal manual deceleration for manual mode + 0.5 + 10.0 + m/s/s + 2 + 1 + modules/mc_pos_control + + Maximum vertical acceleration in velocity controlled modes upward 2.0 15.0 @@ -4215,7 +4445,7 @@ if required for the gimbal (only in AUX output mode) 1 modules/mc_pos_control - + Maximum vertical acceleration in velocity controlled modes down 2.0 15.0 @@ -4224,6 +4454,29 @@ if required for the gimbal (only in AUX output mode) 1 modules/mc_pos_control + + Maximum jerk in manual controlled mode for BRAKING to zero. +If this value is below MPC_JERK_MIN, the acceleration limit in xy and z +is MPC_ACC_HOR_MAX and MPC_ACC_UP_MAX respectively instantaneously when the +user demands brake (=zero stick input). +Otherwise the acceleration limit increases from current acceleration limit +towards MPC_ACC_HOR_MAX/MPC_ACC_UP_MAX with jerk limit + 0.0 + 15.0 + m/s/s/s + 2 + 1 + modules/mc_pos_control + + + Minimum jerk in manual controlled mode for BRAKING to zero + 0.5 + 10.0 + m/s/s/s + 2 + 1 + modules/mc_pos_control + Altitude control mode, note mode 1 only tested with LPE 0 @@ -4367,18 +4620,158 @@ if required for the gimbal (only in AUX output mode) 2 drivers/px4fmu - - Set the PWM output frequency for the main outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. Set to 400 for industry default or 1000 for high frequency ESCs. Set to 0 for Oneshot125. - -1 - 2000 - Hz + + Thrust to PWM model parameter + Parameter used to model the relationship between static thrust and motor input PWM. Model is: thrust = (1-factor)*PWM + factor * PWM^2 + 0.0 + 1.0 + drivers/px4fmu + + + Minimum motor rise time (slew rate limit) + Minimum time allowed for the motor input signal to pass through a range of 1000 PWM units. A value x means that the motor signal can only go from 1000 to 2000 PWM in maximum x seconds. Zero means that slew rate limiting is disabled. + 0.0 + s/(1000*PWM) + drivers/px4fmu + + + Invert direction of main output channel 1 + Set to 1 to invert the channel, 0 for default direction. + true - modules/sensors + drivers/px4io - + + Invert direction of main output channel 2 + Set to 1 to invert the channel, 0 for default direction. + + true + drivers/px4io + + + Invert direction of main output channel 3 + Set to 1 to invert the channel, 0 for default direction. + + true + drivers/px4io + + + Invert direction of main output channel 4 + Set to 1 to invert the channel, 0 for default direction. + + true + drivers/px4io + + + Invert direction of main output channel 5 + Set to 1 to invert the channel, 0 for default direction. + + true + drivers/px4io + + + Invert direction of main output channel 6 + Set to 1 to invert the channel, 0 for default direction. + + true + drivers/px4io + + + Invert direction of main output channel 7 + Set to 1 to invert the channel, 0 for default direction. + + true + drivers/px4io + + + Invert direction of main output channel 8 + Set to 1 to invert the channel, 0 for default direction. + + true + drivers/px4io + + + Trim value for main output channel 1 + Set to normalized offset + -0.2 + 0.2 + 2 + drivers/px4io + + + Trim value for main output channel 2 + Set to normalized offset + -0.2 + 0.2 + 2 + drivers/px4io + + + Trim value for main output channel 3 + Set to normalized offset + -0.2 + 0.2 + 2 + drivers/px4io + + + Trim value for main output channel 4 + Set to normalized offset + -0.2 + 0.2 + 2 + drivers/px4io + + + Trim value for main output channel 5 + Set to normalized offset + -0.2 + 0.2 + 2 + drivers/px4io + + + Trim value for main output channel 6 + Set to normalized offset + -0.2 + 0.2 + 2 + drivers/px4io + + + Trim value for main output channel 7 + Set to normalized offset + -0.2 + 0.2 + 2 + drivers/px4io + + + Trim value for main output channel 8 + Set to normalized offset + -0.2 + 0.2 + 2 + drivers/px4io + + + S.BUS out + Set to 1 to enable S.BUS version 1 output instead of RSSI. + + drivers/px4io + + + Set the PWM output frequency for the main outputs + Set to 400 for industry default or 1000 for high frequency ESCs. Set to 0 for Oneshot125. + -1 + 2000 + Hz + true + modules/sensors + + Set the minimum PWM for the main outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. Set to 1000 for industry default or 900 to increase servo travel. + Set to 1000 for industry default or 900 to increase servo travel. 800 1400 us @@ -4387,7 +4780,7 @@ if required for the gimbal (only in AUX output mode) Set the maximum PWM for the main outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. Set to 2000 for industry default or 2100 to increase servo travel. + Set to 2000 for industry default or 2100 to increase servo travel. 1600 2200 us @@ -4396,16 +4789,142 @@ if required for the gimbal (only in AUX output mode) Set the disarmed PWM for the main outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. + This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. 0 2200 us true modules/sensors + + Set the disarmed PWM for the main 1 output + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used + -1 + 2200 + us + true + modules/sensors + + + Set the disarmed PWM for the main 2 output + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used + -1 + 2200 + us + true + modules/sensors + + + Set the disarmed PWM for the main 3 output + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used + -1 + 2200 + us + true + modules/sensors + + + Set the disarmed PWM for the main 4 output + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used + -1 + 2200 + us + true + modules/sensors + + + Set the disarmed PWM for the main 5 output + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used + -1 + 2200 + us + true + modules/sensors + + + Set the disarmed PWM for the main 6 output + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used + -1 + 2200 + us + true + modules/sensors + + + Set the disarmed PWM for the main 7 output + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used + -1 + 2200 + us + true + modules/sensors + + + Set the disarmed PWM for the main 8 output + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_DISARMED will be used + -1 + 2200 + us + true + modules/sensors + + + Set the disarmed PWM for the AUX 1 output + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used + -1 + 2200 + us + true + modules/sensors + + + Set the disarmed PWM for the AUX 2 output + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used + -1 + 2200 + us + true + modules/sensors + + + Set the disarmed PWM for the AUX 3 output + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used + -1 + 2200 + us + true + modules/sensors + + + Set the disarmed PWM for the AUX 4 output + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used + -1 + 2200 + us + true + modules/sensors + + + Set the disarmed PWM for the AUX 5 output + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used + -1 + 2200 + us + true + modules/sensors + + + Set the disarmed PWM for the AUX 6 output + This is the PWM pulse the autopilot is outputting if not armed. When set to -1 the value for PWM_AUX_DISARMED will be used + -1 + 2200 + us + true + modules/sensors + Set the minimum PWM for the auxiliary outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. Set to 1000 for default or 900 to increase servo travel + Set to 1000 for default or 900 to increase servo travel 800 1400 us @@ -4414,7 +4933,7 @@ if required for the gimbal (only in AUX output mode) Set the maximum PWM for the auxiliary outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. Set to 2000 for default or 2100 to increase servo travel + Set to 2000 for default or 2100 to increase servo travel 1600 2200 us @@ -4423,27 +4942,13 @@ if required for the gimbal (only in AUX output mode) Set the disarmed PWM for auxiliary outputs - IMPORTANT: CHANGING THIS PARAMETER REQUIRES A COMPLETE SYSTEM REBOOT IN ORDER TO APPLY THE CHANGES. This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. + This is the PWM pulse the autopilot is outputting if not armed. The main use of this parameter is to silence ESCs when they are disarmed. 0 2200 us true modules/sensors - - Thrust to PWM model parameter - Parameter used to model the relationship between static thrust and motor input PWM. Model is: thrust = (1-factor)*PWM + factor * PWM^2 - 0.0 - 1.0 - modules/sensors - - - Minimum motor rise time (slew rate limit) - Minimum time allowed for the motor input signal to pass through a range of 1000 PWM units. A value x means that the motor signal can only go from 1000 to 2000 PWM in maximum x seconds. Zero means that slew rate limiting is disabled. - 0.0 - s/(1000*PWM) - modules/sensors - @@ -4854,8 +5359,50 @@ if required for the gimbal (only in AUX output mode) + + PWM input channel that provides RSSI + 0: do not read RSSI from input channel 1-18: read RSSI from specified input channel Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters. + 0 + 18 + drivers/px4io + + Channel 11 + Channel 10 + Channel 13 + Channel 12 + Channel 15 + Channel 14 + Channel 17 + Channel 16 + Channel 18 + Channel 1 + Unassigned + Channel 3 + Channel 2 + Channel 5 + Channel 4 + Channel 7 + Channel 6 + Channel 9 + Channel 8 + + + + Max input value for RSSI reading + Only used if RC_RSSI_PWM_CHAN > 0 + 0 + 2000 + drivers/px4io + + + Min input value for RSSI reading + Only used if RC_RSSI_PWM_CHAN > 0 + 0 + 2000 + drivers/px4io + - RC Channel 1 Minimum + RC channel 1 minimum Minimum value for RC channel 1 800.0 1500.0 @@ -4863,7 +5410,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 1 Trim + RC channel 1 trim Mid point value (same as min for throttle) 800.0 2200.0 @@ -4871,7 +5418,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 1 Maximum + RC channel 1 maximum Maximum value for RC channel 1 1500.0 2200.0 @@ -4879,14 +5426,14 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 1 Reverse + RC channel 1 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 1 dead zone + RC channel 1 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 @@ -4894,7 +5441,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 2 Minimum + RC channel 2 minimum Minimum value for this channel. 800.0 1500.0 @@ -4902,7 +5449,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 2 Trim + RC channel 2 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -4910,7 +5457,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 2 Maximum + RC channel 2 maximum Maximum value for this channel. 1500.0 2200.0 @@ -4918,14 +5465,14 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 2 Reverse + RC channel 2 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 2 dead zone + RC channel 2 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 @@ -4933,7 +5480,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 3 Minimum + RC channel 3 minimum Minimum value for this channel. 800.0 1500.0 @@ -4941,7 +5488,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 3 Trim + RC channel 3 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -4949,7 +5496,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 3 Maximum + RC channel 3 maximum Maximum value for this channel. 1500.0 2200.0 @@ -4957,14 +5504,14 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 3 Reverse + RC channel 3 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 3 dead zone + RC channel 3 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 @@ -4972,7 +5519,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 4 Minimum + RC channel 4 minimum Minimum value for this channel. 800.0 1500.0 @@ -4980,7 +5527,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 4 Trim + RC channel 4 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -4988,7 +5535,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 4 Maximum + RC channel 4 maximum Maximum value for this channel. 1500.0 2200.0 @@ -4996,14 +5543,14 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 4 Reverse + RC channel 4 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 4 dead zone + RC channel 4 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 @@ -5011,7 +5558,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 5 Minimum + RC channel 5 minimum Minimum value for this channel. 800.0 1500.0 @@ -5019,7 +5566,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 5 Trim + RC channel 5 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -5027,7 +5574,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 5 Maximum + RC channel 5 maximum Maximum value for this channel. 1500.0 2200.0 @@ -5035,21 +5582,21 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 5 Reverse + RC channel 5 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 5 dead zone + RC channel 5 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 modules/sensors - RC Channel 6 Minimum + RC channel 6 minimum Minimum value for this channel. 800.0 1500.0 @@ -5057,7 +5604,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 6 Trim + RC channel 6 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -5065,7 +5612,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 6 Maximum + RC channel 6 maximum Maximum value for this channel. 1500.0 2200.0 @@ -5073,21 +5620,21 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 6 Reverse + RC channel 6 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 6 dead zone + RC channel 6 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 modules/sensors - RC Channel 7 Minimum + RC channel 7 minimum Minimum value for this channel. 800.0 1500.0 @@ -5095,7 +5642,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 7 Trim + RC channel 7 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -5103,7 +5650,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 7 Maximum + RC channel 7 maximum Maximum value for this channel. 1500.0 2200.0 @@ -5111,21 +5658,21 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 7 Reverse + RC channel 7 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 7 dead zone + RC channel 7 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 modules/sensors - RC Channel 8 Minimum + RC channel 8 minimum Minimum value for this channel. 800.0 1500.0 @@ -5133,7 +5680,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 8 Trim + RC channel 8 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -5141,7 +5688,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 8 Maximum + RC channel 8 maximum Maximum value for this channel. 1500.0 2200.0 @@ -5149,21 +5696,21 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 8 Reverse + RC channel 8 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 8 dead zone + RC channel 8 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 modules/sensors - RC Channel 9 Minimum + RC channel 9 minimum Minimum value for this channel. 800.0 1500.0 @@ -5171,7 +5718,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 9 Trim + RC channel 9 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -5179,7 +5726,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 9 Maximum + RC channel 9 maximum Maximum value for this channel. 1500.0 2200.0 @@ -5187,21 +5734,21 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 9 Reverse + RC channel 9 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 9 dead zone + RC channel 9 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 modules/sensors - RC Channel 10 Minimum + RC channel 10 minimum Minimum value for this channel. 800.0 1500.0 @@ -5209,7 +5756,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 10 Trim + RC channel 10 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -5217,7 +5764,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 10 Maximum + RC channel 10 maximum Maximum value for this channel. 1500.0 2200.0 @@ -5225,21 +5772,21 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 10 Reverse + RC channel 10 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 10 dead zone + RC channel 10 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 modules/sensors - RC Channel 11 Minimum + RC channel 11 minimum Minimum value for this channel. 800.0 1500.0 @@ -5247,7 +5794,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 11 Trim + RC channel 11 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -5255,7 +5802,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 11 Maximum + RC channel 11 maximum Maximum value for this channel. 1500.0 2200.0 @@ -5263,21 +5810,21 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 11 Reverse + RC channel 11 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 11 dead zone + RC channel 11 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 modules/sensors - RC Channel 12 Minimum + RC channel 12 minimum Minimum value for this channel. 800.0 1500.0 @@ -5285,7 +5832,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 12 Trim + RC channel 12 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -5293,7 +5840,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 12 Maximum + RC channel 12 maximum Maximum value for this channel. 1500.0 2200.0 @@ -5301,21 +5848,21 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 12 Reverse + RC channel 12 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 12 dead zone + RC channel 12 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 modules/sensors - RC Channel 13 Minimum + RC channel 13 minimum Minimum value for this channel. 800.0 1500.0 @@ -5323,7 +5870,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 13 Trim + RC channel 13 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -5331,7 +5878,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 13 Maximum + RC channel 13 maximum Maximum value for this channel. 1500.0 2200.0 @@ -5339,21 +5886,21 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 13 Reverse + RC channel 13 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 13 dead zone + RC channel 13 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 modules/sensors - RC Channel 14 Minimum + RC channel 14 minimum Minimum value for this channel. 800.0 1500.0 @@ -5361,7 +5908,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 14 Trim + RC channel 14 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -5369,7 +5916,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 14 Maximum + RC channel 14 maximum Maximum value for this channel. 1500.0 2200.0 @@ -5377,21 +5924,21 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 14 Reverse + RC channel 14 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 14 dead zone + RC channel 14 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 modules/sensors - RC Channel 15 Minimum + RC channel 15 minimum Minimum value for this channel. 800.0 1500.0 @@ -5399,7 +5946,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 15 Trim + RC channel 15 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -5407,7 +5954,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 15 Maximum + RC channel 15 maximum Maximum value for this channel. 1500.0 2200.0 @@ -5415,21 +5962,21 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 15 Reverse + RC channel 15 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 15 dead zone + RC channel 15 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 modules/sensors - RC Channel 16 Minimum + RC channel 16 minimum Minimum value for this channel. 800.0 1500.0 @@ -5437,7 +5984,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 16 Trim + RC channel 16 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -5445,7 +5992,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 16 Maximum + RC channel 16 maximum Maximum value for this channel. 1500.0 2200.0 @@ -5453,21 +6000,21 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 16 Reverse + RC channel 16 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 16 dead zone + RC channel 16 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 modules/sensors - RC Channel 17 Minimum + RC channel 17 minimum Minimum value for this channel. 800.0 1500.0 @@ -5475,7 +6022,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 17 Trim + RC channel 17 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -5483,7 +6030,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 17 Maximum + RC channel 17 maximum Maximum value for this channel. 1500.0 2200.0 @@ -5491,21 +6038,21 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 17 Reverse + RC channel 17 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 17 dead zone + RC channel 17 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 modules/sensors - RC Channel 18 Minimum + RC channel 18 minimum Minimum value for this channel. 800.0 1500.0 @@ -5513,7 +6060,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 18 Trim + RC channel 18 trim Mid point value (has to be set to the same as min for throttle channel). 800.0 2200.0 @@ -5521,7 +6068,7 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 18 Maximum + RC channel 18 maximum Maximum value for this channel. 1500.0 2200.0 @@ -5529,14 +6076,14 @@ if required for the gimbal (only in AUX output mode) modules/sensors - RC Channel 18 Reverse + RC channel 18 reverse Set to -1 to reverse channel. -1.0 1.0 modules/sensors - RC Channel 18 dead zone + RC channel 18 dead zone The +- range of this value around the trim value will be considered as zero. 0.0 100.0 @@ -5552,17 +6099,6 @@ if required for the gimbal (only in AUX output mode) Disabled - - DSM binding trigger - -1 - 1 - modules/sensors - - Start DSMX bind - Start DSM2 bind - Inactive - - RC channel count This parameter is used by Ground Station software to save the number of channels which were used during RC calibration. It is only meant for ground station use. @@ -5632,6 +6168,34 @@ if required for the gimbal (only in AUX output mode) Channel 8 + + Failsafe channel mapping + The RC mapping index indicates which channel is used for failsafe If 0, whichever channel is mapped to throttle is used otherwise the value indicates the specific RC channel to use + 0 + 18 + modules/sensors + + Channel 11 + Channel 10 + Channel 13 + Channel 12 + Channel 15 + Channel 14 + Channel 17 + Channel 16 + Channel 18 + Channel 1 + Unassigned + Channel 3 + Channel 2 + Channel 5 + Channel 4 + Channel 7 + Channel 6 + Channel 9 + Channel 8 + + Throttle control channel mapping The channel index (starting from 1 for channel 1) indicates which channel should be used for reading throttle inputs from. A value of zero indicates the switch is not assigned. @@ -5689,7 +6253,7 @@ if required for the gimbal (only in AUX output mode) - AUX1 Passthrough RC Channel + AUX1 Passthrough RC channel Default function: Camera pitch 0 18 @@ -5717,7 +6281,7 @@ if required for the gimbal (only in AUX output mode) - AUX2 Passthrough RC Channel + AUX2 Passthrough RC channel Default function: Camera roll 0 18 @@ -5745,7 +6309,7 @@ if required for the gimbal (only in AUX output mode) - AUX3 Passthrough RC Channel + AUX3 Passthrough RC channel Default function: Camera azimuth / yaw 0 18 @@ -5773,7 +6337,7 @@ if required for the gimbal (only in AUX output mode) - AUX4 Passthrough RC Channel + AUX4 Passthrough RC channel 0 18 modules/sensors @@ -5800,7 +6364,7 @@ if required for the gimbal (only in AUX output mode) - AUX5 Passthrough RC Channel + AUX5 Passthrough RC channel 0 18 modules/sensors @@ -5918,48 +6482,6 @@ if required for the gimbal (only in AUX output mode) us modules/sensors - - PWM input channel that provides RSSI - 0: do not read RSSI from input channel 1-18: read RSSI from specified input channel Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters. - 0 - 18 - modules/sensors - - Channel 11 - Channel 10 - Channel 13 - Channel 12 - Channel 15 - Channel 14 - Channel 17 - Channel 16 - Channel 18 - Channel 1 - Unassigned - Channel 3 - Channel 2 - Channel 5 - Channel 4 - Channel 7 - Channel 6 - Channel 9 - Channel 8 - - - - Max input value for RSSI reading - Only used if RC_RSSI_PWM_CHAN > 0 - 0 - 2000 - modules/sensors - - - Min input value for RSSI reading - Only used if RC_RSSI_PWM_CHAN > 0 - 0 - 2000 - modules/sensors - Sample rate of the remote control values for the low pass filter on roll,pitch, yaw and throttle Has an influence on the cutoff frequency precision. @@ -6648,46 +7170,6 @@ FW_AIRSPD_MIN * RWTO_AIRSPD_SCL - - Logging rate - A value of -1 indicates the commandline argument should be obeyed. A value of 0 sets the minimum rate, any other value is interpreted as rate in Hertz. This parameter is only read out before logging starts (which commonly is before arming). - -1 - 250 - Hz - modules/sdlog2 - - - Extended logging mode - A value of -1 indicates the command line argument should be obeyed. A value of 0 disables extended logging mode, a value of 1 enables it. This parameter is only read out before logging starts (which commonly is before arming). - -1 - 1 - modules/sdlog2 - - Enable - Disable - Command Line - - - - Use timestamps only if GPS 3D fix is available - Constrain the log folder creation to only use the time stamp if a 3D GPS lock is present. - - modules/sdlog2 - - - Give logging app higher thread priority to avoid data loss. -This is used for gathering replay logs for the ekf2 module - A value of 0 indicates that the default priority is used. Increasing the parameter in steps of one increases the priority. - 0 - 3 - modules/sdlog2 - - Default priority - Low priority - Max priority - Medium priority - - UTC offset (unit: min) the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets @@ -6736,6 +7218,46 @@ This is used for gathering replay logs for the ekf2 module modules/logger + + Logging rate + A value of -1 indicates the commandline argument should be obeyed. A value of 0 sets the minimum rate, any other value is interpreted as rate in Hertz. This parameter is only read out before logging starts (which commonly is before arming). + -1 + 250 + Hz + modules/sdlog2 + + + Extended logging mode + A value of -1 indicates the command line argument should be obeyed. A value of 0 disables extended logging mode, a value of 1 enables it. This parameter is only read out before logging starts (which commonly is before arming). + -1 + 1 + modules/sdlog2 + + Enable + Disable + Command Line + + + + Use timestamps only if GPS 3D fix is available + Constrain the log folder creation to only use the time stamp if a 3D GPS lock is present. + + modules/sdlog2 + + + Give logging app higher thread priority to avoid data loss. +This is used for gathering replay logs for the ekf2 module + A value of 0 indicates that the default priority is used. Increasing the parameter in steps of one increases the priority. + 0 + 3 + modules/sdlog2 + + Default priority + Low priority + Max priority + Medium priority + + @@ -7258,6 +7780,20 @@ This is used for gathering replay logs for the ekf2 module Primary baro ID modules/sensors + + Airspeed sensor pitot model + modules/sensors + + HB Pitot + + + + Airspeed sensor tube length + 0.01 + 0.5 + meter + modules/sensors + Differential pressure sensor offset The offset (zero-reading) in Pascal @@ -7397,16 +7933,23 @@ DEPRECATED, only used on V1 hardware true modules/sensors - - TeraRanger One (trone) - + + TeraRanger Rangefinder (i2c) + 0 + 3 true modules/sensors + + Autodetect + Disabled + TREvo + TROne + - Lightware SF1xx laser rangefinder (i2c) + Lightware SF1xx/SF20/LW20 laser rangefinder (i2c) 0 - 4 + 5 true modules/sensors @@ -7414,6 +7957,7 @@ DEPRECATED, only used on V1 hardware Disabled SF10/c SF10/b + SF/LW20 SF11/c @@ -7661,380 +8205,396 @@ DEPRECATED, only used on V1 hardware Accelerometer calibration maximum temperature modules/sensors - - Set to 1 to enable thermal compensation for barometric pressure sensors. Set to 0 to disable + + Set to 1 to enable thermal compensation for rate gyro sensors. Set to 0 to disable 0 1 modules/sensors - - ID of Barometer that the calibration is for + + ID of Gyro that the calibration is for modules/sensors - - Barometer offset temperature ^5 polynomial coefficient + + Gyro rate offset temperature ^3 polynomial coefficient - X axis modules/sensors - - Barometer offset temperature ^4 polynomial coefficient + + Gyro rate offset temperature ^3 polynomial coefficient - Y axis modules/sensors - - Barometer offset temperature ^3 polynomial coefficient + + Gyro rate offset temperature ^3 polynomial coefficient - Z axis modules/sensors - - Barometer offset temperature ^2 polynomial coefficient + + Gyro rate offset temperature ^2 polynomial coefficient - X axis modules/sensors - - Barometer offset temperature ^1 polynomial coefficients + + Gyro rate offset temperature ^2 polynomial coefficient - Y axis modules/sensors - - Barometer offset temperature ^0 polynomial coefficient + + Gyro rate offset temperature ^2 polynomial coefficient - Z axis modules/sensors - - Barometer scale factor - X axis + + Gyro rate offset temperature ^1 polynomial coefficient - X axis modules/sensors - - Barometer calibration reference temperature + + Gyro rate offset temperature ^1 polynomial coefficient - Y axis modules/sensors - - Barometer calibration minimum temperature + + Gyro rate offset temperature ^1 polynomial coefficient - Z axis modules/sensors - - Barometer calibration maximum temperature + + Gyro rate offset temperature ^0 polynomial coefficient - X axis modules/sensors - - ID of Barometer that the calibration is for + + Gyro rate offset temperature ^0 polynomial coefficient - Y axis modules/sensors - - Barometer offset temperature ^5 polynomial coefficient + + Gyro rate offset temperature ^0 polynomial coefficient - Z axis modules/sensors - - Barometer offset temperature ^4 polynomial coefficient + + Gyro scale factor - X axis modules/sensors - - Barometer offset temperature ^3 polynomial coefficient + + Gyro scale factor - Y axis modules/sensors - - Barometer offset temperature ^2 polynomial coefficient + + Gyro scale factor - Z axis modules/sensors - - Barometer offset temperature ^1 polynomial coefficients + + Gyro calibration reference temperature modules/sensors - - Barometer offset temperature ^0 polynomial coefficient + + Gyro calibration minimum temperature modules/sensors - - Barometer scale factor - X axis + + Gyro calibration maximum temperature modules/sensors - - Barometer calibration reference temperature + + ID of Gyro that the calibration is for modules/sensors - - Barometer calibration minimum temperature + + Gyro rate offset temperature ^3 polynomial coefficient - X axis modules/sensors - - Barometer calibration maximum temperature + + Gyro rate offset temperature ^3 polynomial coefficient - Y axis modules/sensors - - ID of Barometer that the calibration is for + + Gyro rate offset temperature ^3 polynomial coefficient - Z axis modules/sensors - - Barometer offset temperature ^5 polynomial coefficient + + Gyro rate offset temperature ^2 polynomial coefficient - X axis modules/sensors - - Barometer offset temperature ^4 polynomial coefficient + + Gyro rate offset temperature ^2 polynomial coefficient - Y axis modules/sensors - - Barometer offset temperature ^3 polynomial coefficient + + Gyro rate offset temperature ^2 polynomial coefficient - Z axis modules/sensors - - Barometer offset temperature ^2 polynomial coefficient + + Gyro rate offset temperature ^1 polynomial coefficient - X axis modules/sensors - - Barometer offset temperature ^1 polynomial coefficients + + Gyro rate offset temperature ^1 polynomial coefficient - Y axis modules/sensors - - Barometer offset temperature ^0 polynomial coefficient + + Gyro rate offset temperature ^1 polynomial coefficient - Z axis modules/sensors - - Barometer scale factor - X axis + + Gyro rate offset temperature ^0 polynomial coefficient - X axis modules/sensors - - Barometer calibration reference temperature + + Gyro rate offset temperature ^0 polynomial coefficient - Y axis modules/sensors - - Barometer calibration minimum temperature + + Gyro rate offset temperature ^0 polynomial coefficient - Z axis modules/sensors - - Barometer calibration maximum temperature + + Gyro scale factor - X axis modules/sensors - - Set to 1 to enable thermal compensation for rate gyro sensors. Set to 0 to disable - 0 - 1 + + Gyro scale factor - Y axis modules/sensors - + + Gyro scale factor - Z axis + modules/sensors + + + Gyro calibration reference temperature + modules/sensors + + + Gyro calibration minimum temperature + modules/sensors + + + Gyro calibration maximum temperature + modules/sensors + + ID of Gyro that the calibration is for modules/sensors - + Gyro rate offset temperature ^3 polynomial coefficient - X axis modules/sensors - + Gyro rate offset temperature ^3 polynomial coefficient - Y axis modules/sensors - + Gyro rate offset temperature ^3 polynomial coefficient - Z axis modules/sensors - + Gyro rate offset temperature ^2 polynomial coefficient - X axis modules/sensors - + Gyro rate offset temperature ^2 polynomial coefficient - Y axis modules/sensors - + Gyro rate offset temperature ^2 polynomial coefficient - Z axis modules/sensors - + Gyro rate offset temperature ^1 polynomial coefficient - X axis modules/sensors - + Gyro rate offset temperature ^1 polynomial coefficient - Y axis modules/sensors - + Gyro rate offset temperature ^1 polynomial coefficient - Z axis modules/sensors - + Gyro rate offset temperature ^0 polynomial coefficient - X axis modules/sensors - + Gyro rate offset temperature ^0 polynomial coefficient - Y axis modules/sensors - + Gyro rate offset temperature ^0 polynomial coefficient - Z axis modules/sensors - + Gyro scale factor - X axis modules/sensors - + Gyro scale factor - Y axis modules/sensors - + Gyro scale factor - Z axis modules/sensors - + Gyro calibration reference temperature modules/sensors - + Gyro calibration minimum temperature modules/sensors - + Gyro calibration maximum temperature modules/sensors - - ID of Gyro that the calibration is for - modules/sensors - - - Gyro rate offset temperature ^3 polynomial coefficient - X axis - modules/sensors - - - Gyro rate offset temperature ^3 polynomial coefficient - Y axis - modules/sensors - - - Gyro rate offset temperature ^3 polynomial coefficient - Z axis - modules/sensors - - - Gyro rate offset temperature ^2 polynomial coefficient - X axis + + Set to 1 to enable thermal compensation for barometric pressure sensors. Set to 0 to disable + 0 + 1 modules/sensors - - Gyro rate offset temperature ^2 polynomial coefficient - Y axis + + ID of Barometer that the calibration is for modules/sensors - - Gyro rate offset temperature ^2 polynomial coefficient - Z axis + + Barometer offset temperature ^5 polynomial coefficient modules/sensors - - Gyro rate offset temperature ^1 polynomial coefficient - X axis + + Barometer offset temperature ^4 polynomial coefficient modules/sensors - - Gyro rate offset temperature ^1 polynomial coefficient - Y axis + + Barometer offset temperature ^3 polynomial coefficient modules/sensors - - Gyro rate offset temperature ^1 polynomial coefficient - Z axis + + Barometer offset temperature ^2 polynomial coefficient modules/sensors - - Gyro rate offset temperature ^0 polynomial coefficient - X axis + + Barometer offset temperature ^1 polynomial coefficients modules/sensors - - Gyro rate offset temperature ^0 polynomial coefficient - Y axis + + Barometer offset temperature ^0 polynomial coefficient modules/sensors - - Gyro rate offset temperature ^0 polynomial coefficient - Z axis + + Barometer scale factor - X axis modules/sensors - - Gyro scale factor - X axis + + Barometer calibration reference temperature modules/sensors - - Gyro scale factor - Y axis + + Barometer calibration minimum temperature modules/sensors - - Gyro scale factor - Z axis + + Barometer calibration maximum temperature modules/sensors - - Gyro calibration reference temperature + + ID of Barometer that the calibration is for modules/sensors - - Gyro calibration minimum temperature + + Barometer offset temperature ^5 polynomial coefficient modules/sensors - - Gyro calibration maximum temperature + + Barometer offset temperature ^4 polynomial coefficient modules/sensors - - ID of Gyro that the calibration is for + + Barometer offset temperature ^3 polynomial coefficient modules/sensors - - Gyro rate offset temperature ^3 polynomial coefficient - X axis + + Barometer offset temperature ^2 polynomial coefficient modules/sensors - - Gyro rate offset temperature ^3 polynomial coefficient - Y axis + + Barometer offset temperature ^1 polynomial coefficients modules/sensors - - Gyro rate offset temperature ^3 polynomial coefficient - Z axis + + Barometer offset temperature ^0 polynomial coefficient modules/sensors - - Gyro rate offset temperature ^2 polynomial coefficient - X axis + + Barometer scale factor - X axis modules/sensors - - Gyro rate offset temperature ^2 polynomial coefficient - Y axis + + Barometer calibration reference temperature modules/sensors - - Gyro rate offset temperature ^2 polynomial coefficient - Z axis + + Barometer calibration minimum temperature modules/sensors - - Gyro rate offset temperature ^1 polynomial coefficient - X axis + + Barometer calibration maximum temperature modules/sensors - - Gyro rate offset temperature ^1 polynomial coefficient - Y axis + + ID of Barometer that the calibration is for modules/sensors - - Gyro rate offset temperature ^1 polynomial coefficient - Z axis + + Barometer offset temperature ^5 polynomial coefficient modules/sensors - - Gyro rate offset temperature ^0 polynomial coefficient - X axis + + Barometer offset temperature ^4 polynomial coefficient modules/sensors - - Gyro rate offset temperature ^0 polynomial coefficient - Y axis + + Barometer offset temperature ^3 polynomial coefficient modules/sensors - - Gyro rate offset temperature ^0 polynomial coefficient - Z axis + + Barometer offset temperature ^2 polynomial coefficient modules/sensors - - Gyro scale factor - X axis + + Barometer offset temperature ^1 polynomial coefficients modules/sensors - - Gyro scale factor - Y axis + + Barometer offset temperature ^0 polynomial coefficient modules/sensors - - Gyro scale factor - Z axis + + Barometer scale factor - X axis modules/sensors - - Gyro calibration reference temperature + + Barometer calibration reference temperature modules/sensors - - Gyro calibration minimum temperature + + Barometer calibration minimum temperature modules/sensors - - Gyro calibration maximum temperature + + Barometer calibration maximum temperature modules/sensors + + Run the FMU as a task to reduce latency + If true, the FMU will run in a separate task instead of on the work queue. Set this if low latency is required, for example for racing. This is a trade-off between RAM usage and latency: running as a task, it requires a separate stack and directly polls on the control topics, whereas running on the work queue, it runs at a fixed update rate. + + true + drivers/px4fmu + + + Set usage of IO board + Can be used to use a standard startup script but with a FMU only set-up. Set to 0 to force the FMU only set-up. + 0 + 1 + + true + drivers/px4io + RGB Led brightness limit Set to 0 to disable, 1 for minimum brightness up to 15 (max) @@ -8068,22 +8628,6 @@ DEPRECATED, only used on V1 hardware true modules/systemlib - - Set usage of IO board - Can be used to use a standard startup script but with a FMU only set-up. Set to 0 to force the FMU only set-up. - 0 - 1 - - true - modules/systemlib - - - Run the FMU as a task to reduce latency - If true, the FMU will run in a separate task instead of on the work queue. Set this if low latency is required, for example for racing. This is a trade-off between RAM usage and latency: running as a task, it requires a separate stack and directly polls on the control topics, whereas running on the work queue, it runs at a fixed update rate. - - true - modules/systemlib - Set restart type Set by px4io to indicate type of restart @@ -8302,29 +8846,6 @@ DEPRECATED, only used on V1 hardware - - Target throttle value for pusher/puller motor during the transition to fw mode - 0.0 - 1.0 - 3 - 0.01 - modules/vtol_att_control - - - Maximum allowed down-pitch the controller is able to demand. This prevents large, negative -lift values being created when facing strong winds. The vehicle will use the pusher motor -to accelerate forward if necessary - 0.0 - 45.0 - modules/vtol_att_control - - - Fixed wing thrust scale for hover forward flight - Scale applied to fixed wing thrust being used as source for forward acceleration in multirotor mode. This technique can be used to avoid the plane having to pitch down a lot in order to move forward. Setting this value to 0 (default) will disable this strategy. - 0.0 - 2.0 - modules/vtol_att_control - Position of tilt servo in mc mode 0.0 @@ -8512,6 +9033,16 @@ to accelerate forward if necessary 1 modules/vtol_att_control + + Approximate deceleration during back transition + The approximate deceleration during a back transition in m/s/s Used to calculate back transition distance in mission mode. A lower value will make the VTOL transition further from the destination waypoint. + 0.00 + 20.00 + m/s/s + 2 + 1 + modules/vtol_att_control + Transition blending airspeed Airspeed at which we can start blending both fw and mc controls. Set to 0 to disable. @@ -8572,7 +9103,7 @@ to accelerate forward if necessary modules/vtol_att_control - QuadChute Max Pith + QuadChute Max Pitch Maximum pitch angle before QuadChute engages Above this the vehicle will transition back to MC mode and enter failsafe RTL 0 180 @@ -8593,170 +9124,89 @@ to accelerate forward if necessary seconds modules/vtol_att_control - - - - Failsafe channel mapping - The RC mapping index indicates which channel is used for failsafe If 0, whichever channel is mapped to throttle is used otherwise the value indicates the specific rc channel to use - 0 - 18 - modules/sensors - - Channel 11 - Channel 10 - Channel 13 - Channel 12 - Channel 15 - Channel 14 - Channel 17 - Channel 16 - Channel 18 - Channel 1 - Unassigned - Channel 3 - Channel 2 - Channel 5 - Channel 4 - Channel 7 - Channel 6 - Channel 9 - Channel 8 - - - - COM_RC_STICK_OV - modules/commander + + Target throttle value for pusher/puller motor during the transition to fw mode + 0.0 + 1.0 + 3 + 0.01 + modules/vtol_att_control - - First flightmode slot (1000-1160) - If the main switch channel is in this range the selected flight mode will be applied. - modules/commander - - Land - Takeoff - Follow Me - Altitude - Manual - Mission - Position - Unassigned - Hold - Offboard - Acro - Rattitude - Return - Stabilized - + + Maximum allowed down-pitch the controller is able to demand. This prevents large, negative +lift values being created when facing strong winds. The vehicle will use the pusher motor +to accelerate forward if necessary + 0.0 + 45.0 + modules/vtol_att_control - - Second flightmode slot (1160-1320) - If the main switch channel is in this range the selected flight mode will be applied. - modules/commander - - Land - Takeoff - Follow Me - Altitude - Manual - Mission - Position - Unassigned - Hold - Offboard - Acro - Rattitude - Return - Stabilized - + + Fixed wing thrust scale for hover forward flight + Scale applied to fixed wing thrust being used as source for forward acceleration in multirotor mode. This technique can be used to avoid the plane having to pitch down a lot in order to move forward. Setting this value to 0 (default) will disable this strategy. + 0.0 + 2.0 + modules/vtol_att_control - - Third flightmode slot (1320-1480) - If the main switch channel is in this range the selected flight mode will be applied. - modules/commander - - Land - Takeoff - Follow Me - Altitude - Manual - Mission - Position - Unassigned - Hold - Offboard - Acro - Rattitude - Return - Stabilized - + + Back transition MC motor ramp up time + This sets the duration during wich the MC motors ramp up to the commanded thrust during the back transition stage. + 0.0 + 20.0 + s + modules/vtol_att_control - - Fourth flightmode slot (1480-1640) - If the main switch channel is in this range the selected flight mode will be applied. - modules/commander - - Land - Takeoff - Follow Me - Altitude - Manual - Mission - Position - Unassigned - Hold - Offboard - Acro - Rattitude - Return - Stabilized - + + Output on airbrakes channel during back transition +Used for airbrakes or with ESCs that have reverse thrust enabled on a seperate channel +Airbrakes need to be enables for your selected model/mixer + 0 + 1 + 2 + 0.01 + modules/vtol_att_control - - Fifth flightmode slot (1640-1800) - If the main switch channel is in this range the selected flight mode will be applied. - modules/commander - - Land - Takeoff - Follow Me - Altitude - Manual - Mission - Position - Unassigned - Hold - Offboard - Acro - Rattitude - Return - Stabilized - + + Delay in seconds before applying back transition throttle +Set this to a value greater than 0 to give the motor time to spin down + unit s + 0 + 10 + 2 + 1 + modules/vtol_att_control - - Sixth flightmode slot (1800-2000) - If the main switch channel is in this range the selected flight mode will be applied. - modules/commander - - Land - Takeoff - Follow Me - Altitude - Manual - Mission - Position - Unassigned - Hold - Offboard - Acro - Rattitude - Return - Stabilized - + + Thottle output during back transition +For ESCs and mixers that support reverse thrust on low PWM values set this to a negative value to apply active breaking +For ESCs that support thrust reversal with a control channel please set VT_B_REV_OUT and set this to a positive value to apply active breaking + -1 + 1 + 2 + 0.01 + modules/vtol_att_control + + RV_YAW_P examples/rover_steering_control + + SEG_TH2V_P + examples/segway + + + SEG_TH2V_I + examples/segway + + + SEG_TH2V_I_MAX + examples/segway + + + SEG_Q2V + examples/segway + EXFW_HDNG_P examples/fixedwing_control diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml index b1f77633e2b720ae6e1ec8cf37ed43e42d5b3948..3c87dc13aa576040dca443faee06d60d178dd8a3 100644 --- a/src/FlightDisplay/FlightDisplayView.qml +++ b/src/FlightDisplay/FlightDisplayView.qml @@ -49,7 +49,7 @@ QGCView { property bool _isPipVisible: QGroundControl.videoManager.hasVideo ? QGroundControl.loadBoolGlobalSetting(_PIPVisibleKey, true) : false property real _savedZoomLevel: 0 property real _margins: ScreenTools.defaultFontPixelWidth / 2 - property real _pipSize: mainWindow.width * 0.2 + property real _pipSize: flightView.width * 0.2 property alias _guidedController: guidedActionsController property alias _altitudeSlider: altitudeSlider @@ -287,6 +287,9 @@ QGCView { onHideIt: { setPipVisibility(!state) } + onNewWidth: { + _pipSize = newWidth + } } Row { diff --git a/src/FlightDisplay/FlightDisplayViewWidgets.qml b/src/FlightDisplay/FlightDisplayViewWidgets.qml index fcd04dfdf1306bc9b541d13466e046123384f378..4caab475fca7838b6de1b5eaea18c8212f650e5b 100644 --- a/src/FlightDisplay/FlightDisplayViewWidgets.qml +++ b/src/FlightDisplay/FlightDisplayViewWidgets.qml @@ -42,8 +42,7 @@ Item { if(ScreenTools.isMobile) { return ScreenTools.isTinyScreen ? mainWindow.width * 0.2 : mainWindow.width * 0.15 } - var w = mainWindow.width * 0.15 - return Math.min(w, 200) + return ScreenTools.defaultFontPixelWidth * 30 } function _setInstrumentWidget() { diff --git a/src/FlightMap/Images/pipResize.svg b/src/FlightMap/Images/pipResize.svg new file mode 100644 index 0000000000000000000000000000000000000000..94b3284faa4d890d87b474fb0de215217762ca9a --- /dev/null +++ b/src/FlightMap/Images/pipResize.svg @@ -0,0 +1,373 @@ + + + + + + image/svg+xml + + + + + + + + diff --git a/src/Joystick/Joystick.cc b/src/Joystick/Joystick.cc index b2093d4f4cd2e0ca1b1dd4e6ef5746779e86cf94..a7d4f734fb31216c6fd64ab0ca8b2c8e1c066166 100644 --- a/src/Joystick/Joystick.cc +++ b/src/Joystick/Joystick.cc @@ -75,6 +75,8 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC _rgButtonValues[i] = false; } + _updateTXModeSettingsKey(_multiVehicleManager->activeVehicle()); + _loadSettings(); connect(_multiVehicleManager, &MultiVehicleManager::activeVehicleChanged, this, &Joystick::_activeVehicleChanged); @@ -119,7 +121,7 @@ void Joystick::_setDefaultCalibration(void) { _saveSettings(); } -void Joystick::_activeVehicleChanged(Vehicle *activeVehicle) +void Joystick::_updateTXModeSettingsKey(Vehicle* activeVehicle) { if(activeVehicle) { if(activeVehicle->fixedWing()) { @@ -137,7 +139,16 @@ void Joystick::_activeVehicleChanged(Vehicle *activeVehicle) qWarning() << "No valid joystick TXmode settings key for selected vehicle"; return; } + } else { + _txModeSettingsKey = NULL; + } +} +void Joystick::_activeVehicleChanged(Vehicle* activeVehicle) +{ + _updateTXModeSettingsKey(activeVehicle); + + if(activeVehicle) { QSettings settings; settings.beginGroup(_settingsGroup); int mode = settings.value(_txModeSettingsKey, activeVehicle->firmwarePlugin()->defaultJoystickTXMode()).toInt(); @@ -152,8 +163,10 @@ void Joystick::_loadSettings(void) settings.beginGroup(_settingsGroup); - if(_txModeSettingsKey) - _transmitterMode = settings.value(_txModeSettingsKey, 2).toInt(); + Vehicle* activeVehicle = _multiVehicleManager->activeVehicle(); + + if(_txModeSettingsKey && activeVehicle) + _transmitterMode = settings.value(_txModeSettingsKey, activeVehicle->firmwarePlugin()->defaultJoystickTXMode()).toInt(); settings.beginGroup(_name); diff --git a/src/Joystick/Joystick.h b/src/Joystick/Joystick.h index 89717f715280b7ea5959ade2ff744a6581a21df2..d6f15ed8bf7fd300c9eba04c23f238125a481544 100644 --- a/src/Joystick/Joystick.h +++ b/src/Joystick/Joystick.h @@ -181,6 +181,7 @@ private: virtual int _getAxis(int i) = 0; virtual uint8_t _getHat(int hat,int i) = 0; + void _updateTXModeSettingsKey(Vehicle* activeVehicle); int _mapFunctionMode(int mode, int function); void _remapAxes(int currentMode, int newMode, int (&newMapping)[maxFunction]); diff --git a/src/Joystick/JoystickSDL.cc b/src/Joystick/JoystickSDL.cc index 9e96eebfe5c82adba426633d156bd8614bb5604d..d61238be5924a103c9c27ce303e773f677941442 100644 --- a/src/Joystick/JoystickSDL.cc +++ b/src/Joystick/JoystickSDL.cc @@ -65,7 +65,7 @@ QMap JoystickSDL::discover(MultiVehicleManager* _multiVehicl qCDebug(JoystickLog) << "\t" << name << "axes:" << axisCount << "buttons:" << buttonCount << "hats:" << hatCount << "isGC:" << isGameController; - // Check for joysticks with duplicate names and differentiate the keys when neccessary. + // Check for joysticks with duplicate names and differentiate the keys when necessary. // This is required when using an Xbox 360 wireless receiver that always identifies as // 4 individual joysticks, regardless of how many joysticks are actually connected to the // receiver. Using GUID does not help, all of these devices present the same GUID. diff --git a/src/MissionManager/ComplexMissionItem.h b/src/MissionManager/ComplexMissionItem.h index caf83426a0628128618fb58a94fd640e6690aeca..10ae81c92314137999302b2ef05c67095a5d5336 100644 --- a/src/MissionManager/ComplexMissionItem.h +++ b/src/MissionManager/ComplexMissionItem.h @@ -24,6 +24,7 @@ public: Q_PROPERTY(double complexDistance READ complexDistance NOTIFY complexDistanceChanged) /// @return The distance covered the complex mission item in meters. + /// Signals complexDistanceChanged virtual double complexDistance(void) const = 0; /// @return Amount of additional time delay in seconds needed to fly the complex item @@ -39,6 +40,7 @@ public: /// Get the point of complex mission item furthest away from a coordinate /// @param other QGeoCoordinate to which distance is calculated /// @return the greatest distance from any point of the complex item to some coordinate + /// Signals greatestDistanceToChanged virtual double greatestDistanceTo(const QGeoCoordinate &other) const = 0; /// This mission item attribute specifies the type of the complex item. @@ -46,6 +48,7 @@ public: signals: void complexDistanceChanged (double complexDistance); + void greatestDistanceToChanged (void); void additionalTimeDelayChanged (double additionalTimeDelay); }; diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index c5b8c4cf7f0a9ea756ecf76efdf5d78213f6c312..affa0fa78df13b2ffc9d7375482a5905ac04e592 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -18,6 +18,7 @@ #include "SimpleMissionItem.h" #include "SurveyMissionItem.h" #include "FixedWingLandingComplexItem.h" +#include "StructureScanComplexItem.h" #include "JsonHelper.h" #include "ParameterManager.h" #include "QGroundControlQmlGlobal.h" @@ -60,6 +61,7 @@ MissionController::MissionController(PlanMasterController* masterController, QOb , _itemsRequested(false) , _surveyMissionItemName(tr("Survey")) , _fwLandingMissionItemName(tr("Fixed Wing Landing")) + , _structureScanMissionItemName(tr("Structure Scan")) , _appSettings(qgcApp()->toolbox()->settingsManager()->appSettings()) , _progressPct(0) { @@ -283,11 +285,11 @@ void MissionController::convertToKMLDocument(QDomDocument& document) qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command()); if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) { - coord = QString::number(item->param6()) \ + coord = QString::number(item->param6(),'f',7) \ + "," \ - + QString::number(item->param5()) \ + + QString::number(item->param5(),'f',7) \ + "," \ - + QString::number(item->param7() + altitude); + + QString::number(item->param7() + altitude,'f',2); coords.append(coord); } } @@ -379,6 +381,8 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate } } else if (itemName == _fwLandingMissionItemName) { newItem = new FixedWingLandingComplexItem(_controllerVehicle, _visualItems); + } else if (itemName == _structureScanMissionItemName) { + newItem = new StructureScanComplexItem(_controllerVehicle, _visualItems); } else { qWarning() << "Internal error: Unknown complex item:" << itemName; return sequenceNumber; @@ -1475,6 +1479,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem) ComplexMissionItem* complexItem = qobject_cast(visualItem); if (complexItem) { connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcMissionFlightStatus); + connect(complexItem, &ComplexMissionItem::greatestDistanceToChanged, this, &MissionController::_recalcMissionFlightStatus); connect(complexItem, &ComplexMissionItem::additionalTimeDelayChanged, this, &MissionController::_recalcMissionFlightStatus); } else { qWarning() << "ComplexMissionItem not found"; @@ -1769,6 +1774,9 @@ QStringList MissionController::complexMissionItemNames(void) const if (_controllerVehicle->fixedWing()) { complexItems.append(_fwLandingMissionItemName); } + if (_controllerVehicle->multiRotor() || _controllerVehicle->vtol()) { + complexItems.append(_structureScanMissionItemName); + } return complexItems; } diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index abc553c3781869a44ec18e64c164ce84ce9aefa2..9889466410154964b19fe3b16d38787083f8acae 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -231,6 +231,7 @@ private: MissionFlightStatus_t _missionFlightStatus; QString _surveyMissionItemName; QString _fwLandingMissionItemName; + QString _structureScanMissionItemName; AppSettings* _appSettings; double _progressPct; diff --git a/src/MissionManager/MissionItemTest.cc b/src/MissionManager/MissionItemTest.cc index fd4ab52f65faf3bfead644157a578f046cd9d2fb..1480af7ade69dbcbaa502d373d12cd6fc60d7d9f 100644 --- a/src/MissionManager/MissionItemTest.cc +++ b/src/MissionManager/MissionItemTest.cc @@ -297,7 +297,7 @@ void MissionItemTest::_testLoadFromJsonV1(void) QString errorString; QJsonObject jsonObject = _createV1Json(); - // V1 format has param 1-4 in seperate items instead of in params array + // V1 format has param 1-4 in separate items instead of in params array QStringList removeKeys; removeKeys << MissionItem::_jsonParam1Key << MissionItem::_jsonParam2Key << MissionItem::_jsonParam3Key << MissionItem::_jsonParam4Key; diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc index c61eb2c2ab2620eb204158a35ceff6049073f44b..ab54a7da11981d3f0d41bf89c6ebe1e1c2722bbd 100644 --- a/src/MissionManager/MissionManager.cc +++ b/src/MissionManager/MissionManager.cc @@ -40,8 +40,6 @@ void MissionManager::writeArduPilotGuidedMissionItem(const QGeoCoordinate& gotoC _transactionInProgress = TransactionWrite; - _connectToMavlink(); - mavlink_message_t messageOut; mavlink_mission_item_t missionItem; diff --git a/src/MissionManager/PlanManager.cc b/src/MissionManager/PlanManager.cc index b132c5228e97d0e3eb89fac46901374177edec89..4cbe7b2a02c60cd2872051fefba3177c779cb07f 100644 --- a/src/MissionManager/PlanManager.cc +++ b/src/MissionManager/PlanManager.cc @@ -38,6 +38,7 @@ PlanManager::PlanManager(Vehicle* vehicle, MAV_MISSION_TYPE planType) _ackTimeoutTimer->setInterval(_ackTimeoutMilliseconds); connect(_ackTimeoutTimer, &QTimer::timeout, this, &PlanManager::_ackTimeout); + connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &PlanManager::_mavlinkMessageReceived); } PlanManager::~PlanManager() @@ -62,7 +63,6 @@ void PlanManager::_writeMissionItemsWorker(void) _transactionInProgress = TransactionWrite; _retryCount = 0; emit inProgressChanged(true); - _connectToMavlink(); _writeMissionCount(); } @@ -139,7 +139,6 @@ void PlanManager::loadFromVehicle(void) _retryCount = 0; _transactionInProgress = TransactionRead; emit inProgressChanged(true); - _connectToMavlink(); _requestList(); } @@ -803,7 +802,6 @@ QString PlanManager::_missionResultToString(MAV_MISSION_RESULT result) void PlanManager::_finishTransaction(bool success) { emit progressPct(1); - _disconnectFromMavlink(); _itemIndicesToRead.clear(); _itemIndicesToWrite.clear(); @@ -892,7 +890,6 @@ void PlanManager::_removeAllWorker(void) emit progressPct(0); - _connectToMavlink(); _dedicatedLink = _vehicle->priorityLink(); mavlink_msg_mission_clear_all_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), @@ -944,16 +941,6 @@ void PlanManager::_clearAndDeleteWriteMissionItems(void) _writeMissionItems.clear(); } -void PlanManager::_connectToMavlink(void) -{ - connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &PlanManager::_mavlinkMessageReceived); -} - -void PlanManager::_disconnectFromMavlink(void) -{ - disconnect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &PlanManager::_mavlinkMessageReceived); -} - QString PlanManager::_planTypeString(void) { switch (_planType) { diff --git a/src/MissionManager/PlanManager.h b/src/MissionManager/PlanManager.h index 43f696c14ed9f7f6a8d5834c5cb311070a89e747..8633588e92d6649503cdb39b913cb4b9b0dc0a54 100644 --- a/src/MissionManager/PlanManager.h +++ b/src/MissionManager/PlanManager.h @@ -126,8 +126,6 @@ protected: void _clearAndDeleteWriteMissionItems(void); QString _lastMissionReqestString(MAV_MISSION_RESULT result); void _removeAllWorker(void); - void _connectToMavlink(void); - void _disconnectFromMavlink(void); QString _planTypeString(void); protected: diff --git a/src/MissionManager/QGCMapPolygon.cc b/src/MissionManager/QGCMapPolygon.cc index aef9372ab181be432975d30b04e182f8e396caed..5beefa9b128b3a70fc73d005780a42aadfb51b16 100644 --- a/src/MissionManager/QGCMapPolygon.cc +++ b/src/MissionManager/QGCMapPolygon.cc @@ -354,3 +354,13 @@ void QGCMapPolygon::setInteractive(bool interactive) emit interactiveChanged(interactive); } } + +QGeoCoordinate QGCMapPolygon::vertexCoordinate(int vertex) const +{ + if (vertex >= 0 && vertex < _polygonPath.count()) { + return _polygonPath[vertex].value(); + } else { + qWarning() << "QGCMapPolygon::vertexCoordinate bad vertex requested"; + return QGeoCoordinate(); + } +} diff --git a/src/MissionManager/QGCMapPolygon.h b/src/MissionManager/QGCMapPolygon.h index b2990dbe3f11ec4d59754871860db04f1875ee25..e9abaa2eacb064e123783a4af3546e87ad09b2b4 100644 --- a/src/MissionManager/QGCMapPolygon.h +++ b/src/MissionManager/QGCMapPolygon.h @@ -55,6 +55,9 @@ public: /// Returns the path in a list of QGeoCoordinate's format QList coordinateList(void) const; + /// Returns the QGeoCoordinate for the vertex specified + QGeoCoordinate vertexCoordinate(int vertex) const; + /// Saves the polygon to the json object. /// @param json Json object to save to void saveToJson(QJsonObject& json); diff --git a/src/MissionManager/StructureScan.SettingsGroup.json b/src/MissionManager/StructureScan.SettingsGroup.json new file mode 100644 index 0000000000000000000000000000000000000000..3a0fbbcd158abe88b97ec74b108d99d50d144c94 --- /dev/null +++ b/src/MissionManager/StructureScan.SettingsGroup.json @@ -0,0 +1,35 @@ +[ +{ + "name": "Altitude", + "shortDescription": "Altitude for the bottom layer of the structure scan.", + "type": "double", + "units": "m", + "decimalPlaces": 1, + "defaultValue": 50 +}, +{ + "name": "Layers", + "shortDescription": "Number of scan layers.", + "type": "uint32", + "min": 1, + "defaultValue": 1 +}, +{ + "name": "Layer distance", + "shortDescription": "Distance between each layer.", + "type": "double", + "decimalPlaces": 2, + "min": 0, + "units": "m", + "defaultValue": 25 +}, +{ + "name": "Trigger distance", + "shortDescription": "Distance between each triggering of the camera. 0 specifies not camera trigger.", + "type": "double", + "decimalPlaces": 2, + "min": 0, + "units": "m", + "defaultValue": 25 +} +] diff --git a/src/MissionManager/StructureScanComplexItem.cc b/src/MissionManager/StructureScanComplexItem.cc new file mode 100644 index 0000000000000000000000000000000000000000..5c0257e375aaada626180baebd231b618847709d --- /dev/null +++ b/src/MissionManager/StructureScanComplexItem.cc @@ -0,0 +1,519 @@ +/**************************************************************************** + * + * (c) 2009-2016 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "StructureScanComplexItem.h" +#include "JsonHelper.h" +#include "MissionController.h" +#include "QGCGeo.h" +#include "QGroundControlQmlGlobal.h" +#include "QGCQGeoCoordinate.h" +#include "SettingsManager.h" +#include "AppSettings.h" +#include "QGCQGeoCoordinate.h" + +#include + +QGC_LOGGING_CATEGORY(StructureScanComplexItemLog, "StructureScanComplexItemLog") + +const char* StructureScanComplexItem::jsonComplexItemTypeValue = "StructureScan-WIP"; + +const char* StructureScanComplexItem::_jsonGridObjectKey = "grid"; +const char* StructureScanComplexItem::_jsonGridAltitudeKey = "altitude"; +const char* StructureScanComplexItem::_jsonGridAltitudeRelativeKey = "relativeAltitude"; +const char* StructureScanComplexItem::_jsonGridAngleKey = "angle"; +const char* StructureScanComplexItem::_jsonGridSpacingKey = "spacing"; +const char* StructureScanComplexItem::_jsonGridEntryLocationKey = "entryLocation"; +const char* StructureScanComplexItem::_jsonTurnaroundDistKey = "turnAroundDistance"; +const char* StructureScanComplexItem::_jsonCameraTriggerDistanceKey = "cameraTriggerDistance"; +const char* StructureScanComplexItem::_jsonCameraTriggerInTurnaroundKey = "cameraTriggerInTurnaround"; +const char* StructureScanComplexItem::_jsonHoverAndCaptureKey = "hoverAndCapture"; +const char* StructureScanComplexItem::_jsonGroundResolutionKey = "groundResolution"; +const char* StructureScanComplexItem::_jsonFrontalOverlapKey = "imageFrontalOverlap"; +const char* StructureScanComplexItem::_jsonSideOverlapKey = "imageSideOverlap"; +const char* StructureScanComplexItem::_jsonCameraSensorWidthKey = "sensorWidth"; +const char* StructureScanComplexItem::_jsonCameraSensorHeightKey = "sensorHeight"; +const char* StructureScanComplexItem::_jsonCameraResolutionWidthKey = "resolutionWidth"; +const char* StructureScanComplexItem::_jsonCameraResolutionHeightKey = "resolutionHeight"; +const char* StructureScanComplexItem::_jsonCameraFocalLengthKey = "focalLength"; +const char* StructureScanComplexItem::_jsonCameraMinTriggerIntervalKey = "minTriggerInterval"; +const char* StructureScanComplexItem::_jsonCameraObjectKey = "camera"; +const char* StructureScanComplexItem::_jsonCameraNameKey = "name"; +const char* StructureScanComplexItem::_jsonManualGridKey = "manualGrid"; +const char* StructureScanComplexItem::_jsonCameraOrientationLandscapeKey = "orientationLandscape"; +const char* StructureScanComplexItem::_jsonFixedValueIsAltitudeKey = "fixedValueIsAltitude"; +const char* StructureScanComplexItem::_jsonRefly90DegreesKey = "refly90Degrees"; + +const char* StructureScanComplexItem::_altitudeFactName = "Altitude"; +const char* StructureScanComplexItem::_layersFactName = "Layers"; +const char* StructureScanComplexItem::_layerDistanceFactName = "Layer distance"; +const char* StructureScanComplexItem::_cameraTriggerDistanceFactName = "Trigger distance"; + +QMap StructureScanComplexItem::_metaDataMap; + +StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, QObject* parent) + : ComplexMissionItem (vehicle, parent) + , _sequenceNumber (0) + , _dirty (false) + , _altitudeRelative (true) + , _entryVertex (0) + , _ignoreRecalc (false) + , _scanDistance (0.0) + , _cameraShots (0) + , _cameraMinTriggerInterval (0) + , _altitudeFact (0, _altitudeFactName, FactMetaData::valueTypeDouble) + , _layersFact (0, _layersFactName, FactMetaData::valueTypeUint32) + , _layerDistanceFact (0, _layerDistanceFactName, FactMetaData::valueTypeDouble) + , _cameraTriggerDistanceFact(0, _cameraTriggerDistanceFactName, FactMetaData::valueTypeDouble) +{ + _editorQml = "qrc:/qml/StructureScanEditor.qml"; + + if (_metaDataMap.isEmpty()) { + _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/StructureScan.SettingsGroup.json"), this); + } + + _altitudeFact.setMetaData (_metaDataMap[_altitudeFactName]); + _layersFact.setMetaData (_metaDataMap[_layersFactName]); + _layerDistanceFact.setMetaData (_metaDataMap[_layerDistanceFactName]); + _cameraTriggerDistanceFact.setMetaData (_metaDataMap[_cameraTriggerDistanceFactName]); + + _altitudeFact.setRawValue (_altitudeFact.rawDefaultValue()); + _layersFact.setRawValue (_layersFact.rawDefaultValue()); + _layerDistanceFact.setRawValue (_layerDistanceFact.rawDefaultValue()); + _cameraTriggerDistanceFact.setRawValue (_cameraTriggerDistanceFact.rawDefaultValue()); + + _altitudeFact.setRawValue(qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue()); + + connect(&_altitudeFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty); + connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty); + connect(&_layerDistanceFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty); + connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &StructureScanComplexItem::_setDirty); + + connect(this, &StructureScanComplexItem::altitudeRelativeChanged, this, &StructureScanComplexItem::_setDirty); + connect(this, &StructureScanComplexItem::altitudeRelativeChanged, this, &StructureScanComplexItem::coordinateHasRelativeAltitudeChanged); + connect(this, &StructureScanComplexItem::altitudeRelativeChanged, this, &StructureScanComplexItem::exitCoordinateHasRelativeAltitudeChanged); + + connect(&_altitudeFact, &Fact::valueChanged, this, &StructureScanComplexItem::_updateCoordinateAltitudes); + + connect(&_mapPolygon, &QGCMapPolygon::dirtyChanged, this, &StructureScanComplexItem::_polygonDirtyChanged); + connect(&_mapPolygon, &QGCMapPolygon::countChanged, this, &StructureScanComplexItem::_polygonCountChanged); + connect(&_mapPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_polygonPathChanged); +} + +void StructureScanComplexItem::_setScanDistance(double scanDistance) +{ + if (!qFuzzyCompare(_scanDistance, scanDistance)) { + _scanDistance = scanDistance; + emit complexDistanceChanged(_scanDistance); + } +} + +void StructureScanComplexItem::_setCameraShots(int cameraShots) +{ + if (_cameraShots != cameraShots) { + _cameraShots = cameraShots; + emit cameraShotsChanged(this->cameraShots()); + } +} + +void StructureScanComplexItem::_clearInternal(void) +{ + setDirty(true); + + emit specifiesCoordinateChanged(); + emit lastSequenceNumberChanged(lastSequenceNumber()); +} + +void StructureScanComplexItem::_polygonCountChanged(int count) +{ + Q_UNUSED(count); + emit lastSequenceNumberChanged(lastSequenceNumber()); +} + +int StructureScanComplexItem::lastSequenceNumber(void) const +{ + return _sequenceNumber + + ((_mapPolygon.count() + 1) * _layersFact.rawValue().toInt()) + // 1 waypoint for each polygon vertex + 1 to go back to first polygon vertex + 1; // Gimbal yaw command +} + +void StructureScanComplexItem::setDirty(bool dirty) +{ + if (_dirty != dirty) { + _dirty = dirty; + emit dirtyChanged(_dirty); + } +} + +void StructureScanComplexItem::save(QJsonArray& missionItems) +{ + Q_UNUSED(missionItems); +#if 0 + QJsonObject saveObject; + + saveObject[JsonHelper::jsonVersionKey] = 3; + saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue; + saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue; + saveObject[_jsonManualGridKey] = _manualGridFact.rawValue().toBool(); + saveObject[_jsonFixedValueIsAltitudeKey] = _fixedValueIsAltitudeFact.rawValue().toBool(); + saveObject[_jsonHoverAndCaptureKey] = _hoverAndCaptureFact.rawValue().toBool(); + saveObject[_jsonRefly90DegreesKey] = _refly90Degrees; + saveObject[_jsonCameraTriggerDistanceKey] = _cameraTriggerDistanceFact.rawValue().toDouble(); + + QJsonObject gridObject; + gridObject[_jsonGridAltitudeKey] = _gridAltitudeFact.rawValue().toDouble(); + gridObject[_jsonGridAltitudeRelativeKey] = _gridAltitudeRelativeFact.rawValue().toBool(); + gridObject[_jsonGridAngleKey] = _gridAngleFact.rawValue().toDouble(); + gridObject[_jsonGridSpacingKey] = _gridSpacingFact.rawValue().toDouble(); + gridObject[_jsonGridEntryLocationKey] = _gridEntryLocationFact.rawValue().toDouble(); + gridObject[_jsonTurnaroundDistKey] = _turnaroundDistFact.rawValue().toDouble(); + + saveObject[_jsonGridObjectKey] = gridObject; + + if (!_manualGridFact.rawValue().toBool()) { + QJsonObject cameraObject; + cameraObject[_jsonCameraNameKey] = _cameraFact.rawValue().toString(); + cameraObject[_jsonCameraOrientationLandscapeKey] = _cameraOrientationLandscapeFact.rawValue().toBool(); + cameraObject[_jsonCameraSensorWidthKey] = _cameraSensorWidthFact.rawValue().toDouble(); + cameraObject[_jsonCameraSensorHeightKey] = _cameraSensorHeightFact.rawValue().toDouble(); + cameraObject[_jsonCameraResolutionWidthKey] = _cameraResolutionWidthFact.rawValue().toDouble(); + cameraObject[_jsonCameraResolutionHeightKey] = _cameraResolutionHeightFact.rawValue().toDouble(); + cameraObject[_jsonCameraFocalLengthKey] = _cameraFocalLengthFact.rawValue().toDouble(); + cameraObject[_jsonCameraMinTriggerIntervalKey] = _cameraMinTriggerInterval; + cameraObject[_jsonGroundResolutionKey] = _groundResolutionFact.rawValue().toDouble(); + cameraObject[_jsonFrontalOverlapKey] = _frontalOverlapFact.rawValue().toInt(); + cameraObject[_jsonSideOverlapKey] = _sideOverlapFact.rawValue().toInt(); + + saveObject[_jsonCameraObjectKey] = cameraObject; + } + + // Polygon shape + _mapPolygon.saveToJson(saveObject); + + missionItems.append(saveObject); +#endif +} + +void StructureScanComplexItem::setSequenceNumber(int sequenceNumber) +{ + if (_sequenceNumber != sequenceNumber) { + _sequenceNumber = sequenceNumber; + emit sequenceNumberChanged(sequenceNumber); + emit lastSequenceNumberChanged(lastSequenceNumber()); + } +} + +bool StructureScanComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString) +{ +#if 0 + QJsonObject v2Object = complexObject; + + // We need to pull version first to determine what validation/conversion needs to be performed. + QList versionKeyInfoList = { + { JsonHelper::jsonVersionKey, QJsonValue::Double, true }, + }; + if (!JsonHelper::validateKeys(v2Object, versionKeyInfoList, errorString)) { + return false; + } + + int version = v2Object[JsonHelper::jsonVersionKey].toInt(); + if (version != 2 && version != 3) { + errorString = tr("%1 does not support this version of survey items").arg(qgcApp()->applicationName()); + return false; + } + if (version == 2) { + // Convert to v3 + if (v2Object.contains(VisualMissionItem::jsonTypeKey) && v2Object[VisualMissionItem::jsonTypeKey].toString() == QStringLiteral("survey")) { + v2Object[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue; + v2Object[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue; + } + } + + QList mainKeyInfoList = { + { JsonHelper::jsonVersionKey, QJsonValue::Double, true }, + { VisualMissionItem::jsonTypeKey, QJsonValue::String, true }, + { ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true }, + { QGCMapPolygon::jsonPolygonKey, QJsonValue::Array, true }, + { _jsonGridObjectKey, QJsonValue::Object, true }, + { _jsonCameraObjectKey, QJsonValue::Object, false }, + { _jsonCameraTriggerDistanceKey, QJsonValue::Double, true }, + { _jsonManualGridKey, QJsonValue::Bool, true }, + { _jsonFixedValueIsAltitudeKey, QJsonValue::Bool, true }, + { _jsonHoverAndCaptureKey, QJsonValue::Bool, false }, + { _jsonRefly90DegreesKey, QJsonValue::Bool, false }, + }; + if (!JsonHelper::validateKeys(v2Object, mainKeyInfoList, errorString)) { + return false; + } + + QString itemType = v2Object[VisualMissionItem::jsonTypeKey].toString(); + QString complexType = v2Object[ComplexMissionItem::jsonComplexItemTypeKey].toString(); + if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) { + errorString = tr("%1 does not support loading this complex mission item type: %2:%3").arg(qgcApp()->applicationName()).arg(itemType).arg(complexType); + return false; + } + + _ignoreRecalc = true; + + _mapPolygon.clear(); + + setSequenceNumber(sequenceNumber); + + _manualGridFact.setRawValue (v2Object[_jsonManualGridKey].toBool(true)); + _fixedValueIsAltitudeFact.setRawValue (v2Object[_jsonFixedValueIsAltitudeKey].toBool(true)); + _gridAltitudeRelativeFact.setRawValue (v2Object[_jsonGridAltitudeRelativeKey].toBool(true)); + _hoverAndCaptureFact.setRawValue (v2Object[_jsonHoverAndCaptureKey].toBool(false)); + + _refly90Degrees = v2Object[_jsonRefly90DegreesKey].toBool(false); + + QList gridKeyInfoList = { + { _jsonGridAltitudeKey, QJsonValue::Double, true }, + { _jsonGridAltitudeRelativeKey, QJsonValue::Bool, true }, + { _jsonGridAngleKey, QJsonValue::Double, true }, + { _jsonGridSpacingKey, QJsonValue::Double, true }, + { _jsonGridEntryLocationKey, QJsonValue::Double, false }, + { _jsonTurnaroundDistKey, QJsonValue::Double, true }, + }; + QJsonObject gridObject = v2Object[_jsonGridObjectKey].toObject(); + if (!JsonHelper::validateKeys(gridObject, gridKeyInfoList, errorString)) { + return false; + } + _gridAltitudeFact.setRawValue (gridObject[_jsonGridAltitudeKey].toDouble()); + _gridAngleFact.setRawValue (gridObject[_jsonGridAngleKey].toDouble()); + _gridSpacingFact.setRawValue (gridObject[_jsonGridSpacingKey].toDouble()); + _turnaroundDistFact.setRawValue (gridObject[_jsonTurnaroundDistKey].toDouble()); + _cameraTriggerDistanceFact.setRawValue (v2Object[_jsonCameraTriggerDistanceKey].toDouble()); + if (gridObject.contains(_jsonGridEntryLocationKey)) { + _gridEntryLocationFact.setRawValue(gridObject[_jsonGridEntryLocationKey].toDouble()); + } else { + _gridEntryLocationFact.setRawValue(_gridEntryLocationFact.rawDefaultValue()); + } + + if (!_manualGridFact.rawValue().toBool()) { + if (!v2Object.contains(_jsonCameraObjectKey)) { + errorString = tr("%1 but %2 object is missing").arg("manualGrid = false").arg("camera"); + return false; + } + + QJsonObject cameraObject = v2Object[_jsonCameraObjectKey].toObject(); + + // Older code had typo on "imageSideOverlap" incorrectly being "imageSizeOverlap" + QString incorrectImageSideOverlap = "imageSizeOverlap"; + if (cameraObject.contains(incorrectImageSideOverlap)) { + cameraObject[_jsonSideOverlapKey] = cameraObject[incorrectImageSideOverlap]; + cameraObject.remove(incorrectImageSideOverlap); + } + + QList cameraKeyInfoList = { + { _jsonGroundResolutionKey, QJsonValue::Double, true }, + { _jsonFrontalOverlapKey, QJsonValue::Double, true }, + { _jsonSideOverlapKey, QJsonValue::Double, true }, + { _jsonCameraSensorWidthKey, QJsonValue::Double, true }, + { _jsonCameraSensorHeightKey, QJsonValue::Double, true }, + { _jsonCameraResolutionWidthKey, QJsonValue::Double, true }, + { _jsonCameraResolutionHeightKey, QJsonValue::Double, true }, + { _jsonCameraFocalLengthKey, QJsonValue::Double, true }, + { _jsonCameraNameKey, QJsonValue::String, true }, + { _jsonCameraOrientationLandscapeKey, QJsonValue::Bool, true }, + { _jsonCameraMinTriggerIntervalKey, QJsonValue::Double, false }, + }; + if (!JsonHelper::validateKeys(cameraObject, cameraKeyInfoList, errorString)) { + return false; + } + + _cameraFact.setRawValue(cameraObject[_jsonCameraNameKey].toString()); + _cameraOrientationLandscapeFact.setRawValue(cameraObject[_jsonCameraOrientationLandscapeKey].toBool(true)); + + _groundResolutionFact.setRawValue (cameraObject[_jsonGroundResolutionKey].toDouble()); + _frontalOverlapFact.setRawValue (cameraObject[_jsonFrontalOverlapKey].toInt()); + _sideOverlapFact.setRawValue (cameraObject[_jsonSideOverlapKey].toInt()); + _cameraSensorWidthFact.setRawValue (cameraObject[_jsonCameraSensorWidthKey].toDouble()); + _cameraSensorHeightFact.setRawValue (cameraObject[_jsonCameraSensorHeightKey].toDouble()); + _cameraResolutionWidthFact.setRawValue (cameraObject[_jsonCameraResolutionWidthKey].toDouble()); + _cameraResolutionHeightFact.setRawValue (cameraObject[_jsonCameraResolutionHeightKey].toDouble()); + _cameraFocalLengthFact.setRawValue (cameraObject[_jsonCameraFocalLengthKey].toDouble()); + _cameraMinTriggerInterval = cameraObject[_jsonCameraMinTriggerIntervalKey].toDouble(0); + } + + // Polygon shape + /// Load a polygon from json + /// @param json Json object to load from + /// @param required true: no polygon in object will generate error + /// @param errorString Error string if return is false + /// @return true: success, false: failure (errorString set) + if (!_mapPolygon.loadFromJson(v2Object, true /* required */, errorString)) { + _mapPolygon.clear(); + return false; + } + + _ignoreRecalc = false; + _generateGrid(); + + return true; +#else + Q_UNUSED(complexObject); + Q_UNUSED(sequenceNumber); + Q_UNUSED(errorString); + + return false; +#endif +} + +void StructureScanComplexItem::_polygonPathChanged(void) +{ + emit coordinateChanged(coordinate()); + emit exitCoordinateChanged(exitCoordinate()); + emit greatestDistanceToChanged(); +} + +double StructureScanComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const +{ + double greatestDistance = 0.0; + QList vertices = _mapPolygon.coordinateList(); + + for (int i=0; i greatestDistance) { + greatestDistance = distance; + } + } + + return greatestDistance; +} + +bool StructureScanComplexItem::specifiesCoordinate(void) const +{ + return _mapPolygon.count() > 2; +} + +void StructureScanComplexItem::appendMissionItems(QList& items, QObject* missionItemParent) +{ + int seqNum = _sequenceNumber; + double baseAltitude = _altitudeFact.rawValue().toDouble(); + + MissionItem* item = new MissionItem(seqNum++, + MAV_CMD_DO_MOUNT_CONTROL, + MAV_FRAME_MISSION, + 0, // Gimbal pitch + 0, // Gimbal roll + 90, // Gimbal yaw + 0, 0, 0, // param 4-6 not used + MAV_MOUNT_MODE_MAVLINK_TARGETING, + true, // autoContinue + false, // isCurrentItem + missionItemParent); + items.append(item); + + for (int layer=0; layer<_layersFact.rawValue().toInt(); layer++) { + double layerAltitude = baseAltitude + (layer * _layerDistanceFact.rawValue().toDouble()); + + for (int i=0; i<_mapPolygon.count(); i++) { + QGeoCoordinate vertexCoord = _mapPolygon.pathModel().value(i)->coordinate(); + + MissionItem* item = new MissionItem(seqNum++, + MAV_CMD_NAV_WAYPOINT, + _altitudeRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL, + 0, // No hold time + 0.0, // No acceptance radius specified + 0.0, // Pass through waypoint + 90, //std::numeric_limits::quiet_NaN(), // Yaw unchanged + vertexCoord.latitude(), + vertexCoord.longitude(), + layerAltitude, + true, // autoContinue + false, // isCurrentItem + missionItemParent); + items.append(item); + } + + QGeoCoordinate vertexCoord = _mapPolygon.pathModel().value(0)->coordinate(); + + MissionItem* item = new MissionItem(seqNum++, + MAV_CMD_NAV_WAYPOINT, + _altitudeRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL, + 0, // No hold time + 0.0, // No acceptance radius specified + 0.0, // Pass through waypoint + std::numeric_limits::quiet_NaN(), // Yaw unchanged + vertexCoord.latitude(), + vertexCoord.longitude(), + layerAltitude, + true, // autoContinue + false, // isCurrentItem + missionItemParent); + items.append(item); + } +} + +int StructureScanComplexItem::cameraShots(void) const +{ + return true /*_triggerCamera()*/ ? _cameraShots : 0; +} + +void StructureScanComplexItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus) +{ + ComplexMissionItem::setMissionFlightStatus(missionFlightStatus); + if (!qFuzzyCompare(_cruiseSpeed, missionFlightStatus.vehicleSpeed)) { + _cruiseSpeed = missionFlightStatus.vehicleSpeed; + emit timeBetweenShotsChanged(); + } +} + +void StructureScanComplexItem::_setDirty(void) +{ + setDirty(true); +} + +void StructureScanComplexItem::applyNewAltitude(double newAltitude) +{ + _altitudeFact.setRawValue(newAltitude); +} + +void StructureScanComplexItem::_polygonDirtyChanged(bool dirty) +{ + if (dirty) { + setDirty(true); + } +} + +double StructureScanComplexItem::timeBetweenShots(void) const +{ + return _cruiseSpeed == 0 ? 0 :_cameraTriggerDistanceFact.rawValue().toDouble() / _cruiseSpeed; +} + +QGeoCoordinate StructureScanComplexItem::coordinate(void) const +{ + if (_mapPolygon.count() > 0) { + int entryVertex = qMax(qMin(_entryVertex, _mapPolygon.count() - 1), 0); + return _mapPolygon.vertexCoordinate(entryVertex); + } else { + return QGeoCoordinate(); + } +} + +QGeoCoordinate StructureScanComplexItem::exitCoordinate(void) const +{ + return coordinate(); +} + +void StructureScanComplexItem::_updateCoordinateAltitudes(void) +{ + emit coordinateChanged(coordinate()); + emit exitCoordinateChanged(exitCoordinate()); +} + +void StructureScanComplexItem::rotateEntryPoint(void) +{ + _entryVertex++; + if (_entryVertex >= _mapPolygon.count()) { + _entryVertex = 0; + } + emit coordinateChanged(coordinate()); + emit exitCoordinateChanged(exitCoordinate()); +} diff --git a/src/MissionManager/StructureScanComplexItem.h b/src/MissionManager/StructureScanComplexItem.h new file mode 100644 index 0000000000000000000000000000000000000000..342874301a251777608922f68122495c2fee87c3 --- /dev/null +++ b/src/MissionManager/StructureScanComplexItem.h @@ -0,0 +1,162 @@ +/**************************************************************************** + * + * (c) 2009-2016 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + + +#ifndef StructureScanComplexItem_H +#define StructureScanComplexItem_H + +#include "ComplexMissionItem.h" +#include "MissionItem.h" +#include "SettingsFact.h" +#include "QGCLoggingCategory.h" +#include "QGCMapPolygon.h" + +Q_DECLARE_LOGGING_CATEGORY(StructureScanComplexItemLog) + +class StructureScanComplexItem : public ComplexMissionItem +{ + Q_OBJECT + +public: + StructureScanComplexItem(Vehicle* vehicle, QObject* parent = NULL); + + Q_PROPERTY(Fact* altitude READ altitude CONSTANT) + Q_PROPERTY(Fact* layers READ layers CONSTANT) + Q_PROPERTY(Fact* layerDistance READ layerDistance CONSTANT) + Q_PROPERTY(Fact* cameraTriggerDistance READ cameraTriggerDistance CONSTANT) + Q_PROPERTY(bool altitudeRelative MEMBER _altitudeRelative NOTIFY altitudeRelativeChanged) + Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged) + Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged) + Q_PROPERTY(double cameraMinTriggerInterval MEMBER _cameraMinTriggerInterval NOTIFY cameraMinTriggerIntervalChanged) + Q_PROPERTY(QGCMapPolygon* mapPolygon READ mapPolygon CONSTANT) + + Fact* altitude (void) { return &_altitudeFact; } + Fact* layers (void) { return &_layersFact; } + Fact* layerDistance (void) { return &_layerDistanceFact; } + Fact* cameraTriggerDistance (void) { return &_cameraTriggerDistanceFact; } + + int cameraShots (void) const; + double timeBetweenShots(void) const; + QGCMapPolygon* mapPolygon (void) { return &_mapPolygon; } + + Q_INVOKABLE void rotateEntryPoint(void); + + // Overrides from ComplexMissionItem + + double complexDistance (void) const final { return _scanDistance; } + int lastSequenceNumber (void) const final; + bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final; + double greatestDistanceTo (const QGeoCoordinate &other) const final; + QString mapVisualQML (void) const final { return QStringLiteral("StructureScanMapVisual.qml"); } + + // Overrides from VisualMissionItem + + bool dirty (void) const final { return _dirty; } + bool isSimpleItem (void) const final { return false; } + bool isStandaloneCoordinate (void) const final { return false; } + bool specifiesCoordinate (void) const final; + bool specifiesAltitudeOnly (void) const final { return false; } + QString commandDescription (void) const final { return tr("Structure Scan"); } + QString commandName (void) const final { return tr("Structure Scan"); } + QString abbreviation (void) const final { return "S"; } + QGeoCoordinate coordinate (void) const final; + QGeoCoordinate exitCoordinate (void) const final; + int sequenceNumber (void) const final { return _sequenceNumber; } + double specifiedFlightSpeed (void) final { return std::numeric_limits::quiet_NaN(); } + double specifiedGimbalYaw (void) final { return std::numeric_limits::quiet_NaN(); } + void appendMissionItems (QList& items, QObject* missionItemParent) final; + void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final; + void applyNewAltitude (double newAltitude) final; + + bool coordinateHasRelativeAltitude (void) const final { return _altitudeRelative; } + bool exitCoordinateHasRelativeAltitude (void) const final { return _altitudeRelative; } + bool exitCoordinateSameAsEntry (void) const final { return true; } + + void setDirty (bool dirty) final; + void setCoordinate (const QGeoCoordinate& coordinate) final { Q_UNUSED(coordinate); } + void setSequenceNumber (int sequenceNumber) final; + void save (QJsonArray& missionItems) final; + + static const char* jsonComplexItemTypeValue; + +signals: + void cameraShotsChanged (int cameraShots); + void timeBetweenShotsChanged (void); + void cameraMinTriggerIntervalChanged(double cameraMinTriggerInterval); + void altitudeRelativeChanged (bool altitudeRelative); + +private slots: + void _setDirty(void); + void _polygonDirtyChanged(bool dirty); + void _polygonCountChanged(int count); + void _polygonPathChanged(void); + void _clearInternal(void); + void _updateCoordinateAltitudes(void); + +private: + void _setExitCoordinate(const QGeoCoordinate& coordinate); + void _setScanDistance(double scanDistance); + void _setCameraShots(int cameraShots); + double _triggerDistance(void) const; + + int _sequenceNumber; + bool _dirty; + QGCMapPolygon _mapPolygon; + bool _altitudeRelative; + int _entryVertex; // Polygon vertext which is used as the mission entry point + + bool _ignoreRecalc; + double _scanDistance; + int _cameraShots; + double _timeBetweenShots; + double _cameraMinTriggerInterval; + double _cruiseSpeed; + + static QMap _metaDataMap; + + Fact _altitudeFact; + Fact _layersFact; + Fact _layerDistanceFact; + Fact _cameraTriggerDistanceFact; + + static const char* _altitudeFactName; + static const char* _layersFactName; + static const char* _layerDistanceFactName; + static const char* _cameraTriggerDistanceFactName; + + static const char* _jsonGridObjectKey; + static const char* _jsonGridAltitudeKey; + static const char* _jsonGridAltitudeRelativeKey; + static const char* _jsonGridAngleKey; + static const char* _jsonGridSpacingKey; + static const char* _jsonGridEntryLocationKey; + static const char* _jsonTurnaroundDistKey; + static const char* _jsonCameraTriggerDistanceKey; + static const char* _jsonCameraTriggerInTurnaroundKey; + static const char* _jsonHoverAndCaptureKey; + static const char* _jsonGroundResolutionKey; + static const char* _jsonFrontalOverlapKey; + static const char* _jsonSideOverlapKey; + static const char* _jsonCameraSensorWidthKey; + static const char* _jsonCameraSensorHeightKey; + static const char* _jsonCameraResolutionWidthKey; + static const char* _jsonCameraResolutionHeightKey; + static const char* _jsonCameraFocalLengthKey; + static const char* _jsonCameraMinTriggerIntervalKey; + static const char* _jsonManualGridKey; + static const char* _jsonCameraObjectKey; + static const char* _jsonCameraNameKey; + static const char* _jsonCameraOrientationLandscapeKey; + static const char* _jsonFixedValueIsAltitudeKey; + static const char* _jsonRefly90DegreesKey; + + static const int _hoverAndCaptureDelaySeconds = 1; +}; + +#endif diff --git a/src/MissionManager/SurveyMissionItem.cc b/src/MissionManager/SurveyMissionItem.cc index 89f25851e54e7b33d480181d822080eb4b3469b1..94ca5ae298169ffeefb0f5900c79a9abcd3c34ab 100644 --- a/src/MissionManager/SurveyMissionItem.cc +++ b/src/MissionManager/SurveyMissionItem.cc @@ -1322,7 +1322,7 @@ double SurveyMissionItem::timeBetweenShots(void) const return _cruiseSpeed == 0 ? 0 : _triggerDistance() / _cruiseSpeed; } -void SurveyMissionItem::setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) +void SurveyMissionItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus) { ComplexMissionItem::setMissionFlightStatus(missionFlightStatus); if (!qFuzzyCompare(_cruiseSpeed, missionFlightStatus.vehicleSpeed)) { diff --git a/src/PlanView/MissionItemStatus.qml b/src/PlanView/MissionItemStatus.qml index 1d74f3dc78a3b98a148c24b0d82c37fe07ba730c..94435662c6680fa63785b384983b2231d593dad5 100644 --- a/src/PlanView/MissionItemStatus.qml +++ b/src/PlanView/MissionItemStatus.qml @@ -19,6 +19,7 @@ import QGroundControl.FactSystem 1.0 import QGroundControl.FactControls 1.0 Rectangle { + id: root height: ScreenTools.defaultFontPixelHeight * 7 radius: ScreenTools.defaultFontPixelWidth * 0.5 color: qgcPal.window @@ -27,8 +28,14 @@ Rectangle { property var missionItems ///< List of all available mission items + property real maxWidth: parent.width readonly property real _margins: ScreenTools.defaultFontPixelWidth + onMaxWidthChanged: { + var calcLength = (statusListView.count + 1)*statusListView.contentItem.children[0].width + root.width = root.maxWidth > calcLength ? calcLength : root.maxWidth + } + QGCPalette { id: qgcPal } QGCLabel { @@ -56,6 +63,11 @@ Rectangle { clip: true currentIndex: _currentMissionIndex + onCountChanged: { + var calcLength = (statusListView.count + 1)*statusListView.contentItem.children[0].width + root.width = root.maxWidth > calcLength ? calcLength : root.maxWidth + } + delegate: Item { height: statusListView.height width: display ? (indicator.width + spacing) : 0 diff --git a/src/PlanView/PlanView.qml b/src/PlanView/PlanView.qml index 30618bf04afc82a3ff098db8b88d5b855d806a4a..694cb30566e4d21f21a4239d182a170e278e92f0 100644 --- a/src/PlanView/PlanView.qml +++ b/src/PlanView/PlanView.qml @@ -640,7 +640,7 @@ QGCView { id: waypointValuesDisplay anchors.margins: ScreenTools.defaultFontPixelWidth anchors.left: parent.left - anchors.right: rightPanel.left + maxWidth: parent.width - rightPanel.width - x anchors.bottom: parent.bottom missionItems: _missionController.visualItems visible: _editingLayer === _layerMission && !ScreenTools.isShortScreen diff --git a/src/PlanView/StructureScanEditor.qml b/src/PlanView/StructureScanEditor.qml new file mode 100644 index 0000000000000000000000000000000000000000..a23009bce6c9061e49fff318f18f1b1183d89452 --- /dev/null +++ b/src/PlanView/StructureScanEditor.qml @@ -0,0 +1,143 @@ +import QtQuick 2.3 +import QtQuick.Controls 1.2 +import QtQuick.Controls.Styles 1.4 +import QtQuick.Dialogs 1.2 +import QtQuick.Extras 1.4 +import QtQuick.Layouts 1.2 + +import QGroundControl 1.0 +import QGroundControl.ScreenTools 1.0 +import QGroundControl.Vehicle 1.0 +import QGroundControl.Controls 1.0 +import QGroundControl.FactControls 1.0 +import QGroundControl.Palette 1.0 +import QGroundControl.FlightMap 1.0 + +// Editor for Survery mission items +Rectangle { + id: _root + height: visible ? (editorColumn.height + (_margin * 2)) : 0 + width: availableWidth + color: qgcPal.windowShadeDark + radius: _radius + + // The following properties must be available up the hierarchy chain + //property real availableWidth ///< Width for control + //property var missionItem ///< Mission Item for editor + + property real _margin: ScreenTools.defaultFontPixelWidth / 2 + property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5 + property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle + + + function polygonCaptureStarted() { + missionItem.clearPolygon() + } + + function polygonCaptureFinished(coordinates) { + for (var i=0; i 0 && missionItem.cameraMinTriggerInterval !== 0 && missionItem.cameraMinTriggerInterval > missionItem.timeBetweenShots + } + + GridLayout { + anchors.left: parent.left + anchors.right: parent.right + columnSpacing: _margin + rowSpacing: _margin + columns: 2 + + QGCLabel { text: qsTr("Altitude") } + FactTextField { + fact: missionItem.altitude + Layout.fillWidth: true + } + + QGCLabel { text: qsTr("Layers") } + FactTextField { + fact: missionItem.layers + Layout.fillWidth: true + } + + QGCLabel { text: qsTr("Layer distance") } + FactTextField { + fact: missionItem.layerDistance + Layout.fillWidth: true + } + + QGCLabel { text: qsTr("Trigger Distance") } + FactTextField { + fact: missionItem.cameraTriggerDistance + Layout.fillWidth: true + } + + QGCCheckBox { + text: qsTr("Relative altitude") + checked: missionItem.altitudeRelative + Layout.columnSpan: 2 + onClicked: missionItem.altitudeRelative = checked + } + } + + QGCLabel { text: qsTr("Point camera to structure using:") } + QGCRadioButton { text: qsTr("Vehicle yaw"); enabled: false } + QGCRadioButton { text: qsTr("Gimbal yaw"); checked: true; enabled: false } + + QGCButton { + text: qsTr("Rotate entry point") + onClicked: missionItem.rotateEntryPoint() + } + + SectionHeader { + id: statsHeader + text: qsTr("Statistics") + } + + Grid { + columns: 2 + columnSpacing: ScreenTools.defaultFontPixelWidth + visible: statsHeader.checked + + QGCLabel { text: qsTr("Photo count") } + QGCLabel { text: missionItem.cameraShots } + + QGCLabel { text: qsTr("Photo interval") } + QGCLabel { text: missionItem.timeBetweenShots.toFixed(1) + " " + qsTr("secs") } + } + } +} + diff --git a/src/PlanView/StructureScanMapVisual.qml b/src/PlanView/StructureScanMapVisual.qml new file mode 100644 index 0000000000000000000000000000000000000000..4110ddcbe9e0c675ab50c70c9ac8175c7582400f --- /dev/null +++ b/src/PlanView/StructureScanMapVisual.qml @@ -0,0 +1,151 @@ +/**************************************************************************** + * + * (c) 2009-2016 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +import QtQuick 2.3 +import QtQuick.Controls 1.2 +import QtLocation 5.3 +import QtPositioning 5.3 + +import QGroundControl 1.0 +import QGroundControl.ScreenTools 1.0 +import QGroundControl.Palette 1.0 +import QGroundControl.Controls 1.0 +import QGroundControl.FlightMap 1.0 + +/// Survey Complex Mission Item visuals +Item { + id: _root + + property var map ///< Map control to place item in + + property var _missionItem: object + property var _mapPolygon: object.mapPolygon + property var _gridComponent + property var _entryCoordinate + property var _exitCoordinate + + signal clicked(int sequenceNumber) + + function _addVisualElements() { + _gridComponent = gridComponent.createObject(map) + _entryCoordinate = entryPointComponent.createObject(map) + _exitCoordinate = exitPointComponent.createObject(map) + map.addMapItem(_gridComponent) + map.addMapItem(_entryCoordinate) + map.addMapItem(_exitCoordinate) + } + + function _destroyVisualElements() { + _gridComponent.destroy() + _entryCoordinate.destroy() + _exitCoordinate.destroy() + } + + /// Add an initial 4 sided polygon if there is none + function _addInitialPolygon() { + if (_mapPolygon.count < 3) { + // Initial polygon is inset to take 2/3rds space + var rect = Qt.rect(map.centerViewport.x, map.centerViewport.y, map.centerViewport.width, map.centerViewport.height) + rect.x += (rect.width * 0.25) / 2 + rect.y += (rect.height * 0.25) / 2 + rect.width *= 0.75 + rect.height *= 0.75 + + var centerCoord = map.toCoordinate(Qt.point(rect.x + (rect.width / 2), rect.y + (rect.height / 2)), false /* clipToViewPort */) + var topLeftCoord = map.toCoordinate(Qt.point(rect.x, rect.y), false /* clipToViewPort */) + var topRightCoord = map.toCoordinate(Qt.point(rect.x + rect.width, rect.y), false /* clipToViewPort */) + var bottomLeftCoord = map.toCoordinate(Qt.point(rect.x, rect.y + rect.height), false /* clipToViewPort */) + var bottomRightCoord = map.toCoordinate(Qt.point(rect.x + rect.width, rect.y + rect.height), false /* clipToViewPort */) + + // Initial polygon has max width and height of 3000 meters + var halfWidthMeters = Math.min(topLeftCoord.distanceTo(topRightCoord), 3000) / 2 + var halfHeightMeters = Math.min(topLeftCoord.distanceTo(bottomLeftCoord), 3000) / 2 + topLeftCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, -90).atDistanceAndAzimuth(halfHeightMeters, 0) + topRightCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, 90).atDistanceAndAzimuth(halfHeightMeters, 0) + bottomLeftCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, -90).atDistanceAndAzimuth(halfHeightMeters, 180) + bottomRightCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, 90).atDistanceAndAzimuth(halfHeightMeters, 180) + + _mapPolygon.appendVertex(topLeftCoord) + _mapPolygon.appendVertex(topRightCoord) + _mapPolygon.appendVertex(bottomRightCoord) + _mapPolygon.appendVertex(bottomLeftCoord) + } + } + + Component.onCompleted: { + _addInitialPolygon() + _addVisualElements() + } + + Component.onDestruction: { + _destroyVisualElements() + } + + QGCMapPolygonVisuals { + id: mapPolygonVisuals + mapControl: map + mapPolygon: _mapPolygon + interactive: _missionItem.isCurrentItem + borderWidth: 1 + borderColor: "black" + interiorColor: "green" + interiorOpacity: 0.5 + } + + // Survey grid lines + Component { + id: gridComponent + + MapPolyline { + line.color: "white" + line.width: 2 + path: _missionItem.gridPoints + } + } + + // Entry point + Component { + id: entryPointComponent + + MapQuickItem { + anchorPoint.x: sourceItem.anchorPointX + anchorPoint.y: sourceItem.anchorPointY + z: QGroundControl.zOrderMapItems + coordinate: _missionItem.coordinate + visible: _missionItem.exitCoordinate.isValid + + sourceItem: MissionItemIndexLabel { + index: _missionItem.sequenceNumber + label: "Entry" + checked: _missionItem.isCurrentItem + onClicked: _root.clicked(_missionItem.sequenceNumber) + } + } + } + + // Exit point + Component { + id: exitPointComponent + + MapQuickItem { + anchorPoint.x: sourceItem.anchorPointX + anchorPoint.y: sourceItem.anchorPointY + z: QGroundControl.zOrderMapItems + coordinate: _missionItem.exitCoordinate + visible: _missionItem.exitCoordinate.isValid + + sourceItem: MissionItemIndexLabel { + index: _missionItem.lastSequenceNumber + label: "Exit" + checked: _missionItem.isCurrentItem + onClicked: _root.clicked(_missionItem.sequenceNumber) + } + } + } +} diff --git a/src/QmlControls/ParameterEditor.qml b/src/QmlControls/ParameterEditor.qml index 25c00004aba11f4dab52e538ce33e31b6527793a..2159e6435cd0732962d90baa658cf9de1bb08ab3 100644 --- a/src/QmlControls/ParameterEditor.qml +++ b/src/QmlControls/ParameterEditor.qml @@ -32,7 +32,7 @@ QGCView { property Fact _editorDialogFact: Fact { } property int _rowHeight: ScreenTools.defaultFontPixelHeight * 2 property int _rowWidth: 10 // Dynamic adjusted at runtime - property bool _searchFilter: searchText.text != "" ///< true: showing results of search + property bool _searchFilter: searchText.text.trim() != "" ///< true: showing results of search property var _searchResults ///< List of parameter names from search results property bool _showRCToParam: !ScreenTools.isMobile && QGroundControl.multiVehicleManager.activeVehicle.px4Firmware diff --git a/src/QmlControls/ParameterEditorController.cc b/src/QmlControls/ParameterEditorController.cc index 9520b9eb9783753b6169195b1f52ea104132d274..00ca6d27a29e46dfe3a969a472033315ba1f6ccf 100644 --- a/src/QmlControls/ParameterEditorController.cc +++ b/src/QmlControls/ParameterEditorController.cc @@ -158,8 +158,9 @@ void ParameterEditorController::setRCToParam(const QString& paramName) void ParameterEditorController::_updateParameters(void) { QObjectList newParameterList; + QStringList searchItems = _searchText.split(' ', QString::SkipEmptyParts); - if (_searchText.isEmpty()) { + if (searchItems.isEmpty()) { const QMap >& groupMap = _vehicle->parameterManager()->getGroupMap(); foreach (const QString& parameter, groupMap[_currentComponentId][_currentGroup]) { newParameterList.append(_vehicle->parameterManager()->getParameter(_currentComponentId, parameter)); @@ -167,9 +168,17 @@ void ParameterEditorController::_updateParameters(void) } else { foreach(const QString ¶meter, _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) { Fact* fact = _vehicle->parameterManager()->getParameter(_vehicle->defaultComponentId(), parameter); - if (fact->name().contains(_searchText, Qt::CaseInsensitive) || - fact->shortDescription().contains(_searchText, Qt::CaseInsensitive) || - fact->longDescription().contains(_searchText, Qt::CaseInsensitive)) { + bool matched = true; + + // all of the search items must match in order for the parameter to be added to the list + for (const auto& searchItem : searchItems) { + if (!fact->name().contains(searchItem, Qt::CaseInsensitive) && + !fact->shortDescription().contains(searchItem, Qt::CaseInsensitive) && + !fact->longDescription().contains(searchItem, Qt::CaseInsensitive)) { + matched = false; + } + } + if (matched) { newParameterList.append(fact); } } diff --git a/src/QmlControls/ParameterEditorDialog.qml b/src/QmlControls/ParameterEditorDialog.qml index f3e76069eab49a17968b5fc691eebb728309e2a8..3a1f5e436ab24f1d89eb8ed53022952a2023b3de 100644 --- a/src/QmlControls/ParameterEditorDialog.qml +++ b/src/QmlControls/ParameterEditorDialog.qml @@ -85,6 +85,11 @@ QGCViewDialog { } } + // set focus to the text field when becoming visible (in case of an Enum, + // the valueField is not visible, but it's not an issue because the combo + // box cannot have a focus) + onVisibleChanged: if (visible && !ScreenTools.isMobile) valueField.forceActiveFocus() + QGCFlickable { anchors.fill: parent contentHeight: _column.y + _column.height diff --git a/src/QmlControls/QGCPipable.qml b/src/QmlControls/QGCPipable.qml index 2294835a0ec304c1ae5437ef738e9d7c3fb2b832..3a84d47b81306bd46bf9c2a69002b88a4900e18e 100644 --- a/src/QmlControls/QGCPipable.qml +++ b/src/QmlControls/QGCPipable.qml @@ -22,17 +22,100 @@ Item { property bool isHidden: false property bool isDark: false + // As a percentage of the window width + property real maxSize: 0.75 + property real minSize: 0.10 + signal activated() signal hideIt(bool state) + signal newWidth(real newWidth) MouseArea { + id: pipMouseArea anchors.fill: parent enabled: !isHidden + hoverEnabled: true onClicked: { pip.activated() } } + // MouseArea to drag in order to resize the PiP area + MouseArea { + id: pipResize + anchors.top: parent.top + anchors.right: parent.right + height: ScreenTools.minTouchPixels + width: height + property var initialX: 0 + property var initialWidth: 0 + + onClicked: { + // TODO propagate + } + + // When we push the mouse button down, we un-anchor the mouse area to prevent a resizing loop + onPressed: { + pipResize.anchors.top = undefined // Top doesn't seem to 'detach' + pipResize.anchors.right = undefined // This one works right, which is what we really need + pipResize.initialX = mouse.x + pipResize.initialWidth = pip.width + } + + // When we let go of the mouse button, we re-anchor the mouse area in the correct position + onReleased: { + pipResize.anchors.top = pip.top + pipResize.anchors.right = pip.right + } + + // Drag + onPositionChanged: { + if (pipResize.pressed) { + var parentW = pip.parent.width // flightView + var newW = pipResize.initialWidth + mouse.x - pipResize.initialX + if (newW < parentW * maxSize && newW > parentW * minSize) { + newWidth(newW) + } + } + } + } + + // Resize icon + Image { + source: "/qmlimages/pipResize.svg" + fillMode: Image.PreserveAspectFit + mipmap: true + anchors.right: parent.right + anchors.top: parent.top + visible: !isHidden && (ScreenTools.isMobile || pipMouseArea.containsMouse) + height: ScreenTools.defaultFontPixelHeight * 2.5 + width: ScreenTools.defaultFontPixelHeight * 2.5 + sourceSize.height: height + } + + // Resize pip window if necessary when main window is resized + property var pipLock: 2 + + Connections { + target: pip.parent + onWidthChanged: { + // hackity hack... + // don't fire this while app is loading/initializing (it happens twice) + if (pipLock) { + pipLock-- + return + } + + var parentW = pip.parent.width + + if (pip.width > parentW * maxSize) { + newWidth(parentW * maxSize) + } else if (pip.width < parentW * minSize) { + newWidth(parentW * minSize) + } + } + } + //-- PIP Corner Indicator Image { id: closePIP @@ -41,7 +124,7 @@ Item { fillMode: Image.PreserveAspectFit anchors.left: parent.left anchors.bottom: parent.bottom - visible: !isHidden + visible: !isHidden && (ScreenTools.isMobile || pipMouseArea.containsMouse) height: ScreenTools.defaultFontPixelHeight * 2.5 width: ScreenTools.defaultFontPixelHeight * 2.5 sourceSize.height: height diff --git a/src/QmlControls/QGCViewDialog.qml b/src/QmlControls/QGCViewDialog.qml index f8d1443569c873b31c7807fb76a3738c7e16d550..5e6b7044d1efb74456fca7e627b408fc04817886 100644 --- a/src/QmlControls/QGCViewDialog.qml +++ b/src/QmlControls/QGCViewDialog.qml @@ -31,7 +31,7 @@ FactPanel { if (event.key == Qt.Key_Escape) { reject() event.accepted = true - } else if (event.key == Qt.Key_Return) { + } else if (event.key == Qt.Key_Return || event.key == Qt.Key_Enter) { accept() event.accepted = true } diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 0b63716cde18cdf68afb5ecece3d0454126cf631..495438e62aaaa7a68dc5ee2493f5481629f345f6 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -507,6 +507,14 @@ void Vehicle::resetCounters() void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message) { + // if the minimum supported version of MAVLink is already 2.0 + // set our max proto version to it. + unsigned mavlinkVersion = _mavlink->getCurrentVersion(); + if (_maxProtoVersion != mavlinkVersion && mavlinkVersion >= 200) { + _maxProtoVersion = _mavlink->getCurrentVersion(); + qCDebug(VehicleLog) << "Vehicle::_mavlinkMessageReceived setting _maxProtoVersion" << _maxProtoVersion; + } + if (message.sysid != _id && message.sysid != 0) { // We allow RADIO_STATUS messages which come from a link the vehicle is using to pass through and be handled if (!(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS && _containsLink(link))) { @@ -516,12 +524,6 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes if (!_containsLink(link)) { _addLink(link); - - // if the minimum supported version of MAVLink is already 2.0 - // set our max proto version to it. - if (_mavlink->getCurrentVersion() >= 200) { - _maxProtoVersion = _mavlink->getCurrentVersion(); - } } //-- Check link status @@ -861,6 +863,7 @@ void Vehicle::_setMaxProtoVersion(unsigned version) { // Set only once or if we need to reduce the max version if (_maxProtoVersion == 0 || version < _maxProtoVersion) { + qCDebug(VehicleLog) << "_setMaxProtoVersion before:after" << _maxProtoVersion << version; _maxProtoVersion = version; emit requestProtocolVersion(_maxProtoVersion); @@ -911,60 +914,6 @@ void Vehicle::_handleHilActuatorControls(mavlink_message_t &message) hil.mode); } -void Vehicle::_handleCommandAck(mavlink_message_t& message) -{ - bool showError = false; - - mavlink_command_ack_t ack; - mavlink_msg_command_ack_decode(&message, &ack); - - if (ack.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES && ack.result != MAV_RESULT_ACCEPTED) { - // We aren't going to get a response back for capabilities, so stop waiting for it before we ask for mission items - qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error. Starting mission request."; - _setCapabilities(0); - } - - if (ack.command == MAV_CMD_REQUEST_PROTOCOL_VERSION && ack.result != MAV_RESULT_ACCEPTED) { - // The autopilot does not understand the request and consequently is likely handling only - // MAVLink 1 - if (_maxProtoVersion == 0) { - _setMaxProtoVersion(100); - } - } - - if (_mavCommandQueue.count() && ack.command == _mavCommandQueue[0].command) { - _mavCommandAckTimer.stop(); - showError = _mavCommandQueue[0].showError; - _mavCommandQueue.removeFirst(); - } - - emit mavCommandResult(_id, message.compid, ack.command, ack.result, false /* noResponsefromVehicle */); - - if (showError) { - QString commandName = _toolbox->missionCommandTree()->friendlyName((MAV_CMD)ack.command); - - switch (ack.result) { - case MAV_RESULT_TEMPORARILY_REJECTED: - qgcApp()->showMessage(tr("%1 command temporarily rejected").arg(commandName)); - break; - case MAV_RESULT_DENIED: - qgcApp()->showMessage(tr("%1 command denied").arg(commandName)); - break; - case MAV_RESULT_UNSUPPORTED: - qgcApp()->showMessage(tr("%1 command not supported").arg(commandName)); - break; - case MAV_RESULT_FAILED: - qgcApp()->showMessage(tr("%1 command failed").arg(commandName)); - break; - default: - // Do nothing - break; - } - } - - _sendNextQueuedMavCommand(); -} - void Vehicle::_handleCommandLong(mavlink_message_t& message) { #ifdef __ios__ @@ -2407,6 +2356,7 @@ void Vehicle::_sendMavCommandAgain(void) if (_mavCommandRetryCount++ > _mavCommandMaxRetryCount) { if (queuedCommand.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) { // We aren't going to get a response back for capabilities, so stop waiting for it before we ask for mission items + qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES. Setting no capabilities. Starting Plan request."; _setCapabilities(0); _startPlanRequest(); } @@ -2414,8 +2364,12 @@ void Vehicle::_sendMavCommandAgain(void) if (queuedCommand.command == MAV_CMD_REQUEST_PROTOCOL_VERSION) { // We aren't going to get a response back for the protocol version, so assume v1 is all we can do. // If the max protocol version is uninitialized, fall back to v1. + qCDebug(VehicleLog) << "Vehicle failed to responded to MAV_CMD_REQUEST_PROTOCOL_VERSION. Starting Plan request."; if (_maxProtoVersion == 0) { + qCDebug(VehicleLog) << "Setting _maxProtoVersion to 100 since not yet set."; _setMaxProtoVersion(100); + } else { + qCDebug(VehicleLog) << "Leaving _maxProtoVersion at current value" << _maxProtoVersion; } } @@ -2487,6 +2441,66 @@ void Vehicle::_sendNextQueuedMavCommand(void) } +void Vehicle::_handleCommandAck(mavlink_message_t& message) +{ + bool showError = false; + + mavlink_command_ack_t ack; + mavlink_msg_command_ack_decode(&message, &ack); + + if (ack.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES && ack.result != MAV_RESULT_ACCEPTED) { + // We aren't going to get a response back for capabilities, so stop waiting for it before we ask for mission items + qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES with error(%1). Setting no capabilities. Starting Plan request.").arg(ack.result); + _setCapabilities(0); + } + + if (ack.command == MAV_CMD_REQUEST_PROTOCOL_VERSION && ack.result != MAV_RESULT_ACCEPTED) { + // The autopilot does not understand the request and consequently is likely handling only + // MAVLink 1 + qCDebug(VehicleLog) << QStringLiteral("Vehicle responded to MAV_CMD_REQUEST_PROTOCOL_VERSION with error(%1).").arg(ack.result); + if (_maxProtoVersion == 0) { + qCDebug(VehicleLog) << "Setting _maxProtoVersion to 100 since not yet set."; + _setMaxProtoVersion(100); + } else { + qCDebug(VehicleLog) << "Leaving _maxProtoVersion at current value" << _maxProtoVersion; + } + // FIXME: Is this missing here. I believe it is a bug. Debug to verify. May need to go into Stable. + //_startPlanRequest(); + } + + if (_mavCommandQueue.count() && ack.command == _mavCommandQueue[0].command) { + _mavCommandAckTimer.stop(); + showError = _mavCommandQueue[0].showError; + _mavCommandQueue.removeFirst(); + } + + emit mavCommandResult(_id, message.compid, ack.command, ack.result, false /* noResponsefromVehicle */); + + if (showError) { + QString commandName = _toolbox->missionCommandTree()->friendlyName((MAV_CMD)ack.command); + + switch (ack.result) { + case MAV_RESULT_TEMPORARILY_REJECTED: + qgcApp()->showMessage(tr("%1 command temporarily rejected").arg(commandName)); + break; + case MAV_RESULT_DENIED: + qgcApp()->showMessage(tr("%1 command denied").arg(commandName)); + break; + case MAV_RESULT_UNSUPPORTED: + qgcApp()->showMessage(tr("%1 command not supported").arg(commandName)); + break; + case MAV_RESULT_FAILED: + qgcApp()->showMessage(tr("%1 command failed").arg(commandName)); + break; + default: + // Do nothing + break; + } + } + + _sendNextQueuedMavCommand(); +} + void Vehicle::setPrearmError(const QString& prearmError) { _prearmError = prearmError; diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 0972751cb976607995452c56e2a7fad7ce1be548..9052ad608fcf52869de9edf186231c3692faac7a 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -382,8 +382,6 @@ void MAVLinkProtocol::_vehicleCountChanged(void) if (count == 0) { // Last vehicle is gone, close out logging _stopLogging(); - // Reset protocol version handling - _current_version = 0; _radio_version_mismatch_count = 0; } } diff --git a/tools/fix_code_style.sh b/tools/fix_code_style.sh deleted file mode 100755 index a6543998868e9eeb25d6224bfaca4ccd4585dfc5..0000000000000000000000000000000000000000 --- a/tools/fix_code_style.sh +++ /dev/null @@ -1,19 +0,0 @@ -#!/bin/sh -astyle \ - --style=allman \ - --indent=spaces=4 \ - --indent-cases \ - --indent-preprocessor \ - --break-blocks=all \ - --pad-oper \ - --pad-header \ - --unpad-paren \ - --keep-one-line-blocks \ - --keep-one-line-statements \ - --align-pointer=name \ - --align-reference=name \ - --suffix=none \ - --ignore-exclude-errors-x \ - --lineend=linux \ - --exclude=EASTL \ - $*