From 4757b20cc1b4909ad73c118e5ce6ce8bbe5c0190 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 22 Sep 2017 19:32:45 -0400 Subject: [PATCH] update PX4 airframe and param metadata (#5696) --- .../PX4/AirframeFactMetaData.xml | 248 +-- .../PX4/PX4ParameterFactMetaData.xml | 1778 +++++++++++------ 2 files changed, 1243 insertions(+), 783 deletions(-) diff --git a/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml b/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml index e9add7e348..f5f460bc8e 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/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 7b9962b76a..29f28cac21 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 -- GitLab