mirror of https://github.com/ArduPilot/ardupilot
Plane: don't start summing for loiter until we reach loiter circle
This commit is contained in:
parent
f3638f421e
commit
d7d528560d
|
@ -34,7 +34,10 @@ void Plane::loiter_angle_update(void)
|
||||||
{
|
{
|
||||||
int32_t target_bearing_cd = nav_controller->target_bearing_cd();
|
int32_t target_bearing_cd = nav_controller->target_bearing_cd();
|
||||||
int32_t loiter_delta_cd;
|
int32_t loiter_delta_cd;
|
||||||
if (loiter.sum_cd == 0) {
|
if (loiter.sum_cd == 0 && !nav_controller->reached_loiter_target()) {
|
||||||
|
// we don't start summing until we are doing the real loiter
|
||||||
|
loiter_delta_cd = 0;
|
||||||
|
} else if (loiter.sum_cd == 0) {
|
||||||
// use 1 cd for initial delta
|
// use 1 cd for initial delta
|
||||||
loiter_delta_cd = 1;
|
loiter_delta_cd = 1;
|
||||||
} else {
|
} else {
|
||||||
|
|
Loading…
Reference in New Issue