ACM: use get_distance_cm() not get_distance()

this fixes a bug introduced in 28f2eb6b9
This commit is contained in:
Andrew Tridgell 2012-07-11 07:50:07 +10:00
parent a72f6acef6
commit be763a6ead
2 changed files with 4 additions and 4 deletions

View File

@ -137,7 +137,7 @@ static void set_next_WP(struct Location *wp)
if (next_WP.lat == 0 || command_nav_index <= 1){ if (next_WP.lat == 0 || command_nav_index <= 1){
prev_WP = current_loc; prev_WP = current_loc;
}else{ }else{
if (get_distance(&current_loc, &next_WP) < 500) if (get_distance_cm(&current_loc, &next_WP) < 500)
prev_WP = next_WP; prev_WP = next_WP;
else else
prev_WP = current_loc; prev_WP = current_loc;
@ -165,7 +165,7 @@ static void set_next_WP(struct Location *wp)
// this is handy for the groundstation // this is handy for the groundstation
// ----------------------------------- // -----------------------------------
wp_distance = get_distance(&current_loc, &next_WP); wp_distance = get_distance_cm(&current_loc, &next_WP);
target_bearing = get_bearing(&prev_WP, &next_WP); target_bearing = get_bearing(&prev_WP, &next_WP);
// calc the location error: // calc the location error:

View File

@ -7,8 +7,8 @@ static void navigate()
{ {
// waypoint distance from plane in cm // waypoint distance from plane in cm
// --------------------------------------- // ---------------------------------------
wp_distance = get_distance(&current_loc, &next_WP); wp_distance = get_distance_cm(&current_loc, &next_WP);
home_distance = get_distance(&current_loc, &home); home_distance = get_distance_cm(&current_loc, &home);
// target_bearing is where we should be heading // target_bearing is where we should be heading
// -------------------------------------------- // --------------------------------------------