mirror of https://github.com/ArduPilot/ardupilot
Added Bearing to home, distance to home calcs
This commit is contained in:
parent
49806d93d9
commit
3ff7b047d5
|
@ -12,6 +12,7 @@ static byte navigate()
|
||||||
// waypoint distance from plane
|
// waypoint distance from plane
|
||||||
// ----------------------------
|
// ----------------------------
|
||||||
wp_distance = get_distance(¤t_loc, &next_WP);
|
wp_distance = get_distance(¤t_loc, &next_WP);
|
||||||
|
home_distance = get_distance(¤t_loc, &home);
|
||||||
|
|
||||||
if (wp_distance < 0){
|
if (wp_distance < 0){
|
||||||
//gcs_send_text_P(SEVERITY_HIGH,PSTR("<navigate> WP error - distance < 0"));
|
//gcs_send_text_P(SEVERITY_HIGH,PSTR("<navigate> WP error - distance < 0"));
|
||||||
|
@ -23,6 +24,7 @@ static byte navigate()
|
||||||
// target_bearing is where we should be heading
|
// target_bearing is where we should be heading
|
||||||
// --------------------------------------------
|
// --------------------------------------------
|
||||||
target_bearing = get_bearing(¤t_loc, &next_WP);
|
target_bearing = get_bearing(¤t_loc, &next_WP);
|
||||||
|
home_to_copter_bearing = get_bearing(&home, ¤t_loc);
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue