Copter: sanity check do-set-home and do-set-ROI location

This commit is contained in:
Randy Mackay 2015-08-27 14:38:55 +09:00
parent 13e360df08
commit 3ee88112cf
1 changed files with 8 additions and 0 deletions

View File

@ -1211,6 +1211,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
result = MAV_RESULT_ACCEPTED;
}
} else {
// sanity check location
if (fabsf(packet.param5) > 90.0f || fabsf(packet.param6) > 180.0f) {
break;
}
Location new_home_loc;
new_home_loc.lat = (int32_t)(packet.param5 * 1.0e7f);
new_home_loc.lng = (int32_t)(packet.param6 * 1.0e7f);
@ -1237,6 +1241,10 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// param5 : x / lat
// param6 : y / lon
// param7 : z / alt
// sanity check location
if (fabsf(packet.param5) > 90.0f || fabsf(packet.param6) > 180.0f) {
break;
}
Location roi_loc;
roi_loc.lat = (int32_t)(packet.param5 * 1.0e7f);
roi_loc.lng = (int32_t)(packet.param6 * 1.0e7f);