Browse Source

AP_Landing: Leverage new nav_controller loiter radius interface

master
Michael du Breuil 8 years ago committed by Andrew Tridgell
parent
commit
a0cb34db57
  1. 6
      libraries/AP_Landing/AP_Landing_Deepstall.cpp

6
libraries/AP_Landing/AP_Landing_Deepstall.cpp

@ -375,9 +375,11 @@ void AP_Landing_Deepstall::build_approach_path(void) @@ -375,9 +375,11 @@ void AP_Landing_Deepstall::build_approach_path(void)
memcpy(&arc, &arc_exit, sizeof(Location));
memcpy(&arc_entry, &arc_exit, sizeof(Location));
float loiter_radius = landing.nav_controller->loiter_radius(landing.aparm.loiter_radius);
// TODO: Support loitering on either side of the approach path
location_update(arc, target_heading_deg + 90.0, landing.aparm.loiter_radius);
location_update(arc_entry, target_heading_deg + 90.0, landing.aparm.loiter_radius * 2);
location_update(arc, target_heading_deg + 90.0, loiter_radius);
location_update(arc_entry, target_heading_deg + 90.0, loiter_radius * 2);
#ifdef DEBUG_PRINTS
// TODO: Send this information via a MAVLink packet

Loading…
Cancel
Save