diff --git a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/pedestrian/follow_lane_action.hpp b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/pedestrian/follow_lane_action.hpp index 1327e2e0a08..36c44c6d665 100644 --- a/simulation/behavior_tree_plugin/include/behavior_tree_plugin/pedestrian/follow_lane_action.hpp +++ b/simulation/behavior_tree_plugin/include/behavior_tree_plugin/pedestrian/follow_lane_action.hpp @@ -19,6 +19,7 @@ #include #include +#include #include #include #include diff --git a/simulation/behavior_tree_plugin/src/pedestrian/follow_lane_action.cpp b/simulation/behavior_tree_plugin/src/pedestrian/follow_lane_action.cpp index a6ac7d67df0..6f4e7ad7e2f 100644 --- a/simulation/behavior_tree_plugin/src/pedestrian/follow_lane_action.cpp +++ b/simulation/behavior_tree_plugin/src/pedestrian/follow_lane_action.cpp @@ -53,22 +53,33 @@ bool FollowLaneAction::detectObstacleInLane( return false; } - auto hasObstacleInPedestrianLanes = [this](const lanelet::Ids pedestrian_lanes_local) { - lanelet::Ids other_entity_lane_ids; - for (const auto & [_, status] : other_entity_status) { - if (status.isInLanelet()) { + auto hasObstacleInPedestrianLanes = + [this](const lanelet::Ids pedestrian_lanes_local, const double max_detect_length) { + using math::geometry::operator-; + const auto & pedestrian_position = canonicalized_entity_status->getMapPose().position; + lanelet::Ids other_entity_lane_ids; + for (const auto & [_, status] : other_entity_status) { + if (status.getType().type != traffic_simulator_msgs::msg::EntityType::EGO) { + continue; + } + if (!status.isInLanelet()) { + continue; + } + const auto norm = math::geometry::norm(status.getMapPose().position - pedestrian_position); + if (!(norm < max_detect_length)) { + continue; + } other_entity_lane_ids.push_back(status.getLaneletId()); } - } - std::unordered_set other_lane_id_set( - other_entity_lane_ids.begin(), other_entity_lane_ids.end()); - for (const auto & pedestrian_lane : pedestrian_lanes_local) { - if (other_lane_id_set.count(pedestrian_lane)) { - return true; + std::unordered_set other_lane_id_set( + other_entity_lane_ids.begin(), other_entity_lane_ids.end()); + for (const auto & pedestrian_lane : pedestrian_lanes_local) { + if (other_lane_id_set.count(pedestrian_lane)) { + return true; + } } - } - return false; - }; + return false; + }; auto hasObstacleInFrontOfPedestrian = [this]() { using math::geometry::operator-; @@ -86,7 +97,7 @@ bool FollowLaneAction::detectObstacleInLane( return false; }; - if (hasObstacleInPedestrianLanes(pedestrian_lanes) && hasObstacleInFrontOfPedestrian()) { + if (hasObstacleInPedestrianLanes(pedestrian_lanes, 10) && hasObstacleInFrontOfPedestrian()) { return true; } else { return false;