mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Added Nav Rate tuning
This commit is contained in:
parent
0a4b8c123c
commit
bd52458e74
@ -1454,6 +1454,12 @@ static void tuning(){
|
|||||||
g.rc_6.set_range(0,1000);
|
g.rc_6.set_range(0,1000);
|
||||||
g.waypoint_speed_max = g.rc_6.control_in;
|
g.waypoint_speed_max = g.rc_6.control_in;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
case CH6_NAV_P:
|
||||||
|
g.rc_6.set_range(0,6000);
|
||||||
|
g.pi_nav_lat.kP(tuning_value);
|
||||||
|
g.pi_nav_lon.kP(tuning_value);
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -156,6 +156,8 @@
|
|||||||
#define CH6_RELAY 9
|
#define CH6_RELAY 9
|
||||||
#define CH6_TRAVERSE_SPEED 10
|
#define CH6_TRAVERSE_SPEED 10
|
||||||
|
|
||||||
|
#define CH6_NAV_P 11
|
||||||
|
|
||||||
// nav byte mask
|
// nav byte mask
|
||||||
// -------------
|
// -------------
|
||||||
#define NAV_LOCATION 1
|
#define NAV_LOCATION 1
|
||||||
|
Loading…
Reference in New Issue
Block a user