mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Added Loiter P tuning as #12
This commit is contained in:
parent
d0405b0a0a
commit
469acff0fa
@ -1330,6 +1330,12 @@ static void tuning(){
|
||||
g.waypoint_speed_max = g.rc_6.control_in;
|
||||
break;
|
||||
|
||||
case CH6_LOITER_P:
|
||||
g.rc_6.set_range(0,1000);
|
||||
g.pi_loiter_lat.kP(tuning_value);
|
||||
g.pi_loiter_lon.kP(tuning_value);
|
||||
break;
|
||||
|
||||
case CH6_NAV_P:
|
||||
g.rc_6.set_range(0,6000);
|
||||
g.pi_nav_lat.kP(tuning_value);
|
||||
|
@ -151,6 +151,7 @@
|
||||
#define CH6_TRAVERSE_SPEED 10
|
||||
|
||||
#define CH6_NAV_P 11
|
||||
#define CH6_LOITER_P 12
|
||||
|
||||
// nav byte mask
|
||||
// -------------
|
||||
|
Loading…
Reference in New Issue
Block a user