Skip to content

Commit bd987a3

Browse files
authored
Merge pull request #1233 from maxime-clem/cherry-pick/out_of_lane
feat(out_of_lane): cherry-pick lane change bug fix + cut pred paths at red light
2 parents 4bef186 + a3ee6f4 commit bd987a3

10 files changed

+248
-52
lines changed

planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
# if false, assume the object moves at constant velocity along *all* lanelets it currently is located in.
1919
predicted_path_min_confidence : 0.1 # when using predicted paths, ignore the ones whose confidence is lower than this value.
2020
distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane
21+
cut_predicted_paths_beyond_red_lights: true # if true, predicted paths are cut beyond the stop line of red traffic lights
2122

2223
overlap:
2324
minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered

planning/behavior_velocity_out_of_lane_module/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727
<depend>tf2</depend>
2828
<depend>tier4_autoware_utils</depend>
2929
<depend>tier4_planning_msgs</depend>
30+
<depend>traffic_light_utils</depend>
3031
<depend>vehicle_info_util</depend>
3132
<depend>visualization_msgs</depend>
3233

planning/behavior_velocity_out_of_lane_module/src/decisions.cpp

+13-1
Original file line numberDiff line numberDiff line change
@@ -73,11 +73,13 @@ std::optional<std::pair<double, double>> object_time_to_range(
7373
if (!object_is_incoming(object_point, route_handler, range.lane)) return {};
7474

7575
const auto max_deviation = object.shape.dimensions.y + range.inside_distance + dist_buffer;
76+
const auto max_lon_deviation = object.shape.dimensions.x / 2.0;
7677
auto worst_enter_time = std::optional<double>();
7778
auto worst_exit_time = std::optional<double>();
7879

7980
for (const auto & predicted_path : object.kinematics.predicted_paths) {
8081
const auto unique_path_points = motion_utils::removeOverlapPoints(predicted_path.path);
82+
if (unique_path_points.size() < 2) continue;
8183
const auto time_step = rclcpp::Duration(predicted_path.time_step).seconds();
8284
const auto enter_point =
8385
geometry_msgs::msg::Point().set__x(range.entering_point.x()).set__y(range.entering_point.y());
@@ -121,7 +123,17 @@ std::optional<std::pair<double, double>> object_time_to_range(
121123
max_deviation);
122124
continue;
123125
}
124-
// else we rely on the interpolation to estimate beyond the end of the predicted path
126+
const auto is_last_predicted_path_point =
127+
(exit_segment_idx + 2 == unique_path_points.size() ||
128+
enter_segment_idx + 2 == unique_path_points.size());
129+
const auto does_not_reach_overlap =
130+
is_last_predicted_path_point && (std::min(exit_offset, enter_offset) > max_lon_deviation);
131+
if (does_not_reach_overlap) {
132+
RCLCPP_DEBUG(
133+
logger, " * does not reach the overlap = %2.2fm | max_dev = %2.2fm\n",
134+
std::min(exit_offset, enter_offset), max_lon_deviation);
135+
continue;
136+
}
125137

126138
const auto same_driving_direction_as_ego = enter_time < exit_time;
127139
if (same_driving_direction_as_ego) {
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,146 @@
1+
// Copyright 2023-2024 TIER IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "filter_predicted_objects.hpp"
16+
17+
#include <motion_utils/trajectory/trajectory.hpp>
18+
#include <traffic_light_utils/traffic_light_utils.hpp>
19+
20+
#include <boost/geometry/algorithms/intersects.hpp>
21+
22+
#include <lanelet2_core/geometry/LaneletMap.h>
23+
#include <lanelet2_core/primitives/BasicRegulatoryElements.h>
24+
25+
#include <algorithm>
26+
27+
namespace behavior_velocity_planner::out_of_lane
28+
{
29+
void cut_predicted_path_beyond_line(
30+
autoware_auto_perception_msgs::msg::PredictedPath & predicted_path,
31+
const lanelet::BasicLineString2d & stop_line, const double object_front_overhang)
32+
{
33+
auto stop_line_idx = 0UL;
34+
bool found = false;
35+
lanelet::BasicSegment2d path_segment;
36+
path_segment.first.x() = predicted_path.path.front().position.x;
37+
path_segment.first.y() = predicted_path.path.front().position.y;
38+
for (stop_line_idx = 1; stop_line_idx < predicted_path.path.size(); ++stop_line_idx) {
39+
path_segment.second.x() = predicted_path.path[stop_line_idx].position.x;
40+
path_segment.second.y() = predicted_path.path[stop_line_idx].position.y;
41+
if (boost::geometry::intersects(stop_line, path_segment)) {
42+
found = true;
43+
break;
44+
}
45+
path_segment.first = path_segment.second;
46+
}
47+
if (found) {
48+
auto cut_idx = stop_line_idx;
49+
double arc_length = 0;
50+
while (cut_idx > 0 && arc_length < object_front_overhang) {
51+
arc_length += tier4_autoware_utils::calcDistance2d(
52+
predicted_path.path[cut_idx], predicted_path.path[cut_idx - 1]);
53+
--cut_idx;
54+
}
55+
predicted_path.path.resize(cut_idx);
56+
}
57+
}
58+
59+
std::optional<const lanelet::BasicLineString2d> find_next_stop_line(
60+
const autoware_auto_perception_msgs::msg::PredictedPath & path, const PlannerData & planner_data)
61+
{
62+
lanelet::ConstLanelets lanelets;
63+
lanelet::BasicLineString2d query_line;
64+
for (const auto & p : path.path) query_line.emplace_back(p.position.x, p.position.y);
65+
const auto query_results = lanelet::geometry::findWithin2d(
66+
planner_data.route_handler_->getLaneletMapPtr()->laneletLayer, query_line);
67+
for (const auto & r : query_results) lanelets.push_back(r.second);
68+
for (const auto & ll : lanelets) {
69+
for (const auto & element : ll.regulatoryElementsAs<lanelet::TrafficLight>()) {
70+
const auto traffic_signal_stamped = planner_data.getTrafficSignal(element->id());
71+
if (
72+
traffic_signal_stamped.has_value() && element->stopLine().has_value() &&
73+
traffic_light_utils::isTrafficSignalStop(ll, traffic_signal_stamped.value().signal)) {
74+
lanelet::BasicLineString2d stop_line;
75+
for (const auto & p : *(element->stopLine())) stop_line.emplace_back(p.x(), p.y());
76+
return stop_line;
77+
}
78+
}
79+
}
80+
return std::nullopt;
81+
}
82+
83+
void cut_predicted_path_beyond_red_lights(
84+
autoware_auto_perception_msgs::msg::PredictedPath & predicted_path,
85+
const PlannerData & planner_data, const double object_front_overhang)
86+
{
87+
const auto stop_line = find_next_stop_line(predicted_path, planner_data);
88+
if (stop_line) {
89+
// we use a longer stop line to also cut predicted paths that slightly go around the stop line
90+
auto longer_stop_line = *stop_line;
91+
const auto diff = stop_line->back() - stop_line->front();
92+
longer_stop_line.front() -= diff * 0.5;
93+
longer_stop_line.back() += diff * 0.5;
94+
cut_predicted_path_beyond_line(predicted_path, longer_stop_line, object_front_overhang);
95+
}
96+
}
97+
98+
autoware_auto_perception_msgs::msg::PredictedObjects filter_predicted_objects(
99+
const PlannerData & planner_data, const EgoData & ego_data, const PlannerParam & params)
100+
{
101+
autoware_auto_perception_msgs::msg::PredictedObjects filtered_objects;
102+
filtered_objects.header = planner_data.predicted_objects->header;
103+
for (const auto & object : planner_data.predicted_objects->objects) {
104+
const auto is_pedestrian =
105+
std::find_if(object.classification.begin(), object.classification.end(), [](const auto & c) {
106+
return c.label == autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN;
107+
}) != object.classification.end();
108+
if (is_pedestrian) continue;
109+
110+
auto filtered_object = object;
111+
const auto is_invalid_predicted_path = [&](const auto & predicted_path) {
112+
const auto is_low_confidence = predicted_path.confidence < params.objects_min_confidence;
113+
const auto no_overlap_path = motion_utils::removeOverlapPoints(predicted_path.path);
114+
if (no_overlap_path.size() <= 1) return true;
115+
const auto lat_offset_to_current_ego =
116+
std::abs(motion_utils::calcLateralOffset(no_overlap_path, ego_data.pose.position));
117+
const auto is_crossing_ego =
118+
lat_offset_to_current_ego <=
119+
object.shape.dimensions.y / 2.0 + std::max(
120+
params.left_offset + params.extra_left_offset,
121+
params.right_offset + params.extra_right_offset);
122+
return is_low_confidence || is_crossing_ego;
123+
};
124+
if (params.objects_use_predicted_paths) {
125+
auto & predicted_paths = filtered_object.kinematics.predicted_paths;
126+
const auto new_end =
127+
std::remove_if(predicted_paths.begin(), predicted_paths.end(), is_invalid_predicted_path);
128+
predicted_paths.erase(new_end, predicted_paths.end());
129+
if (params.objects_cut_predicted_paths_beyond_red_lights)
130+
for (auto & predicted_path : predicted_paths)
131+
cut_predicted_path_beyond_red_lights(
132+
predicted_path, planner_data, filtered_object.shape.dimensions.x);
133+
predicted_paths.erase(
134+
std::remove_if(
135+
predicted_paths.begin(), predicted_paths.end(),
136+
[](const auto & p) { return p.path.empty(); }),
137+
predicted_paths.end());
138+
}
139+
140+
if (!params.objects_use_predicted_paths || !filtered_object.kinematics.predicted_paths.empty())
141+
filtered_objects.objects.push_back(filtered_object);
142+
}
143+
return filtered_objects;
144+
}
145+
146+
} // namespace behavior_velocity_planner::out_of_lane
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2023 TIER IV, Inc.
1+
// Copyright 2023-2024 TIER IV, Inc.
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -17,56 +17,41 @@
1717

1818
#include "types.hpp"
1919

20-
#include <motion_utils/trajectory/trajectory.hpp>
20+
#include <behavior_velocity_planner_common/planner_data.hpp>
2121

22-
#include <string>
22+
#include <optional>
2323

2424
namespace behavior_velocity_planner::out_of_lane
2525
{
26+
/// @brief cut a predicted path beyond the given stop line
27+
/// @param [inout] predicted_path predicted path to cut
28+
/// @param [in] stop_line stop line used for cutting
29+
/// @param [in] object_front_overhang extra distance to cut ahead of the stop line
30+
void cut_predicted_path_beyond_line(
31+
autoware_auto_perception_msgs::msg::PredictedPath & predicted_path,
32+
const lanelet::BasicLineString2d & stop_line, const double object_front_overhang);
33+
34+
/// @brief find the next red light stop line along the given path
35+
/// @param [in] path predicted path to check for a stop line
36+
/// @param [in] planner_data planner data with stop line information
37+
/// @return the first red light stop line found along the path (if any)
38+
std::optional<const lanelet::BasicLineString2d> find_next_stop_line(
39+
const autoware_auto_perception_msgs::msg::PredictedPath & path, const PlannerData & planner_data);
40+
41+
/// @brief cut predicted path beyond stop lines of red lights
42+
/// @param [inout] predicted_path predicted path to cut
43+
/// @param [in] planner_data planner data to get the map and traffic light information
44+
void cut_predicted_path_beyond_red_lights(
45+
autoware_auto_perception_msgs::msg::PredictedPath & predicted_path,
46+
const PlannerData & planner_data, const double object_front_overhang);
47+
2648
/// @brief filter predicted objects and their predicted paths
27-
/// @param [in] objects predicted objects to filter
49+
/// @param [in] planner_data planner data
2850
/// @param [in] ego_data ego data
2951
/// @param [in] params parameters
3052
/// @return filtered predicted objects
3153
autoware_auto_perception_msgs::msg::PredictedObjects filter_predicted_objects(
32-
const autoware_auto_perception_msgs::msg::PredictedObjects & objects, const EgoData & ego_data,
33-
const PlannerParam & params)
34-
{
35-
autoware_auto_perception_msgs::msg::PredictedObjects filtered_objects;
36-
filtered_objects.header = objects.header;
37-
for (const auto & object : objects.objects) {
38-
const auto is_pedestrian =
39-
std::find_if(object.classification.begin(), object.classification.end(), [](const auto & c) {
40-
return c.label == autoware_auto_perception_msgs::msg::ObjectClassification::PEDESTRIAN;
41-
}) != object.classification.end();
42-
if (is_pedestrian) continue;
43-
44-
auto filtered_object = object;
45-
const auto is_invalid_predicted_path = [&](const auto & predicted_path) {
46-
const auto is_low_confidence = predicted_path.confidence < params.objects_min_confidence;
47-
const auto no_overlap_path = motion_utils::removeOverlapPoints(predicted_path.path);
48-
if (no_overlap_path.size() <= 1) return true;
49-
const auto lat_offset_to_current_ego =
50-
std::abs(motion_utils::calcLateralOffset(no_overlap_path, ego_data.pose.position));
51-
const auto is_crossing_ego =
52-
lat_offset_to_current_ego <=
53-
object.shape.dimensions.y / 2.0 + std::max(
54-
params.left_offset + params.extra_left_offset,
55-
params.right_offset + params.extra_right_offset);
56-
return is_low_confidence || is_crossing_ego;
57-
};
58-
if (params.objects_use_predicted_paths) {
59-
auto & predicted_paths = filtered_object.kinematics.predicted_paths;
60-
const auto new_end =
61-
std::remove_if(predicted_paths.begin(), predicted_paths.end(), is_invalid_predicted_path);
62-
predicted_paths.erase(new_end, predicted_paths.end());
63-
}
64-
if (!params.objects_use_predicted_paths || !filtered_object.kinematics.predicted_paths.empty())
65-
filtered_objects.objects.push_back(filtered_object);
66-
}
67-
return filtered_objects;
68-
}
69-
54+
const PlannerData & planner_data, const EgoData & ego_data, const PlannerParam & params);
7055
} // namespace behavior_velocity_planner::out_of_lane
7156

7257
#endif // FILTER_PREDICTED_OBJECTS_HPP_

planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.cpp

+39-2
Original file line numberDiff line numberDiff line change
@@ -24,12 +24,47 @@
2424

2525
namespace behavior_velocity_planner::out_of_lane
2626
{
27+
28+
lanelet::ConstLanelets consecutive_lanelets(
29+
const route_handler::RouteHandler & route_handler, const lanelet::ConstLanelet & lanelet)
30+
{
31+
lanelet::ConstLanelets consecutives = route_handler.getRoutingGraphPtr()->following(lanelet);
32+
const auto previous = route_handler.getRoutingGraphPtr()->previous(lanelet);
33+
consecutives.insert(consecutives.end(), previous.begin(), previous.end());
34+
return consecutives;
35+
}
36+
37+
lanelet::ConstLanelets get_missing_lane_change_lanelets(
38+
lanelet::ConstLanelets & path_lanelets, const route_handler::RouteHandler & route_handler)
39+
{
40+
lanelet::ConstLanelets missing_lane_change_lanelets;
41+
const auto & routing_graph = *route_handler.getRoutingGraphPtr();
42+
lanelet::ConstLanelets adjacents;
43+
lanelet::ConstLanelets consecutives;
44+
for (const auto & ll : path_lanelets) {
45+
const auto consecutives_of_ll = consecutive_lanelets(route_handler, ll);
46+
std::copy_if(
47+
consecutives_of_ll.begin(), consecutives_of_ll.end(), std::back_inserter(consecutives),
48+
[&](const auto & l) { return !contains_lanelet(consecutives, l.id()); });
49+
const auto adjacents_of_ll = routing_graph.besides(ll);
50+
std::copy_if(
51+
adjacents_of_ll.begin(), adjacents_of_ll.end(), std::back_inserter(adjacents),
52+
[&](const auto & l) { return !contains_lanelet(adjacents, l.id()); });
53+
}
54+
std::copy_if(
55+
adjacents.begin(), adjacents.end(), std::back_inserter(missing_lane_change_lanelets),
56+
[&](const auto & l) {
57+
return !contains_lanelet(missing_lane_change_lanelets, l.id()) &&
58+
!contains_lanelet(path_lanelets, l.id()) && contains_lanelet(consecutives, l.id());
59+
});
60+
return missing_lane_change_lanelets;
61+
}
62+
2763
lanelet::ConstLanelets calculate_path_lanelets(
2864
const EgoData & ego_data, const route_handler::RouteHandler & route_handler)
2965
{
3066
const auto lanelet_map_ptr = route_handler.getLaneletMapPtr();
31-
lanelet::ConstLanelets path_lanelets =
32-
planning_utils::getLaneletsOnPath(ego_data.path, lanelet_map_ptr, ego_data.pose);
67+
lanelet::ConstLanelets path_lanelets;
3368
lanelet::BasicLineString2d path_ls;
3469
for (const auto & p : ego_data.path.points)
3570
path_ls.emplace_back(p.point.pose.position.x, p.point.pose.position.y);
@@ -38,6 +73,8 @@ lanelet::ConstLanelets calculate_path_lanelets(
3873
if (!contains_lanelet(path_lanelets, dist_lanelet.second.id()))
3974
path_lanelets.push_back(dist_lanelet.second);
4075
}
76+
const auto missing_lanelets = get_missing_lane_change_lanelets(path_lanelets, route_handler);
77+
path_lanelets.insert(path_lanelets.end(), missing_lanelets.begin(), missing_lanelets.end());
4178
return path_lanelets;
4279
}
4380

planning/behavior_velocity_out_of_lane_module/src/lanelets_selection.hpp

+7
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,13 @@ inline bool contains_lanelet(const lanelet::ConstLanelets & lanelets, const lane
4141
/// @return lanelets crossed by the ego vehicle
4242
lanelet::ConstLanelets calculate_path_lanelets(
4343
const EgoData & ego_data, const route_handler::RouteHandler & route_handler);
44+
/// @brief calculate lanelets that may not be crossed by the path but may be overlapped during a
45+
/// lane change
46+
/// @param [in] path_lanelets lanelets driven by the ego vehicle
47+
/// @param [in] route_handler route handler
48+
/// @return lanelets that may be overlapped by a lane change (and are not already in path_lanelets)
49+
lanelet::ConstLanelets get_missing_lane_change_lanelets(
50+
lanelet::ConstLanelets & path_lanelets, const route_handler::RouteHandler & route_handler);
4451
/// @brief calculate lanelets that should be ignored
4552
/// @param [in] ego_data data about the ego vehicle
4653
/// @param [in] path_lanelets lanelets driven by the ego vehicle

planning/behavior_velocity_out_of_lane_module/src/manager.cpp

+2
Original file line numberDiff line numberDiff line change
@@ -51,6 +51,8 @@ OutOfLaneModuleManager::OutOfLaneModuleManager(rclcpp::Node & node)
5151
pp.objects_min_confidence =
5252
getOrDeclareParameter<double>(node, ns + ".objects.predicted_path_min_confidence");
5353
pp.objects_dist_buffer = getOrDeclareParameter<double>(node, ns + ".objects.distance_buffer");
54+
pp.objects_cut_predicted_paths_beyond_red_lights =
55+
getOrDeclareParameter<bool>(node, ns + ".objects.cut_predicted_paths_beyond_red_lights");
5456

5557
pp.overlap_min_dist = getOrDeclareParameter<double>(node, ns + ".overlap.minimum_distance");
5658
pp.overlap_extra_length = getOrDeclareParameter<double>(node, ns + ".overlap.extra_length");

0 commit comments

Comments
 (0)