mirror of https://github.com/ArduPilot/ardupilot
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:
parent
c28c50babe
commit
2be84183b7
|
@ -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
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue