mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
Rover: 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
6ffdfd9f48
commit
1ec61c57ba
@ -945,8 +945,9 @@ bool ModeAuto::do_circle(const AP_Mission::Mission_Command& cmd)
|
|||||||
|
|
||||||
bool ModeAuto::verify_circle(const AP_Mission::Mission_Command& cmd)
|
bool ModeAuto::verify_circle(const AP_Mission::Mission_Command& cmd)
|
||||||
{
|
{
|
||||||
|
const float turns = cmd.get_loiter_turns();
|
||||||
// check if we have completed circling
|
// check if we have completed circling
|
||||||
return ((g2.mode_circle.get_angle_total_rad() / M_2PI) >= LOWBYTE(cmd.p1));
|
return ((g2.mode_circle.get_angle_total_rad() / M_2PI) >= turns);
|
||||||
}
|
}
|
||||||
|
|
||||||
/********************************************************************************/
|
/********************************************************************************/
|
||||||
|
Loading…
Reference in New Issue
Block a user