mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
AP_Landing: move get_bearing_cd to Location and rename to get_bearing_to
This commit is contained in:
parent
2efe32e4b1
commit
288ae80a59
@ -174,7 +174,7 @@ void AP_Landing_Deepstall::verify_abort_landing(const Location &prev_WP_loc, Loc
|
||||
// when aborting a landing, mimic the verify_takeoff with steering hold. Once
|
||||
// the altitude has been reached, restart the landing sequence
|
||||
throttle_suppressed = false;
|
||||
landing.nav_controller->update_heading_hold(get_bearing_cd(prev_WP_loc, next_WP_loc));
|
||||
landing.nav_controller->update_heading_hold(prev_WP_loc.get_bearing_to(next_WP_loc));
|
||||
}
|
||||
|
||||
|
||||
|
@ -39,7 +39,7 @@ void AP_Landing::type_slope_verify_abort_landing(const Location &prev_WP_loc, Lo
|
||||
// when aborting a landing, mimic the verify_takeoff with steering hold. Once
|
||||
// the altitude has been reached, restart the landing sequence
|
||||
throttle_suppressed = false;
|
||||
nav_controller->update_heading_hold(get_bearing_cd(prev_WP_loc, next_WP_loc));
|
||||
nav_controller->update_heading_hold(prev_WP_loc.get_bearing_to(next_WP_loc));
|
||||
}
|
||||
|
||||
/*
|
||||
@ -136,7 +136,8 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n
|
||||
prevents sudden turns if we overshoot the landing point
|
||||
*/
|
||||
struct Location land_WP_loc = next_WP_loc;
|
||||
int32_t land_bearing_cd = get_bearing_cd(prev_WP_loc, next_WP_loc);
|
||||
|
||||
int32_t land_bearing_cd = prev_WP_loc.get_bearing_to(next_WP_loc);
|
||||
location_update(land_WP_loc,
|
||||
land_bearing_cd*0.01f,
|
||||
prev_WP_loc.get_distance(current_loc) + 200);
|
||||
@ -288,7 +289,7 @@ void AP_Landing::type_slope_setup_landing_glide_slope(const Location &prev_WP_lo
|
||||
// project a point 500 meters past the landing point, passing
|
||||
// through the landing point
|
||||
const float land_projection = 500;
|
||||
int32_t land_bearing_cd = get_bearing_cd(prev_WP_loc, next_WP_loc);
|
||||
int32_t land_bearing_cd = prev_WP_loc.get_bearing_to(next_WP_loc);
|
||||
|
||||
// now calculate our aim point, which is before the landing
|
||||
// point and above it
|
||||
|
Loading…
Reference in New Issue
Block a user