Skip to content

Commit 35e1dde

Browse files
fix(virtual traffic light): suppress lauch (#1290)
* suppress launch Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp> * add existence check Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp> --------- Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp> Co-authored-by: Shigekazu Fukuta <107168699+sfukuta@users.noreply.github.com>
1 parent 39fe090 commit 35e1dde

File tree

1 file changed

+21
-1
lines changed
  • planning/behavior_velocity_planner/src/scene_module/virtual_traffic_light

1 file changed

+21
-1
lines changed

planning/behavior_velocity_planner/src/scene_module/virtual_traffic_light/manager.cpp

+21-1
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,9 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
#include "tier4_autoware_utils/geometry/boost_geometry.hpp"
16+
17+
#include <lanelet2_extension/utility/utilities.hpp>
1518
#include <scene_module/virtual_traffic_light/manager.hpp>
1619
#include <tier4_autoware_utils/math/unit_conversion.hpp>
1720

@@ -81,11 +84,28 @@ VirtualTrafficLightModuleManager::VirtualTrafficLightModuleManager(rclcpp::Node
8184
void VirtualTrafficLightModuleManager::launchNewModules(
8285
const autoware_auto_planning_msgs::msg::PathWithLaneId & path)
8386
{
87+
tier4_autoware_utils::LineString2d ego_path_linestring;
88+
for (const auto & path_point : path.points) {
89+
ego_path_linestring.push_back(
90+
tier4_autoware_utils::fromMsg(path_point.point.pose.position).to_2d());
91+
}
92+
8493
for (const auto & m : getRegElemMapOnPath<VirtualTrafficLight>(
8594
path, planner_data_->route_handler_->getLaneletMapPtr())) {
95+
const auto stop_line_opt = m.first->getStopLine();
96+
if (!stop_line_opt) {
97+
RCLCPP_FATAL(
98+
logger_, "No stop line at virtual_traffic_light_reg_elem_id = %ld, please fix the map!",
99+
m.first->id());
100+
continue;
101+
}
102+
86103
// Use lanelet_id to unregister module when the route is changed
87104
const auto module_id = m.second.id();
88-
if (!isModuleRegistered(module_id)) {
105+
if (
106+
!isModuleRegistered(module_id) &&
107+
boost::geometry::intersects(
108+
ego_path_linestring, lanelet::utils::to2D(stop_line_opt.value()).basicLineString())) {
89109
registerModule(std::make_shared<VirtualTrafficLightModule>(
90110
module_id, *m.first, m.second, planner_param_,
91111
logger_.get_child("virtual_traffic_light_module"), clock_));

0 commit comments

Comments
 (0)