forked from Archive/PX4-Autopilot
mc_pos_control: improve parameter metadata
- Adapted descriptions to be more clear - Adjusted some limits and decimals
This commit is contained in:
parent
d00ad1b815
commit
54a351639c
|
@ -32,25 +32,25 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Maximum vertical acceleration in velocity controlled modes upward
|
||||
* Maximum upwards acceleration in climb rate controlled modes
|
||||
*
|
||||
* @unit m/s^2
|
||||
* @min 2.0
|
||||
* @max 15.0
|
||||
* @decimal 1
|
||||
* @increment 1
|
||||
* @decimal 2
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_ACC_UP_MAX, 4.0f);
|
||||
|
||||
/**
|
||||
* Maximum vertical acceleration in velocity controlled modes down
|
||||
* Maximum downwards acceleration in climb rate controlled modes
|
||||
*
|
||||
* @unit m/s^2
|
||||
* @min 2.0
|
||||
* @max 15.0
|
||||
* @decimal 1
|
||||
* @increment 1
|
||||
* @decimal 2
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_ACC_DOWN_MAX, 3.0f);
|
||||
|
@ -58,18 +58,20 @@ PARAM_DEFINE_FLOAT(MPC_ACC_DOWN_MAX, 3.0f);
|
|||
/**
|
||||
* Manual yaw rate input filter time constant
|
||||
*
|
||||
* Not used in Stabilized mode
|
||||
* Setting this parameter to 0 disables the filter
|
||||
*
|
||||
* @unit s
|
||||
* @min 0.0
|
||||
* @max 5.0
|
||||
* @decimal 2
|
||||
* @increment 0.2
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_MAN_Y_TAU, 0.08f);
|
||||
|
||||
/**
|
||||
* Altitude control mode.
|
||||
* Altitude reference mode
|
||||
*
|
||||
* Set to 0 to control height relative to the earth frame origin. This origin may move up and down in
|
||||
* flight due to sensor drift.
|
||||
|
@ -93,9 +95,11 @@ PARAM_DEFINE_INT32(MPC_ALT_MODE, 0);
|
|||
/**
|
||||
* Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)
|
||||
*
|
||||
* Only used with MPC_POS_MODE 0 or MPC_ALT_MODE 2
|
||||
*
|
||||
* @unit m/s
|
||||
* @min 0.0
|
||||
* @max 3.0
|
||||
* @min 0
|
||||
* @max 3
|
||||
* @decimal 2
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
|
@ -104,9 +108,11 @@ PARAM_DEFINE_FLOAT(MPC_HOLD_MAX_XY, 0.8f);
|
|||
/**
|
||||
* Maximum vertical velocity for which position hold is enabled (use 0 to disable check)
|
||||
*
|
||||
* Only used with MPC_ALT_MODE 1
|
||||
*
|
||||
* @unit m/s
|
||||
* @min 0.0
|
||||
* @max 3.0
|
||||
* @min 0
|
||||
* @max 3
|
||||
* @decimal 2
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
|
|
|
@ -32,76 +32,72 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Default horizontal velocity in mission
|
||||
* Default horizontal velocity in autonomous modes
|
||||
*
|
||||
* Horizontal velocity used when flying autonomously in e.g. Missions, RTL, Goto.
|
||||
* e.g. in Missions, RTL, Goto if the waypoint does not specify differently
|
||||
*
|
||||
* @unit m/s
|
||||
* @min 3.0
|
||||
* @max 20.0
|
||||
* @decimal 0
|
||||
* @increment 1
|
||||
* @decimal 2
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_CRUISE, 5.0f);
|
||||
|
||||
/**
|
||||
* Automatic ascent velocity
|
||||
* Ascent velocity in autonomous modes
|
||||
*
|
||||
* Ascent velocity in auto modes.
|
||||
* For manual modes and offboard, see MPC_Z_VEL_MAX_UP
|
||||
* For manually controlled modes and offboard see MPC_Z_VEL_MAX_UP
|
||||
*
|
||||
* @unit m/s
|
||||
* @min 0.5
|
||||
* @max 8.0
|
||||
* @increment 0.1
|
||||
* @decimal 1
|
||||
* @increment 0.5
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_V_AUTO_UP, 3.f);
|
||||
|
||||
/**
|
||||
* Automatic descent velocity
|
||||
* Descent velocity in autonomous modes
|
||||
*
|
||||
* Descent velocity in auto modes.
|
||||
* For manual modes and offboard, see MPC_Z_VEL_MAX_DN
|
||||
*
|
||||
* @unit m/s
|
||||
* @min 0.5
|
||||
* @max 4.0
|
||||
* @increment 0.1
|
||||
* @decimal 1
|
||||
* @increment 0.5
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_V_AUTO_DN, 1.5f);
|
||||
|
||||
/**
|
||||
* Acceleration for auto and for manual
|
||||
* Acceleration for autonomous and for manual modes
|
||||
*
|
||||
* Note: In manual, this parameter is only used in MPC_POS_MODE 4.
|
||||
* When piloting manually, this parameter is only used in MPC_POS_MODE 4.
|
||||
*
|
||||
* @unit m/s^2
|
||||
* @min 2.0
|
||||
* @max 15.0
|
||||
* @decimal 1
|
||||
* @increment 1
|
||||
* @decimal 2
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
|
||||
PARAM_DEFINE_FLOAT(MPC_ACC_HOR, 3.0f);
|
||||
|
||||
/**
|
||||
* Jerk limit in auto mode
|
||||
* Jerk limit in autonomous modes
|
||||
*
|
||||
* Limit the maximum jerk of the vehicle (how fast the acceleration can change).
|
||||
* A lower value leads to smoother vehicle motions, but it also limits its
|
||||
* agility.
|
||||
* A lower value leads to smoother vehicle motions but also limited agility.
|
||||
*
|
||||
* @unit m/s^3
|
||||
* @min 1.0
|
||||
* @max 80.0
|
||||
* @increment 1
|
||||
* @decimal 1
|
||||
* @increment 1
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_JERK_AUTO, 4.0f);
|
||||
|
@ -112,6 +108,7 @@ PARAM_DEFINE_FLOAT(MPC_JERK_AUTO, 4.0f);
|
|||
* @min 0.1
|
||||
* @max 1.0
|
||||
* @decimal 1
|
||||
* @increment 0.1
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_TRAJ_P, 0.5f);
|
||||
|
@ -130,29 +127,28 @@ PARAM_DEFINE_FLOAT(MPC_XY_TRAJ_P, 0.5f);
|
|||
* @min 0.1
|
||||
* @max 10.0
|
||||
* @decimal 1
|
||||
* @increment 1
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_ERR_MAX, 2.0f);
|
||||
|
||||
/**
|
||||
* Max yaw rate in auto mode
|
||||
* Max yaw rate in autonomous modes
|
||||
*
|
||||
* Limit the rate of change of the yaw setpoint in autonomous mode
|
||||
* to avoid large control output and mixer saturation.
|
||||
* Limits the rate of change of the yaw setpoint to avoid large
|
||||
* control output and mixer saturation.
|
||||
*
|
||||
* @unit deg/s
|
||||
* @min 0.0
|
||||
* @max 360.0
|
||||
* @decimal 1
|
||||
* @decimal 0
|
||||
* @increment 5
|
||||
* @group Multicopter Attitude Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_YAWRAUTO_MAX, 45.0f);
|
||||
|
||||
/**
|
||||
* Yaw mode.
|
||||
*
|
||||
* Specifies the heading in Auto.
|
||||
* Heading behavior in autonomous modes
|
||||
*
|
||||
* @min 0
|
||||
* @max 4
|
||||
|
|
|
@ -32,20 +32,20 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Enable user assisted descent for autonomous land routine
|
||||
* Enable nudging based on user input during autonomous land routine
|
||||
*
|
||||
* When enabled, descent speed will be:
|
||||
* Using stick input the vehicle can be moved horizontally and yawed.
|
||||
* The descend speed is amended:
|
||||
* stick full up - 0
|
||||
* stick centered - MPC_LAND_SPEED
|
||||
* stick full down - 2 * MPC_LAND_SPEED
|
||||
*
|
||||
* Additionally, the vehicle can be yawed and moved laterally using the other sticks.
|
||||
* Manual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE).
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @value 0 Fixed descent speed of MPC_LAND_SPEED
|
||||
* @value 1 User assisted descent speed
|
||||
* @value 0 Nudging disabled
|
||||
* @value 1 Nudging enabled
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MPC_LAND_RC_HELP, 0);
|
||||
|
@ -53,13 +53,13 @@ PARAM_DEFINE_INT32(MPC_LAND_RC_HELP, 0);
|
|||
/**
|
||||
* User assisted landing radius
|
||||
*
|
||||
* When user assisted descent is enabled (see MPC_LAND_RC_HELP),
|
||||
* this parameter controls the maximum position adjustment
|
||||
* allowed from the original landing point.
|
||||
* When nudging is enabled (see MPC_LAND_RC_HELP), this controls
|
||||
* the maximum allowed horizontal displacement from the original landing point.
|
||||
*
|
||||
* @unit m
|
||||
* @min 0
|
||||
* @decimal 1
|
||||
* @decimal 0
|
||||
* @increment 1
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_LAND_RADIUS, 1000.f);
|
||||
|
|
|
@ -34,9 +34,12 @@
|
|||
/**
|
||||
* Proportional gain for vertical position error
|
||||
*
|
||||
* @min 0.0
|
||||
* Defined as corrective velocity in m/s per m position error
|
||||
*
|
||||
* @min 0.1
|
||||
* @max 1.5
|
||||
* @decimal 2
|
||||
* @decimal 1
|
||||
* @increment 0.1
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_P, 1.0f);
|
||||
|
@ -44,9 +47,12 @@ PARAM_DEFINE_FLOAT(MPC_Z_P, 1.0f);
|
|||
/**
|
||||
* Proportional gain for horizontal position error
|
||||
*
|
||||
* Defined as corrective velocity in m/s per m position error
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 2.0
|
||||
* @decimal 2
|
||||
* @decimal 1
|
||||
* @increment 0.1
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_P, 0.95f);
|
||||
|
@ -54,11 +60,12 @@ PARAM_DEFINE_FLOAT(MPC_XY_P, 0.95f);
|
|||
/**
|
||||
* Proportional gain for vertical velocity error
|
||||
*
|
||||
* defined as correction acceleration in m/s^2 per m/s velocity error
|
||||
* Defined as corrective acceleration in m/s^2 per m/s velocity error
|
||||
*
|
||||
* @min 2.0
|
||||
* @max 15.0
|
||||
* @decimal 2
|
||||
* @decimal 1
|
||||
* @increment 0.1
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_VEL_P_ACC, 4.0f);
|
||||
|
@ -66,11 +73,12 @@ PARAM_DEFINE_FLOAT(MPC_Z_VEL_P_ACC, 4.0f);
|
|||
/**
|
||||
* Proportional gain for horizontal velocity error
|
||||
*
|
||||
* defined as correction acceleration in m/s^2 per m/s velocity error
|
||||
* Defined as corrective acceleration in m/s^2 per m/s velocity error
|
||||
*
|
||||
* @min 1.2
|
||||
* @max 5.0
|
||||
* @decimal 2
|
||||
* @decimal 1
|
||||
* @increment 0.1
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_VEL_P_ACC, 1.8f);
|
||||
|
@ -78,13 +86,12 @@ PARAM_DEFINE_FLOAT(MPC_XY_VEL_P_ACC, 1.8f);
|
|||
/**
|
||||
* Integral gain for vertical velocity error
|
||||
*
|
||||
* defined as correction acceleration in m/s^2 per m velocity integral
|
||||
*
|
||||
* Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff.
|
||||
* Defined as corrective acceleration in m/s^2 per m velocity integral
|
||||
*
|
||||
* @min 0.2
|
||||
* @max 3.0
|
||||
* @decimal 3
|
||||
* @decimal 1
|
||||
* @increment 0.1
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_VEL_I_ACC, 2.0f);
|
||||
|
@ -92,12 +99,13 @@ PARAM_DEFINE_FLOAT(MPC_Z_VEL_I_ACC, 2.0f);
|
|||
/**
|
||||
* Integral gain for horizontal velocity error
|
||||
*
|
||||
* defined as correction acceleration in m/s^2 per m velocity integral
|
||||
* Non-zero value allows to eliminate steady state errors in the presence of disturbances like wind.
|
||||
* Defined as correction acceleration in m/s^2 per m velocity integral
|
||||
* Allows to eliminate steady state errors in disturbances like wind.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 60.0
|
||||
* @decimal 3
|
||||
* @decimal 2
|
||||
* @increment 0.02
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_VEL_I_ACC, 0.4f);
|
||||
|
@ -105,23 +113,25 @@ PARAM_DEFINE_FLOAT(MPC_XY_VEL_I_ACC, 0.4f);
|
|||
/**
|
||||
* Differential gain for vertical velocity error
|
||||
*
|
||||
* defined as correction acceleration in m/s^2 per m/s^2 velocity derivative
|
||||
* Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 2.0
|
||||
* @decimal 3
|
||||
* @decimal 2
|
||||
* @increment 0.02
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_VEL_D_ACC, 0.0f);
|
||||
|
||||
/**
|
||||
* Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
|
||||
* Differential gain for horizontal velocity error
|
||||
*
|
||||
* defined as correction acceleration in m/s^2 per m/s^2 velocity derivative
|
||||
* Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative
|
||||
*
|
||||
* @min 0.1
|
||||
* @max 2.0
|
||||
* @decimal 3
|
||||
* @decimal 2
|
||||
* @increment 0.02
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_VEL_D_ACC, 0.2f);
|
||||
|
|
|
@ -34,14 +34,14 @@
|
|||
/**
|
||||
* Maximum horizontal velocity
|
||||
*
|
||||
* Maximum horizontal velocity in AUTO mode. If higher speeds
|
||||
* are commanded in a mission they will be capped to this velocity.
|
||||
* Absolute maximum for all velocity controlled modes.
|
||||
* Any higher value is truncated.
|
||||
*
|
||||
* @unit m/s
|
||||
* @min 0.0
|
||||
* @max 20.0
|
||||
* @decimal 0
|
||||
* @increment 1
|
||||
* @decimal 2
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 12.0f);
|
||||
|
@ -49,38 +49,41 @@ PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 12.0f);
|
|||
/**
|
||||
* Maximum tilt angle in air
|
||||
*
|
||||
* Limits maximum tilt in AUTO and POSCTRL modes during flight.
|
||||
* Absolute maximum for all velocity or acceleration controlled modes.
|
||||
* Any higher value is truncated.
|
||||
*
|
||||
* @unit deg
|
||||
* @min 20.0
|
||||
* @max 89.0
|
||||
* @decimal 1
|
||||
* @decimal 0
|
||||
* @increment 1
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_TILTMAX_AIR, 45.0f);
|
||||
|
||||
/**
|
||||
* Maximum tilt during landing
|
||||
* Maximum tilt during inital takeoff ramp
|
||||
*
|
||||
* Limits maximum tilt angle on landing.
|
||||
* Tighter tilt limit during takeoff to avoid tip over.
|
||||
*
|
||||
* @unit deg
|
||||
* @min 10.0
|
||||
* @min 5.0
|
||||
* @max 89.0
|
||||
* @decimal 1
|
||||
* @decimal 0
|
||||
* @increment 1
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_TILTMAX_LND, 12.0f);
|
||||
|
||||
/**
|
||||
* Minimum collective thrust in auto thrust control
|
||||
* Minimum collective thrust in climb rate controlled modes
|
||||
*
|
||||
* It's recommended to set it > 0 to avoid free fall with zero thrust.
|
||||
* Note: Without airmode zero thrust leads to zero roll/pitch control authority. (see MC_AIRMODE)
|
||||
* Too low thrust leads to loss of roll/pitch/yaw torque control authority.
|
||||
* Airmode is used to keep torque authority even with zero thrust (see MC_AIRMODE).
|
||||
*
|
||||
* @unit norm
|
||||
* @min 0.05
|
||||
* @max 1.0
|
||||
* @max 0.5
|
||||
* @decimal 2
|
||||
* @increment 0.01
|
||||
* @group Multicopter Position Control
|
||||
|
@ -88,15 +91,15 @@ PARAM_DEFINE_FLOAT(MPC_TILTMAX_LND, 12.0f);
|
|||
PARAM_DEFINE_FLOAT(MPC_THR_MIN, 0.12f);
|
||||
|
||||
/**
|
||||
* Maximum thrust in auto thrust control
|
||||
* Maximum collective thrust in climb rate controlled modes
|
||||
*
|
||||
* Limit max allowed thrust
|
||||
* Limit allowed thrust e.g. for indoor test of overpowered vehicle.
|
||||
*
|
||||
* @unit norm
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @decimal 2
|
||||
* @increment 0.01
|
||||
* @increment 0.05
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_THR_MAX, 1.0f);
|
||||
|
|
|
@ -32,16 +32,12 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Hover thrust
|
||||
* Vertical thrust required to hover
|
||||
*
|
||||
* Vertical thrust required to hover.
|
||||
* This value is mapped to center stick for manual throttle control.
|
||||
* With this value set to the thrust required to hover, transition
|
||||
* from manual to Altitude or Position mode while hovering will occur with the
|
||||
* throttle stick near center, which is then interpreted as (near)
|
||||
* zero demand for vertical speed.
|
||||
*
|
||||
* This parameter is also important for the landing detection to work correctly.
|
||||
* Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE).
|
||||
* Used for initialization of the hover thrust estimator (see MPC_USE_HTE).
|
||||
* The estimated hover thrust is used as base for zero vertical acceleration in altitude control.
|
||||
* The hover thrust is important for land detection to work correctly.
|
||||
*
|
||||
* @unit norm
|
||||
* @min 0.1
|
||||
|
@ -53,10 +49,10 @@
|
|||
PARAM_DEFINE_FLOAT(MPC_THR_HOVER, 0.5f);
|
||||
|
||||
/**
|
||||
* Hover thrust source selector
|
||||
* Hover thrust estimator
|
||||
*
|
||||
* Set false to use the fixed parameter MPC_THR_HOVER
|
||||
* Set true to use the value computed by the hover thrust estimator
|
||||
* Disable to use the fixed parameter MPC_THR_HOVER
|
||||
* Enable to use the hover thrust estimator
|
||||
*
|
||||
* @boolean
|
||||
* @group Multicopter Position Control
|
||||
|
@ -66,7 +62,7 @@ PARAM_DEFINE_INT32(MPC_USE_HTE, 1);
|
|||
/**
|
||||
* Horizontal thrust margin
|
||||
*
|
||||
* Margin that is kept for horizontal control when prioritizing vertical thrust.
|
||||
* Margin that is kept for horizontal control when higher priority vertical thrust is saturated.
|
||||
* To avoid completely starving horizontal control with high vertical error.
|
||||
*
|
||||
* @unit norm
|
||||
|
@ -79,12 +75,13 @@ PARAM_DEFINE_INT32(MPC_USE_HTE, 1);
|
|||
PARAM_DEFINE_FLOAT(MPC_THR_XY_MARG, 0.3f);
|
||||
|
||||
/**
|
||||
* Low pass filter cut freq. for numerical velocity derivative
|
||||
* Numerical velocity derivative low pass cutoff frequency
|
||||
*
|
||||
* @unit Hz
|
||||
* @min 0.0
|
||||
* @max 10
|
||||
* @decimal 2
|
||||
* @decimal 1
|
||||
* @increment 0.5
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_VELD_LP, 5.0f);
|
||||
|
|
|
@ -32,18 +32,19 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Manual-Position control sub-mode
|
||||
* Position/Altitude mode variant
|
||||
*
|
||||
* The supported sub-modes are:
|
||||
* 0 Simple position control where sticks map directly to velocity setpoints
|
||||
* without smoothing. Useful for velocity control tuning.
|
||||
* 3 Smooth position control with maximum acceleration and jerk limits based on
|
||||
* 0 Sticks directly map to velocity setpoints without smoothing.
|
||||
* Also applies to vertical direction and Altitude mode.
|
||||
* Useful for velocity control tuning.
|
||||
* 3 Sticks map to velocity but with maximum acceleration and jerk limits based on
|
||||
* jerk optimized trajectory generator (different algorithm than 1).
|
||||
* 4 Smooth position control where sticks map to acceleration and there's a virtual brake drag
|
||||
* 4 Sticks map to acceleration and there's a virtual brake drag
|
||||
*
|
||||
* @value 0 Simple position control
|
||||
* @value 3 Smooth position control (Jerk optimized)
|
||||
* @value 4 Acceleration based input
|
||||
* @value 0 Direct velocity
|
||||
* @value 3 Smoothed velocity
|
||||
* @value 4 Acceleration based
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_INT32(MPC_POS_MODE, 4);
|
||||
|
@ -51,8 +52,7 @@ PARAM_DEFINE_INT32(MPC_POS_MODE, 4);
|
|||
/**
|
||||
* Maximum horizontal velocity setpoint in Position mode
|
||||
*
|
||||
* If velocity setpoint larger than MPC_XY_VEL_MAX is set, then
|
||||
* the setpoint will be capped to MPC_XY_VEL_MAX
|
||||
* Must be smaller than MPC_XY_VEL_MAX.
|
||||
*
|
||||
* The maximum sideways and backward speed can be set differently
|
||||
* using MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively.
|
||||
|
@ -61,7 +61,7 @@ PARAM_DEFINE_INT32(MPC_POS_MODE, 4);
|
|||
* @min 3.0
|
||||
* @max 20.0
|
||||
* @increment 1
|
||||
* @decimal 2
|
||||
* @decimal 0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_VEL_MANUAL, 10.0f);
|
||||
|
@ -75,8 +75,8 @@ PARAM_DEFINE_FLOAT(MPC_VEL_MANUAL, 10.0f);
|
|||
* @unit m/s
|
||||
* @min -1.0
|
||||
* @max 20.0
|
||||
* @increment 0.1
|
||||
* @decimal 2
|
||||
* @increment 1
|
||||
* @decimal 0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_VEL_MAN_SIDE, -1.0f);
|
||||
|
@ -90,17 +90,16 @@ PARAM_DEFINE_FLOAT(MPC_VEL_MAN_SIDE, -1.0f);
|
|||
* @unit m/s
|
||||
* @min -1.0
|
||||
* @max 20.0
|
||||
* @increment 0.1
|
||||
* @decimal 2
|
||||
* @increment 1
|
||||
* @decimal 0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_VEL_MAN_BACK, -1.0f);
|
||||
|
||||
/**
|
||||
* Maximum ascent velocity
|
||||
* Maximum ascent velocity in manually piloted climb rate controlled modes and offboard
|
||||
*
|
||||
* Ascent velocity in manual modes and offboard.
|
||||
* For auto modes, see MPC_Z_V_AUTO_UP
|
||||
* For autonomous modes see MPC_Z_V_AUTO_UP
|
||||
*
|
||||
* @unit m/s
|
||||
* @min 0.5
|
||||
|
@ -112,10 +111,9 @@ PARAM_DEFINE_FLOAT(MPC_VEL_MAN_BACK, -1.0f);
|
|||
PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX_UP, 3.f);
|
||||
|
||||
/**
|
||||
* Maximum descent velocity
|
||||
* Maximum descent velocity in manually piloted climb rate controlled modes and offboard
|
||||
*
|
||||
* Descent velocity in manual modes and offboard.
|
||||
* For auto modes, see MPC_Z_V_AUTO_DN
|
||||
* For autonomous modes, see MPC_Z_V_AUTO_DN
|
||||
*
|
||||
* @unit m/s
|
||||
* @min 0.5
|
||||
|
@ -127,12 +125,12 @@ PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX_UP, 3.f);
|
|||
PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX_DN, 1.5f);
|
||||
|
||||
/**
|
||||
* Maximum horizontal acceleration for auto mode and for manual mode
|
||||
* Maximum horizontal acceleration
|
||||
*
|
||||
* MPC_POS_MODE
|
||||
* 1 just deceleration
|
||||
* 3 acceleration and deceleration
|
||||
* 4 just acceleration
|
||||
* 4 use MPC_ACC_HOR instead
|
||||
*
|
||||
* @unit m/s^2
|
||||
* @min 2.0
|
||||
|
@ -144,31 +142,34 @@ PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX_DN, 1.5f);
|
|||
PARAM_DEFINE_FLOAT(MPC_ACC_HOR_MAX, 5.0f);
|
||||
|
||||
/**
|
||||
* Maximum jerk limit
|
||||
* Maximum horizontal and vertical jerk in Position/Altitude mode
|
||||
*
|
||||
* Limit the maximum jerk of the vehicle (how fast the acceleration can change).
|
||||
* A lower value leads to smoother vehicle motions, but it also limits its
|
||||
* agility (how fast it can change directions or break).
|
||||
* A lower value leads to smoother motions but limits agility
|
||||
* (how fast it can change directions or break).
|
||||
*
|
||||
* Setting this to the maximum value essentially disables the limit.
|
||||
*
|
||||
* Note: This is only used when MPC_POS_MODE is set to a smoothing mode 3 or 4.
|
||||
* Only used with smooth MPC_POS_MODE 3 and 4.
|
||||
*
|
||||
* @unit m/s^3
|
||||
* @min 0.5
|
||||
* @max 500.0
|
||||
* @decimal 0
|
||||
* @increment 1
|
||||
* @decimal 2
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_JERK_MAX, 8.0f);
|
||||
|
||||
/**
|
||||
* Deadzone of sticks where position hold is enabled
|
||||
* Deadzone for sticks in manual piloted modes
|
||||
*
|
||||
* Does not apply to manual throttle and direct attitude piloting by stick.
|
||||
*
|
||||
* @min 0.0
|
||||
* @max 1.0
|
||||
* @decimal 2
|
||||
* @increment 0.01
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_HOLD_DZ, 0.1f);
|
||||
|
@ -179,12 +180,13 @@ PARAM_DEFINE_FLOAT(MPC_HOLD_DZ, 0.1f);
|
|||
* The higher the value the less sensitivity the stick has around zero
|
||||
* while still reaching the maximum value with full stick deflection.
|
||||
*
|
||||
* 0 Purely linear input curve (default)
|
||||
* 0 Purely linear input curve
|
||||
* 1 Purely cubic input curve
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @decimal 2
|
||||
* @increment 0.01
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_MAN_EXPO, 0.6f);
|
||||
|
@ -195,12 +197,13 @@ PARAM_DEFINE_FLOAT(MPC_XY_MAN_EXPO, 0.6f);
|
|||
* The higher the value the less sensitivity the stick has around zero
|
||||
* while still reaching the maximum value with full stick deflection.
|
||||
*
|
||||
* 0 Purely linear input curve (default)
|
||||
* 0 Purely linear input curve
|
||||
* 1 Purely cubic input curve
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @decimal 2
|
||||
* @increment 0.01
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_MAN_EXPO, 0.6f);
|
||||
|
@ -211,12 +214,13 @@ PARAM_DEFINE_FLOAT(MPC_Z_MAN_EXPO, 0.6f);
|
|||
* The higher the value the less sensitivity the stick has around zero
|
||||
* while still reaching the maximum value with full stick deflection.
|
||||
*
|
||||
* 0 Purely linear input curve (default)
|
||||
* 0 Purely linear input curve
|
||||
* 1 Purely cubic input curve
|
||||
*
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @decimal 2
|
||||
* @increment 0.01
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_YAW_EXPO, 0.6f);
|
||||
|
|
|
@ -62,7 +62,7 @@ PARAM_DEFINE_FLOAT(SYS_VEHICLE_RESP, -0.4f);
|
|||
* @increment 1
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_VEL_ALL, -10.0f);
|
||||
PARAM_DEFINE_FLOAT(MPC_XY_VEL_ALL, -10.f);
|
||||
|
||||
/**
|
||||
* Overall Vertical Velocity Limit
|
||||
|
@ -77,4 +77,4 @@ PARAM_DEFINE_FLOAT(MPC_XY_VEL_ALL, -10.0f);
|
|||
* @increment 0.5
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_VEL_ALL, -3.0f);
|
||||
PARAM_DEFINE_FLOAT(MPC_Z_VEL_ALL, -3.f);
|
||||
|
|
|
@ -32,32 +32,36 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Maximal tilt angle in manual or altitude mode
|
||||
* Maximal tilt angle in Stabilized or Altitude mode
|
||||
*
|
||||
* @unit deg
|
||||
* @min 0.0
|
||||
* @max 90.0
|
||||
* @decimal 1
|
||||
* @min 0
|
||||
* @max 90
|
||||
* @decimal 0
|
||||
* @increment 1
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_MAN_TILT_MAX, 35.0f);
|
||||
PARAM_DEFINE_FLOAT(MPC_MAN_TILT_MAX, 35.f);
|
||||
|
||||
/**
|
||||
* Max manual yaw rate
|
||||
* Max manual yaw rate for Stabilized, Altitude, Position mode
|
||||
*
|
||||
* @unit deg/s
|
||||
* @min 0.0
|
||||
* @min 0
|
||||
* @max 400
|
||||
* @decimal 1
|
||||
* @decimal 0
|
||||
* @increment 10
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_MAN_Y_MAX, 150.0f);
|
||||
PARAM_DEFINE_FLOAT(MPC_MAN_Y_MAX, 150.f);
|
||||
|
||||
/**
|
||||
* Minimum manual thrust
|
||||
* Minimum collective thrust in Stabilized mode
|
||||
*
|
||||
* Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust.
|
||||
* With MC_AIRMODE set to 1, this can safely be set to 0.
|
||||
* The value is mapped to the lowest throttle stick position in Stabilized mode.
|
||||
*
|
||||
* Too low collective thrust leads to loss of roll/pitch/yaw torque control authority.
|
||||
* Airmode is used to keep torque authority with zero thrust (see MC_AIRMODE).
|
||||
*
|
||||
* @unit norm
|
||||
* @min 0.0
|
||||
|
@ -69,17 +73,17 @@ PARAM_DEFINE_FLOAT(MPC_MAN_Y_MAX, 150.0f);
|
|||
PARAM_DEFINE_FLOAT(MPC_MANTHR_MIN, 0.08f);
|
||||
|
||||
/**
|
||||
* Thrust curve in Manual Mode
|
||||
* Thrust curve mapping in Stabilized Mode
|
||||
*
|
||||
* This parameter defines how the throttle stick input is mapped to commanded thrust
|
||||
* in Manual/Stabilized flight mode.
|
||||
* This parameter defines how the throttle stick input is mapped to collective thrust
|
||||
* in Stabilized mode.
|
||||
*
|
||||
* In case the default is used ('Rescale to hover thrust'), the stick input is linearly
|
||||
* rescaled, such that a centered stick corresponds to the hover throttle (see MPC_THR_HOVER).
|
||||
*
|
||||
* Select 'No Rescale' to directly map the stick 1:1 to the output. This can be useful
|
||||
* in case the hover thrust is very low and the default would lead to too much distortion
|
||||
* (e.g. if hover thrust is set to 20%, 80% of the upper thrust range is squeezed into the
|
||||
* (e.g. if hover thrust is set to 20%, then 80% of the upper thrust range is squeezed into the
|
||||
* upper half of the stick range).
|
||||
*
|
||||
* Note: In case MPC_THR_HOVER is set to 50%, the modes 0 and 1 are the same.
|
||||
|
|
|
@ -32,12 +32,13 @@
|
|||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Position control smooth takeoff ramp time constant
|
||||
* Smooth takeoff ramp time constant
|
||||
*
|
||||
* Increasing this value will make automatic and manual takeoff slower.
|
||||
* Increasing this value will make climb rate controlled takeoff slower.
|
||||
* If it's too slow the drone might scratch the ground and tip over.
|
||||
* A time constant of 0 disables the ramp
|
||||
*
|
||||
* @unit s
|
||||
* @min 0
|
||||
* @max 5
|
||||
* @group Multicopter Position Control
|
||||
|
|
Loading…
Reference in New Issue