Added Nav Rate tuning

This commit is contained in:
Jason Short 2011-09-10 18:37:28 -07:00
parent 8f399625f3
commit b4a51806bc
2 changed files with 8 additions and 0 deletions

View File

@ -1454,6 +1454,12 @@ static void tuning(){
g.rc_6.set_range(0,1000);
g.waypoint_speed_max = g.rc_6.control_in;
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;
}
}

View File

@ -156,6 +156,8 @@
#define CH6_RELAY 9
#define CH6_TRAVERSE_SPEED 10
#define CH6_NAV_P 11
// nav byte mask
// -------------
#define NAV_LOCATION 1