mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
SITL: Helicopter parameter updates
This commit is contained in:
parent
b89b0d7f9e
commit
4f7246c432
@ -77,3 +77,10 @@ H_RSC_MIN 1000
|
||||
H_RSC_MAX 2000
|
||||
EK2_ENABLE 1
|
||||
AHRS_EKF_TYPE 2
|
||||
IM_ACRO_COL_EXP 0.2
|
||||
IM_STAB_COL_1 400
|
||||
IM_STAB_COL_2 600
|
||||
IM_STAB_COL_3 700
|
||||
IM_STAB_COL_4 900
|
||||
ATC_PIRO_COMP 1
|
||||
|
||||
|
@ -42,7 +42,7 @@ private:
|
||||
float terminal_rotation_rate = 4*radians(360.0f);
|
||||
float hover_throttle = 0.65f;
|
||||
float terminal_velocity = 40;
|
||||
float hover_lean = 8.0f;
|
||||
float hover_lean = 3.0f;
|
||||
float yaw_zero = 0.1f;
|
||||
float rotor_rot_accel = radians(20);
|
||||
float roll_rate_max = radians(1400);
|
||||
|
Loading…
Reference in New Issue
Block a user