From 995727383badc20a5d1b2ac4e2899760aabe78f9 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 10 Dec 2011 23:29:29 -0800 Subject: [PATCH] Adjust Simple mode on the fly. --- ArduCopter/ArduCopter.pde | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 17b90aa557..5099b58c35 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1257,10 +1257,11 @@ static void update_navigation() // are we in SIMPLE mode? if(do_simple){ // get distance to home - if(home_distance > 1000){ + if(home_distance > 10){ // 10m // we reset the angular offset to be a vector from home to the quad - //initial_simple_bearing = home_to_copter_bearing; + initial_simple_bearing = home_to_copter_bearing; + //Serial.printf("ISB: %d\n", initial_simple_bearing); } }