ACM: Switched to filtered_loc for distance calcs

This commit is contained in:
Jason Short 2012-08-14 14:08:04 -07:00
parent a4bc5950cf
commit cdd2093a4c
1 changed files with 2 additions and 2 deletions

View File

@ -139,7 +139,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_cm(&current_loc, &next_WP) < 500)
if (get_distance_cm(&filtered_loc, &next_WP) < 500)
prev_WP = next_WP;
else
prev_WP = current_loc;
@ -167,7 +167,7 @@ static void set_next_WP(struct Location *wp)
// this is handy for the groundstation
// -----------------------------------
wp_distance = get_distance_cm(&current_loc, &next_WP);
wp_distance = get_distance_cm(&filtered_loc, &next_WP);
target_bearing = get_bearing_cd(&prev_WP, &next_WP);
// calc the location error: