From 043c3197da63eb4af392b3469af176b3b30c1a85 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 12 Nov 2011 21:39:00 -0800 Subject: [PATCH] Added additional nav params to reset --- ArduCopter/Attitude.pde | 17 +++++++++++++---- 1 file changed, 13 insertions(+), 4 deletions(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 9f636b1513..3850e7dc39 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -140,14 +140,23 @@ static void reset_hold_I(void) // Keeps outdated data out of our calculations static void reset_nav(void) { - nav_throttle = 0; - invalid_throttle = true; + nav_throttle = 0; + invalid_throttle = true; g.pi_nav_lat.reset_I(); g.pi_nav_lon.reset_I(); - long_error = 0; - lat_error = 0; + circle_angle = 0; + crosstrack_error = 0; + nav_lat = 0; + nav_lon = 0; + nav_roll = 0; + nav_pitch = 0; + target_bearing = 0; + wp_distance = 0; + wp_totalDistance = 0; + long_error = 0; + lat_error = 0; }