diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index f834c8791a0..a35a1786bb4 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -861,6 +861,7 @@ void Costmap2DROS::getCostsCallback( pose_transformed.pose.position.y, mx, my); if (!in_bounds) { + response->success = false; response->costs.push_back(LETHAL_OBSTACLE); continue; }