From 5ad38a32bf79b17617355b2ffae616c64778465c Mon Sep 17 00:00:00 2001 From: Jason Short Date: Fri, 9 Nov 2012 21:43:05 -0800 Subject: [PATCH] ACM : Attitude : added nav param reset --- ArduCopter/Attitude.pde | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index dfd77bb2e6..0750cf91fb 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -527,8 +527,14 @@ static void reset_nav_params(void) wp_distance = 0; // Will be set by new command, used by loiter - long_error = 0; - lat_error = 0; + long_error = 0; + lat_error = 0; + nav_lon = 0; + nav_lat = 0; + nav_roll = 0; + nav_pitch = 0; + auto_roll = 0; + auto_pitch = 0; // make sure we stick to Nav yaw on takeoff auto_yaw = nav_yaw;