mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: fix RTL alt when no using Rally points
This commit is contained in:
parent
0545185218
commit
64629914a4
@ -118,7 +118,7 @@ static void rtl_return_start()
|
||||
Vector3f destination = pv_location_to_vector(rally_point);
|
||||
#else
|
||||
Vector3f destination = pv_location_to_vector(ahrs.get_home());
|
||||
destination.z = get_RTL_alt();
|
||||
destination.z = pv_alt_above_origin(get_RTL_alt());
|
||||
#endif
|
||||
|
||||
wp_nav.set_wp_destination(destination);
|
||||
|
Loading…
Reference in New Issue
Block a user