mirror of https://github.com/ArduPilot/ardupilot
Copter: bug fix rally point landing target
was drifting toward home by some distance as (0,0,0) was hard-coded in control_rtl.pde. Fixed, tested in SITL
This commit is contained in:
parent
6b0d5f9770
commit
8640e11728
|
@ -236,7 +236,7 @@ static void rtl_descent_start()
|
|||
rtl_state_complete = false;
|
||||
|
||||
// Set wp navigation target to above home
|
||||
wp_nav.set_loiter_target(Vector3f(0,0,0));
|
||||
wp_nav.set_loiter_target(wp_nav.get_wp_destination());
|
||||
|
||||
// initialise altitude target to stopping point
|
||||
pos_control.set_target_to_stopping_point_z();
|
||||
|
@ -295,7 +295,7 @@ static void rtl_land_start()
|
|||
rtl_state_complete = false;
|
||||
|
||||
// Set wp navigation target to above home
|
||||
wp_nav.set_loiter_target(Vector3f(0,0,0));
|
||||
wp_nav.set_loiter_target(wp_nav.get_wp_destination());
|
||||
|
||||
// initialise altitude target to stopping point
|
||||
pos_control.set_target_to_stopping_point_z();
|
||||
|
|
Loading…
Reference in New Issue