Skip to content

Commit

Permalink
Copter: initialize the land controller when starting the land phase o…
Browse files Browse the repository at this point in the history
…f an RTL

* ensures static variables for the landing ramp will be set properly on every landing
  • Loading branch information
wsilva32 committed Oct 3, 2016
1 parent 14268ad commit 313da4c
Showing 1 changed file with 3 additions and 0 deletions.
3 changes: 3 additions & 0 deletions ArduCopter/control_rtl.pde
Original file line number Diff line number Diff line change
Expand Up @@ -303,6 +303,9 @@ static void rtl_land_start()
rtl_state = Land;
rtl_state_complete = false;

// Setup land controller
land_init(false);

// Set wp navigation target to above home
wp_nav.init_loiter_target(wp_nav.get_wp_destination());

Expand Down

0 comments on commit 313da4c

Please sign in to comment.