Skip to content

Commit 49af265

Browse files
authored
fix(behavior_path_planner): fix turn signal endless loop (#5444)
Signed-off-by: kosuke55 <kosuke.tnp@gmail.com>
1 parent 2ee44a3 commit 49af265

File tree

1 file changed

+5
-19
lines changed

1 file changed

+5
-19
lines changed

planning/behavior_path_planner/src/turn_signal_decider.cpp

+5-19
Original file line numberDiff line numberDiff line change
@@ -165,30 +165,16 @@ boost::optional<TurnSignalInfo> TurnSignalDecider::getIntersectionTurnSignalInfo
165165
const std::string lane_attribute =
166166
current_lane.attributeOr("turn_direction", std::string("none"));
167167

168-
// check next lanes
169-
auto next_lanes = route_handler.getNextLanelets(current_lane);
170-
if (next_lanes.empty()) {
168+
// check next lane has the same attribute
169+
lanelet::ConstLanelet next_lane{};
170+
if (!route_handler.getNextLaneletWithinRoute(current_lane, &next_lane)) {
171171
break;
172172
}
173-
174-
// filter next lanes with same attribute in the path
175-
std::vector<lanelet::ConstLanelet> next_lanes_in_path{};
176-
std::copy_if(
177-
next_lanes.begin(), next_lanes.end(), std::back_inserter(next_lanes_in_path),
178-
[&](const auto & next_lane) {
179-
const bool is_in_unique_ids =
180-
std::find(unique_lane_ids.begin(), unique_lane_ids.end(), next_lane.id()) !=
181-
unique_lane_ids.end();
182-
const bool has_same_attribute =
183-
next_lane.attributeOr("turn_direction", std::string("none")) == lane_attribute;
184-
return is_in_unique_ids && has_same_attribute;
185-
});
186-
if (next_lanes_in_path.empty()) {
173+
if (next_lane.attributeOr("turn_direction", std::string("none")) != lane_attribute) {
187174
break;
188175
}
189176

190-
// assume that the next lane in the path is only one
191-
current_lane = next_lanes_in_path.front();
177+
current_lane = next_lane;
192178
}
193179

194180
if (!combined_lane_elems.empty()) {

0 commit comments

Comments
 (0)