mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Copter: bug fix for descent during loiter_turns
This commit is contained in:
parent
032cc513ca
commit
02b64e259d
@ -287,6 +287,7 @@ update_circle(float dt)
|
|||||||
// calculate target position
|
// calculate target position
|
||||||
circle_target.x = circle_center.x + cir_radius * cosf(-circle_angle);
|
circle_target.x = circle_center.x + cir_radius * cosf(-circle_angle);
|
||||||
circle_target.y = circle_center.y - cir_radius * sinf(-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
|
// re-use loiter position controller
|
||||||
wp_nav.set_loiter_target(circle_target);
|
wp_nav.set_loiter_target(circle_target);
|
||||||
|
Loading…
Reference in New Issue
Block a user