ArduPlane: 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 c28c50babe
commit 2be84183b7
1 changed files with 2 additions and 1 deletions

View File

@ -476,8 +476,9 @@ void Plane::do_loiter_turns(const AP_Mission::Mission_Command& cmd)
cmdloc.sanitize(current_loc); cmdloc.sanitize(current_loc);
set_next_WP(cmdloc); set_next_WP(cmdloc);
loiter_set_direction_wp(cmd); loiter_set_direction_wp(cmd);
const float turns = cmd.get_loiter_turns();
loiter.total_cd = (uint32_t)(LOWBYTE(cmd.p1)) * 36000UL; loiter.total_cd = (uint32_t)(turns * 36000UL);
condition_value = 1; // used to signify primary turns goal not yet met condition_value = 1; // used to signify primary turns goal not yet met
} }