mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduSub: support *10 multipler when storing/retrieving radius in NAV_LOITER_TURNS
This commit is contained in:
parent
3bf0a21887
commit
317457ec1a
@ -353,7 +353,10 @@ void Sub::do_circle(const AP_Mission::Mission_Command& cmd)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// calculate radius
|
// calculate radius
|
||||||
uint8_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1
|
uint16_t circle_radius_m = HIGHBYTE(cmd.p1); // circle radius held in high byte of p1
|
||||||
|
if (cmd.type_specific_bits & (1U << 0)) {
|
||||||
|
circle_radius_m *= 10;
|
||||||
|
}
|
||||||
|
|
||||||
// move to edge of circle (verify_circle) will ensure we begin circling once we reach the edge
|
// move to edge of circle (verify_circle) will ensure we begin circling once we reach the edge
|
||||||
auto_circle_movetoedge_start(circle_center, circle_radius_m);
|
auto_circle_movetoedge_start(circle_center, circle_radius_m);
|
||||||
|
Loading…
Reference in New Issue
Block a user