mirror of https://github.com/ArduPilot/ardupilot
changed tuning range
This commit is contained in:
parent
b543bbf514
commit
a685510c38
|
@ -1961,7 +1961,7 @@ static void tuning(){
|
|||
break;
|
||||
|
||||
case CH6_LOITER_P:
|
||||
g.rc_6.set_range(0,1000);
|
||||
g.rc_6.set_range(0,2000);
|
||||
g.pi_loiter_lat.kP(tuning_value);
|
||||
g.pi_loiter_lon.kP(tuning_value);
|
||||
break;
|
||||
|
|
Loading…
Reference in New Issue