From bd52458e740aa66303ff62c3176b29a696b044f0 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 10 Sep 2011 18:37:28 -0700 Subject: [PATCH] Added Nav Rate tuning --- ArduCopter/ArduCopter.pde | 6 ++++++ ArduCopter/defines.h | 2 ++ 2 files changed, 8 insertions(+) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 423c1cfd7f..37331f0ce3 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -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; } } diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 6b687b81b2..848d2e79c3 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -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