Copter: bug fix for descent during loiter_turns

This commit is contained in:
Randy Mackay 2013-07-15 20:44:18 +09:00
parent 032cc513ca
commit 02b64e259d
1 changed files with 1 additions and 0 deletions

View File

@ -287,6 +287,7 @@ update_circle(float dt)
// calculate target position
circle_target.x = circle_center.x + cir_radius * cosf(-circle_angle);
circle_target.y = circle_center.y - cir_radius * sinf(-circle_angle);
circle_target.z = wp_nav.get_desired_alt();
// re-use loiter position controller
wp_nav.set_loiter_target(circle_target);