forked from Archive/PX4-Autopilot
Merged master into ekf_params
This commit is contained in:
commit
f7065dce84
|
@ -117,7 +117,7 @@ extern struct system_load_s system_load;
|
|||
#define STICK_ON_OFF_HYSTERESIS_TIME_MS 1000
|
||||
#define STICK_ON_OFF_COUNTER_LIMIT (STICK_ON_OFF_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC)
|
||||
|
||||
#define POSITION_TIMEOUT 50000 /**< consider the local or global position estimate invalid after 50ms */
|
||||
#define POSITION_TIMEOUT 100000 /**< consider the local or global position estimate invalid after 100ms */
|
||||
#define RC_TIMEOUT 500000
|
||||
#define DIFFPRESS_TIMEOUT 2000000
|
||||
|
||||
|
|
|
@ -174,16 +174,28 @@ PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 5.0f);
|
|||
PARAM_DEFINE_FLOAT(MPC_XY_FF, 0.5f);
|
||||
|
||||
/**
|
||||
* Maximum tilt
|
||||
* Maximum tilt angle in air
|
||||
*
|
||||
* Limits maximum tilt in AUTO and EASY modes.
|
||||
* Limits maximum tilt in AUTO and EASY modes during flight.
|
||||
*
|
||||
* @unit deg
|
||||
* @min 0.0
|
||||
* @max 90.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_TILT_MAX, 45.0f);
|
||||
PARAM_DEFINE_FLOAT(MPC_TILTMAX_AIR, 45.0f);
|
||||
|
||||
/**
|
||||
* Maximum tilt during landing
|
||||
*
|
||||
* Limits maximum tilt angle on landing.
|
||||
*
|
||||
* @unit deg
|
||||
* @min 0.0
|
||||
* @max 90.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_TILTMAX_LND, 15.0f);
|
||||
|
||||
/**
|
||||
* Landing descend rate
|
||||
|
@ -194,14 +206,3 @@ PARAM_DEFINE_FLOAT(MPC_TILT_MAX, 45.0f);
|
|||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_LAND_SPEED, 1.0f);
|
||||
|
||||
/**
|
||||
* Maximum landing tilt
|
||||
*
|
||||
* Limits maximum tilt on landing.
|
||||
*
|
||||
* @unit deg
|
||||
* @min 0.0
|
||||
* @max 90.0
|
||||
* @group Multicopter Position Control
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(MPC_LAND_TILT, 15.0f);
|
||||
|
|
Loading…
Reference in New Issue