From 650b9784a0a8dd5fae1e98b7ad75b6922df4cac6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 21 Nov 2024 10:26:58 +1100 Subject: [PATCH] GCS_MAVLink: validate vertex count before assignment this assignments following these lines were silently truncating the param1 value to uint8_t value --- libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp index aea6d20933..fdb3d11e6c 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Fence.cpp @@ -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: