ArduCopter: fractional Loiter Turn Support

Adds special storage handling for loiter turns. Fractional Loiter
Turns 0<N<1 are stored by multiplying the turn number by 256, then
dividing that number by 256 on retrieval.
This commit is contained in:
J.R. Bronkar 2024-01-12 15:14:19 +11:00 committed by Tom Pittenger
parent 784a21bcab
commit c28c50babe
1 changed files with 3 additions and 1 deletions

View File

@ -2190,8 +2190,10 @@ bool ModeAuto::verify_circle(const AP_Mission::Mission_Command& cmd)
return false;
}
const float turns = cmd.get_loiter_turns();
// check if we have completed circling
return fabsf(copter.circle_nav->get_angle_total()/float(M_2PI)) >= LOWBYTE(cmd.p1);
return fabsf(copter.circle_nav->get_angle_total()/float(M_2PI)) >= turns;
}
// verify_spline_wp - check if we have reached the next way point using spline