Browse Source

Mission: fix bounds checking of MISSION_ITEM lat/lon

mission-4.1.18
Michael du Breuil 9 years ago committed by Tom Pittenger
parent
commit
fb07b8c4cc
  1. 12
      libraries/AP_Mission/AP_Mission.cpp

12
libraries/AP_Mission/AP_Mission.cpp

@ -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
mav_cmd.x = packet.x * 1.0e7f; if (fabsf(packet.x) < 90.0f) {
mav_cmd.y = packet.y * 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;
} else {
return MAV_MISSION_INVALID_PARAM6_Y;
}
break; break;
} }

Loading…
Cancel
Save