mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
ACM: use get_distance_cm() not get_distance()
this fixes a bug introduced in 28f2eb6b9
This commit is contained in:
parent
63a83b95b4
commit
a643d2aa6b
@ -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:
|
||||
|
@ -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
|
||||
// --------------------------------------------
|
||||
|
Loading…
Reference in New Issue
Block a user