mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Mission: fix bounds checking of MISSION_ITEM lat/lon
This commit is contained in:
parent
41bb237799
commit
fb07b8c4cc
@ -859,8 +859,16 @@ MAV_MISSION_RESULT AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item
|
|||||||
default:
|
default:
|
||||||
// all other commands use x and y as lat/lon. We need to
|
// all other commands use x and y as lat/lon. We need to
|
||||||
// multiply by 1e7 to convert to int32_t
|
// multiply by 1e7 to convert to int32_t
|
||||||
|
if (fabsf(packet.x) < 90.0f) {
|
||||||
mav_cmd.x = packet.x * 1.0e7f;
|
mav_cmd.x = packet.x * 1.0e7f;
|
||||||
|
} else {
|
||||||
|
return MAV_MISSION_INVALID_PARAM5_X;
|
||||||
|
}
|
||||||
|
if (fabsf(packet.y) < 180.0f) {
|
||||||
mav_cmd.y = packet.y * 1.0e7f;
|
mav_cmd.y = packet.y * 1.0e7f;
|
||||||
|
} else {
|
||||||
|
return MAV_MISSION_INVALID_PARAM6_Y;
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user