Skip to content

Commit

Permalink
GCS_MAVLink: validate vertex count before assignment
Browse files Browse the repository at this point in the history
this assignments following these lines were silently truncating the param1 value to uint8_t value
  • Loading branch information
peterbarker committed Nov 25, 2024
1 parent e19636e commit 650b978
Showing 1 changed file with 6 additions and 0 deletions.
6 changes: 6 additions & 0 deletions libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -110,10 +110,16 @@ MAV_MISSION_RESULT MissionItemProtocol_Fence::convert_MISSION_ITEM_INT_to_AC_Pol
switch (mission_item_int.command) {
case MAV_CMD_NAV_FENCE_POLYGON_VERTEX_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;
break;
case MAV_CMD_NAV_FENCE_POLYGON_VERTEX_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;
break;
case MAV_CMD_NAV_FENCE_RETURN_POINT:
Expand Down

0 comments on commit 650b978

Please sign in to comment.