From be763a6ead0b85c678bf25c7c7476b1e9d3d7d00 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 11 Jul 2012 07:50:07 +1000 Subject: [PATCH] ACM: use get_distance_cm() not get_distance() this fixes a bug introduced in 28f2eb6b9 --- ArduCopter/commands.pde | 4 ++-- ArduCopter/navigation.pde | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopter/commands.pde b/ArduCopter/commands.pde index 2cdea618e3..464353ecd1 100644 --- a/ArduCopter/commands.pde +++ b/ArduCopter/commands.pde @@ -137,7 +137,7 @@ static void set_next_WP(struct Location *wp) if (next_WP.lat == 0 || command_nav_index <= 1){ prev_WP = current_loc; }else{ - if (get_distance(¤t_loc, &next_WP) < 500) + if (get_distance_cm(¤t_loc, &next_WP) < 500) prev_WP = next_WP; else prev_WP = current_loc; @@ -165,7 +165,7 @@ static void set_next_WP(struct Location *wp) // this is handy for the groundstation // ----------------------------------- - wp_distance = get_distance(¤t_loc, &next_WP); + wp_distance = get_distance_cm(¤t_loc, &next_WP); target_bearing = get_bearing(&prev_WP, &next_WP); // calc the location error: diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index f6d27ed122..0cd91e8a62 100644 --- a/ArduCopter/navigation.pde +++ b/ArduCopter/navigation.pde @@ -7,8 +7,8 @@ static void navigate() { // waypoint distance from plane in cm // --------------------------------------- - wp_distance = get_distance(¤t_loc, &next_WP); - home_distance = get_distance(¤t_loc, &home); + wp_distance = get_distance_cm(¤t_loc, &next_WP); + home_distance = get_distance_cm(¤t_loc, &home); // target_bearing is where we should be heading // --------------------------------------------