mirror of https://github.com/ArduPilot/ardupilot
ArduSub: 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:
parent
2be84183b7
commit
6ffdfd9f48
|
@ -539,9 +539,10 @@ bool Sub::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(sub.circle_nav.get_angle_total()/M_2PI) >= LOWBYTE(cmd.p1);
|
||||
return fabsf(sub.circle_nav.get_angle_total()/M_2PI) >= turns;
|
||||
}
|
||||
|
||||
#if NAV_GUIDED == ENABLED
|
||||
|
|
Loading…
Reference in New Issue