mirror of https://github.com/ArduPilot/ardupilot
TradHeli - modified the default collective min/max values to restrict movement to about half the full range.
This commit is contained in:
parent
a4e00f7459
commit
85167be181
|
@ -362,11 +362,11 @@ public:
|
||||||
heli_servo3_pos (180, k_param_heli_servo3_pos, PSTR("SV3_POS_")),
|
heli_servo3_pos (180, k_param_heli_servo3_pos, PSTR("SV3_POS_")),
|
||||||
heli_roll_max (4500, k_param_heli_roll_max, PSTR("ROL_MAX_")),
|
heli_roll_max (4500, k_param_heli_roll_max, PSTR("ROL_MAX_")),
|
||||||
heli_pitch_max (4500, k_param_heli_pitch_max, PSTR("PIT_MAX_")),
|
heli_pitch_max (4500, k_param_heli_pitch_max, PSTR("PIT_MAX_")),
|
||||||
heli_coll_min (1000, k_param_heli_collective_min, PSTR("COL_MIN_")),
|
heli_coll_min (1250, k_param_heli_collective_min, PSTR("COL_MIN_")),
|
||||||
heli_coll_max (2000, k_param_heli_collective_max, PSTR("COL_MAX_")),
|
heli_coll_max (1750, k_param_heli_collective_max, PSTR("COL_MAX_")),
|
||||||
heli_coll_mid (1500, k_param_heli_collective_mid, PSTR("COL_MID_")),
|
heli_coll_mid (1500, k_param_heli_collective_mid, PSTR("COL_MID_")),
|
||||||
heli_ext_gyro_enabled (0, k_param_heli_ext_gyro_enabled, PSTR("GYR_ENABLE_")),
|
heli_ext_gyro_enabled (0, k_param_heli_ext_gyro_enabled, PSTR("GYR_ENABLE_")),
|
||||||
heli_ext_gyro_gain (1000, k_param_heli_ext_gyro_gain, PSTR("GYR_GAIN_")),
|
heli_ext_gyro_gain (1350, k_param_heli_ext_gyro_gain, PSTR("GYR_GAIN_")),
|
||||||
heli_servo_averaging (0, k_param_heli_servo_averaging, PSTR("SV_AVG")),
|
heli_servo_averaging (0, k_param_heli_servo_averaging, PSTR("SV_AVG")),
|
||||||
heli_servo_manual (0, k_param_heli_servo_manual, PSTR("HSV_MAN")),
|
heli_servo_manual (0, k_param_heli_servo_manual, PSTR("HSV_MAN")),
|
||||||
heli_phase_angle (0, k_param_heli_phase_angle, PSTR("H_PHANG")),
|
heli_phase_angle (0, k_param_heli_phase_angle, PSTR("H_PHANG")),
|
||||||
|
|
Loading…
Reference in New Issue