mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Landing: avoid using struct Location
clang reports this could be a problem when compiling under some EABIs. Remove it from most places as it is just noise, replace with class where we want to avoid including Location.h
This commit is contained in:
parent
787dc5ccf1
commit
034671b969
@ -148,7 +148,7 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n
|
|||||||
when landing we keep the L1 navigation waypoint 200m ahead. This
|
when landing we keep the L1 navigation waypoint 200m ahead. This
|
||||||
prevents sudden turns if we overshoot the landing point
|
prevents sudden turns if we overshoot the landing point
|
||||||
*/
|
*/
|
||||||
struct Location land_WP_loc = next_WP_loc;
|
Location land_WP_loc = next_WP_loc;
|
||||||
|
|
||||||
int32_t land_bearing_cd = prev_WP_loc.get_bearing_to(next_WP_loc);
|
int32_t land_bearing_cd = prev_WP_loc.get_bearing_to(next_WP_loc);
|
||||||
land_WP_loc.offset_bearing(land_bearing_cd * 0.01f, prev_WP_loc.get_distance(current_loc) + 200);
|
land_WP_loc.offset_bearing(land_bearing_cd * 0.01f, prev_WP_loc.get_distance(current_loc) + 200);
|
||||||
|
Loading…
Reference in New Issue
Block a user