GCS_MAVLink: validate vertex count before assignment

this assignments following these lines were silently truncating the param1 value to uint8_t value
This commit is contained in:
Peter Barker 2024-11-21 10:26:58 +11:00 committed by Peter Barker
parent e19636e4ad
commit 650b9784a0
1 changed files with 6 additions and 0 deletions

View File

@ -110,10 +110,16 @@ MAV_MISSION_RESULT MissionItemProtocol_Fence::convert_MISSION_ITEM_INT_to_AC_Pol
switch (mission_item_int.command) { switch (mission_item_int.command) {
case MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION: case MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION:
ret.type = AC_PolyFenceType::POLYGON_INCLUSION; ret.type = AC_PolyFenceType::POLYGON_INCLUSION;
if (mission_item_int.param1 > 255) {
return MAV_MISSION_INVALID_PARAM1;
}
ret.vertex_count = mission_item_int.param1; ret.vertex_count = mission_item_int.param1;
break; break;
case MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION: case MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION:
ret.type = AC_PolyFenceType::POLYGON_EXCLUSION; ret.type = AC_PolyFenceType::POLYGON_EXCLUSION;
if (mission_item_int.param1 > 255) {
return MAV_MISSION_INVALID_PARAM1;
}
ret.vertex_count = mission_item_int.param1; ret.vertex_count = mission_item_int.param1;
break; break;
case MAV_CMD_NAV_FENCE_RETURN_POINT: case MAV_CMD_NAV_FENCE_RETURN_POINT: