mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 00:33:56 -04:00
Copter: sanity check gps latlng
This commit is contained in:
parent
698017d0b1
commit
b433250da5
@ -1129,7 +1129,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
// y : lon
|
// y : lon
|
||||||
// z : alt
|
// z : alt
|
||||||
// sanity check location
|
// sanity check location
|
||||||
if (labs(packet.x) >= 900000000l || labs(packet.y) >= 1800000000l) {
|
if (!check_latlng(packet.x, packet.y)) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
Location roi_loc;
|
Location roi_loc;
|
||||||
@ -1244,7 +1244,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
// sanity check location
|
// sanity check location
|
||||||
if (fabsf(packet.param5) > 90.0f || fabsf(packet.param6) > 180.0f) {
|
if (!check_latlng(packet.param5, packet.param6)) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
Location new_home_loc;
|
Location new_home_loc;
|
||||||
@ -1274,7 +1274,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
// param6 : y / lon
|
// param6 : y / lon
|
||||||
// param7 : z / alt
|
// param7 : z / alt
|
||||||
// sanity check location
|
// sanity check location
|
||||||
if (fabsf(packet.param5) > 90.0f || fabsf(packet.param6) > 180.0f) {
|
if (!check_latlng(packet.param5, packet.param6)) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
Location roi_loc;
|
Location roi_loc;
|
||||||
@ -1784,6 +1784,11 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
Vector3f pos_ned;
|
Vector3f pos_ned;
|
||||||
|
|
||||||
if(!pos_ignore) {
|
if(!pos_ignore) {
|
||||||
|
// sanity check location
|
||||||
|
if (!check_latlng(packet.lat_int, packet.lon_int)) {
|
||||||
|
result = MAV_RESULT_FAILED;
|
||||||
|
break;
|
||||||
|
}
|
||||||
Location loc;
|
Location loc;
|
||||||
loc.lat = packet.lat_int;
|
loc.lat = packet.lat_int;
|
||||||
loc.lng = packet.lon_int;
|
loc.lng = packet.lon_int;
|
||||||
@ -1838,6 +1843,11 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
mavlink_hil_state_t packet;
|
mavlink_hil_state_t packet;
|
||||||
mavlink_msg_hil_state_decode(msg, &packet);
|
mavlink_msg_hil_state_decode(msg, &packet);
|
||||||
|
|
||||||
|
// sanity check location
|
||||||
|
if (!check_latlng(packet.lat, packet.lon)) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
// set gps hil sensor
|
// set gps hil sensor
|
||||||
Location loc;
|
Location loc;
|
||||||
loc.lat = packet.lat;
|
loc.lat = packet.lat;
|
||||||
@ -1961,6 +1971,11 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// sanity check location
|
||||||
|
if (!check_latlng(packet.lat, packet.lng)) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
RallyLocation rally_point;
|
RallyLocation rally_point;
|
||||||
rally_point.lat = packet.lat;
|
rally_point.lat = packet.lat;
|
||||||
rally_point.lng = packet.lng;
|
rally_point.lng = packet.lng;
|
||||||
@ -2022,7 +2037,7 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
copter.set_home_to_current_location_and_lock();
|
copter.set_home_to_current_location_and_lock();
|
||||||
} else {
|
} else {
|
||||||
// sanity check location
|
// sanity check location
|
||||||
if (labs(packet.latitude) > 90*10e7 || labs(packet.longitude) > 180 * 10e7) {
|
if (!check_latlng(packet.latitude, packet.longitude)) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
Location new_home_loc;
|
Location new_home_loc;
|
||||||
|
Loading…
Reference in New Issue
Block a user