AP_Mission: improved handling of large LOITER_TURNS

instead of wrapping we should use MIN with 255, which is closer to
what was requested
This commit is contained in:
Andrew Tridgell 2022-05-10 19:27:12 +10:00 committed by Randy Mackay
parent 7a2d48389c
commit 6bf9556612
1 changed files with 2 additions and 2 deletions

View File

@ -920,8 +920,8 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
break; break;
case MAV_CMD_NAV_LOITER_TURNS: { // MAV ID: 18 case MAV_CMD_NAV_LOITER_TURNS: { // MAV ID: 18
uint16_t num_turns = packet.param1; // param 1 is number of times to circle is held in low p1 uint16_t num_turns = MIN(255,packet.param1); // param 1 is number of times to circle is held in low p1
uint16_t radius_m = fabsf(packet.param3); // param 3 is radius in meters is held in high p1 uint16_t radius_m = MIN(255,fabsf(packet.param3)); // param 3 is radius in meters is held in high p1
cmd.p1 = (radius_m<<8) | (num_turns & 0x00FF); // store radius in high byte of p1, num turns in low byte of p1 cmd.p1 = (radius_m<<8) | (num_turns & 0x00FF); // store radius in high byte of p1, num turns in low byte of p1
cmd.content.location.loiter_ccw = (packet.param3 < 0); cmd.content.location.loiter_ccw = (packet.param3 < 0);
cmd.content.location.loiter_xtrack = (packet.param4 > 0); // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location cmd.content.location.loiter_xtrack = (packet.param4 > 0); // 0 to xtrack from center of waypoint, 1 to xtrack from tangent exit location