From 3ff7b047d5275ed2a659a73fcc9ff8f6d5eacdb7 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Fri, 9 Dec 2011 15:34:20 -0800 Subject: [PATCH] Added Bearing to home, distance to home calcs --- ArduCopter/navigation.pde | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index 044cc072bc..d262615a6d 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -12,6 +12,7 @@ static byte navigate() // waypoint distance from plane // ---------------------------- wp_distance = get_distance(¤t_loc, &next_WP); + home_distance = get_distance(¤t_loc, &home); if (wp_distance < 0){ //gcs_send_text_P(SEVERITY_HIGH,PSTR(" WP error - distance < 0")); @@ -23,6 +24,7 @@ static byte navigate() // target_bearing is where we should be heading // -------------------------------------------- target_bearing = get_bearing(¤t_loc, &next_WP); + home_to_copter_bearing = get_bearing(&home, ¤t_loc); return 1; }