Skip to content

Commit 7ac2439

Browse files
authored
feat(out_of_lane): more stable stop decisions (autowarefoundation#896)
* feat(out_of_lane): more stable decisions Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp> * Remove tf2_geometry_msg changes Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp> --------- Signed-off-by: Maxime CLEMENT <maxime.clement@tier4.jp>
1 parent 5ddb2e2 commit 7ac2439

12 files changed

+273
-91
lines changed

planning/behavior_velocity_out_of_lane_module/config/out_of_lane.param.yaml

+2
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717
use_predicted_paths: true # if true, use the predicted paths to estimate future positions.
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.
20+
distance_buffer: 1.0 # [m] distance buffer used to determine if a collision will occur in the other lane
2021

2122
overlap:
2223
minimum_distance: 0.0 # [m] minimum distance inside a lanelet for an overlap to be considered
@@ -26,6 +27,7 @@
2627
skip_if_over_max_decel: true # if true, do not take an action that would cause more deceleration than the maximum allowed
2728
precision: 0.1 # [m] precision when inserting a stop pose in the path
2829
distance_buffer: 1.5 # [m] buffer distance to try to keep between the ego footprint and lane
30+
min_duration: 1.0 # [s] minimum duration needed before a decision can be canceled
2931
slowdown:
3032
distance_threshold: 30.0 # [m] insert a slowdown when closer than this distance from an overlap
3133
velocity: 2.0 # [m/s] slowdown velocity

planning/behavior_velocity_out_of_lane_module/src/calculate_slowdown_points.hpp

+27-8
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,11 @@
2626
namespace behavior_velocity_planner::out_of_lane
2727
{
2828

29+
/// @brief estimate whether ego can decelerate without breaking the deceleration limit
30+
/// @details assume ego wants to reach the target point at the target velocity
31+
/// @param [in] ego_data ego data
32+
/// @param [in] point target point
33+
/// @param [in] target_vel target_velocity
2934
bool can_decelerate(
3035
const EgoData & ego_data, const PathPointWithLaneId & point, const double target_vel)
3136
{
@@ -37,9 +42,16 @@ bool can_decelerate(
3742
return acc_to_target_vel < std::abs(ego_data.max_decel);
3843
}
3944

45+
/// @brief calculate the last pose along the path where ego does not overlap the lane to avoid
46+
/// @param [in] ego_data ego data
47+
/// @param [in] decision the input decision (i.e., which lane to avoid and at what speed)
48+
/// @param [in] footprint the ego footprint
49+
/// @param [in] prev_slowdown_point previous slowdown point. If set, ignore deceleration limits
50+
/// @param [in] params parameters
51+
/// @return the last pose that is not out of lane (if found)
4052
std::optional<PathPointWithLaneId> calculate_last_in_lane_pose(
4153
const EgoData & ego_data, const Slowdown & decision, const Polygon2d & footprint,
42-
const PlannerParam & params)
54+
const std::optional<SlowdownToInsert> & prev_slowdown_point, const PlannerParam & params)
4355
{
4456
const auto from_arc_length =
4557
motion_utils::calcSignedArcLength(ego_data.path.points, 0, ego_data.first_path_idx);
@@ -50,12 +62,17 @@ std::optional<PathPointWithLaneId> calculate_last_in_lane_pose(
5062
// TODO(Maxime): binary search
5163
interpolated_point.point.pose = motion_utils::calcInterpolatedPose(ego_data.path.points, l);
5264
const auto respect_decel_limit =
53-
!params.skip_if_over_max_decel ||
65+
!params.skip_if_over_max_decel || prev_slowdown_point ||
5466
can_decelerate(ego_data, interpolated_point, decision.velocity);
55-
if (
56-
respect_decel_limit && !boost::geometry::overlaps(
57-
project_to_pose(footprint, interpolated_point.point.pose),
58-
decision.lane_to_avoid.polygon2d().basicPolygon()))
67+
const auto interpolated_footprint = project_to_pose(footprint, interpolated_point.point.pose);
68+
const auto is_overlap_lane = boost::geometry::overlaps(
69+
interpolated_footprint, decision.lane_to_avoid.polygon2d().basicPolygon());
70+
const auto is_overlap_extra_lane =
71+
prev_slowdown_point &&
72+
boost::geometry::overlaps(
73+
interpolated_footprint,
74+
prev_slowdown_point->slowdown.lane_to_avoid.polygon2d().basicPolygon());
75+
if (respect_decel_limit && !is_overlap_lane && !is_overlap_extra_lane)
5976
return interpolated_point;
6077
}
6178
return std::nullopt;
@@ -64,18 +81,20 @@ std::optional<PathPointWithLaneId> calculate_last_in_lane_pose(
6481
/// @brief calculate the slowdown point to insert in the path
6582
/// @param ego_data ego data (path, velocity, etc)
6683
/// @param decisions decision (before which point to stop, what lane to avoid entering, etc)
84+
/// @param prev_slowdown_point previously calculated slowdown point
6785
/// @param params parameters
6886
/// @return optional slowdown point to insert in the path
6987
std::optional<SlowdownToInsert> calculate_slowdown_point(
70-
const EgoData & ego_data, const std::vector<Slowdown> & decisions, PlannerParam params)
88+
const EgoData & ego_data, const std::vector<Slowdown> & decisions,
89+
const std::optional<SlowdownToInsert> prev_slowdown_point, PlannerParam params)
7190
{
7291
params.extra_front_offset += params.dist_buffer;
7392
const auto base_footprint = make_base_footprint(params);
7493

7594
// search for the first slowdown decision for which a stop point can be inserted
7695
for (const auto & decision : decisions) {
7796
const auto last_in_lane_pose =
78-
calculate_last_in_lane_pose(ego_data, decision, base_footprint, params);
97+
calculate_last_in_lane_pose(ego_data, decision, base_footprint, prev_slowdown_point, params);
7998
if (last_in_lane_pose) return SlowdownToInsert{decision, *last_in_lane_pose};
8099
}
81100
return std::nullopt;

planning/behavior_velocity_out_of_lane_module/src/debug.cpp

+83-4
Original file line numberDiff line numberDiff line change
@@ -32,13 +32,12 @@ visualization_msgs::msg::Marker get_base_marker()
3232
base_marker.pose.orientation = tier4_autoware_utils::createMarkerOrientation(0, 0, 0, 1.0);
3333
base_marker.scale = tier4_autoware_utils::createMarkerScale(0.1, 0.1, 0.1);
3434
base_marker.color = tier4_autoware_utils::createMarkerColor(1.0, 0.1, 0.1, 0.5);
35-
base_marker.lifetime = rclcpp::Duration::from_seconds(0.5);
3635
return base_marker;
3736
}
3837
} // namespace
3938
void add_footprint_markers(
4039
visualization_msgs::msg::MarkerArray & debug_marker_array,
41-
const lanelet::BasicPolygons2d & footprints, const double z)
40+
const lanelet::BasicPolygons2d & footprints, const double z, const size_t prev_nb)
4241
{
4342
auto debug_marker = get_base_marker();
4443
debug_marker.ns = "footprints";
@@ -52,12 +51,14 @@ void add_footprint_markers(
5251
debug_marker.id++;
5352
debug_marker.points.clear();
5453
}
54+
for (; debug_marker.id < static_cast<int>(prev_nb); ++debug_marker.id)
55+
debug_marker_array.markers.push_back(debug_marker);
5556
}
5657

5758
void add_current_overlap_marker(
5859
visualization_msgs::msg::MarkerArray & debug_marker_array,
5960
const lanelet::BasicPolygon2d & current_footprint,
60-
const lanelet::ConstLanelets & current_overlapped_lanelets, const double z)
61+
const lanelet::ConstLanelets & current_overlapped_lanelets, const double z, const size_t prev_nb)
6162
{
6263
auto debug_marker = get_base_marker();
6364
debug_marker.ns = "current_overlap";
@@ -80,12 +81,14 @@ void add_current_overlap_marker(
8081
debug_marker_array.markers.push_back(debug_marker);
8182
debug_marker.id++;
8283
}
84+
for (; debug_marker.id < static_cast<int>(prev_nb); ++debug_marker.id)
85+
debug_marker_array.markers.push_back(debug_marker);
8386
}
8487

8588
void add_lanelet_markers(
8689
visualization_msgs::msg::MarkerArray & debug_marker_array,
8790
const lanelet::ConstLanelets & lanelets, const std::string & ns,
88-
const std_msgs::msg::ColorRGBA & color)
91+
const std_msgs::msg::ColorRGBA & color, const size_t prev_nb)
8992
{
9093
auto debug_marker = get_base_marker();
9194
debug_marker.ns = ns;
@@ -101,6 +104,82 @@ void add_lanelet_markers(
101104
debug_marker_array.markers.push_back(debug_marker);
102105
debug_marker.id++;
103106
}
107+
debug_marker.action = debug_marker.DELETE;
108+
for (; debug_marker.id < static_cast<int>(prev_nb); ++debug_marker.id)
109+
debug_marker_array.markers.push_back(debug_marker);
110+
}
111+
112+
void add_range_markers(
113+
visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges,
114+
const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const size_t first_ego_idx,
115+
const double z, const size_t prev_nb)
116+
{
117+
auto debug_marker = get_base_marker();
118+
debug_marker.ns = "ranges";
119+
debug_marker.color = tier4_autoware_utils::createMarkerColor(0.2, 0.9, 0.1, 0.5);
120+
for (const auto & range : ranges) {
121+
debug_marker.points.clear();
122+
debug_marker.points.push_back(
123+
path.points[first_ego_idx + range.entering_path_idx].point.pose.position);
124+
debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition(
125+
range.entering_point.x(), range.entering_point.y(), z));
126+
for (const auto & overlap : range.debug.overlaps) {
127+
debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition(
128+
overlap.min_overlap_point.x(), overlap.min_overlap_point.y(), z));
129+
debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition(
130+
overlap.max_overlap_point.x(), overlap.max_overlap_point.y(), z));
131+
}
132+
debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition(
133+
range.exiting_point.x(), range.exiting_point.y(), z));
134+
debug_marker.points.push_back(
135+
path.points[first_ego_idx + range.exiting_path_idx].point.pose.position);
136+
debug_marker_array.markers.push_back(debug_marker);
137+
debug_marker.id++;
138+
}
139+
debug_marker.action = debug_marker.DELETE;
140+
for (; debug_marker.id < static_cast<int>(prev_nb); ++debug_marker.id)
141+
debug_marker_array.markers.push_back(debug_marker);
142+
debug_marker.action = debug_marker.ADD;
143+
debug_marker.id = 0;
144+
debug_marker.ns = "decisions";
145+
debug_marker.color = tier4_autoware_utils::createMarkerColor(0.9, 0.1, 0.1, 1.0);
146+
debug_marker.points.clear();
147+
for (const auto & range : ranges) {
148+
debug_marker.type = debug_marker.LINE_STRIP;
149+
if (range.debug.decision) {
150+
debug_marker.points.push_back(tier4_autoware_utils::createMarkerPosition(
151+
range.entering_point.x(), range.entering_point.y(), z));
152+
debug_marker.points.push_back(
153+
range.debug.object->kinematics.initial_pose_with_covariance.pose.position);
154+
}
155+
debug_marker_array.markers.push_back(debug_marker);
156+
debug_marker.points.clear();
157+
debug_marker.id++;
158+
159+
debug_marker.type = debug_marker.TEXT_VIEW_FACING;
160+
debug_marker.pose.position.x = range.entering_point.x();
161+
debug_marker.pose.position.y = range.entering_point.y();
162+
debug_marker.pose.position.z = z;
163+
std::stringstream ss;
164+
ss << "Ego: " << range.debug.times.ego.enter_time << " - " << range.debug.times.ego.exit_time
165+
<< "\n";
166+
if (range.debug.object) {
167+
debug_marker.pose.position.x +=
168+
range.debug.object->kinematics.initial_pose_with_covariance.pose.position.x;
169+
debug_marker.pose.position.y +=
170+
range.debug.object->kinematics.initial_pose_with_covariance.pose.position.y;
171+
debug_marker.pose.position.x /= 2;
172+
debug_marker.pose.position.y /= 2;
173+
ss << "Obj: " << range.debug.times.object.enter_time << " - "
174+
<< range.debug.times.object.exit_time << "\n";
175+
}
176+
debug_marker.scale.z = 1.0;
177+
debug_marker.text = ss.str();
178+
debug_marker_array.markers.push_back(debug_marker);
179+
debug_marker.id++;
180+
}
181+
for (; debug_marker.id < static_cast<int>(prev_nb); ++debug_marker.id)
182+
debug_marker_array.markers.push_back(debug_marker);
104183
}
105184

106185
} // namespace behavior_velocity_planner::out_of_lane::debug

planning/behavior_velocity_out_of_lane_module/src/debug.hpp

+17-3
Original file line numberDiff line numberDiff line change
@@ -29,27 +29,41 @@ namespace behavior_velocity_planner::out_of_lane::debug
2929
/// @param [inout] debug_marker_array marker array
3030
/// @param [in] footprints footprints to turn into markers
3131
/// @param [in] z z value to use for the markers
32+
/// @param [in] prev_nb previous number of markers (used to delete the extra ones)
3233
void add_footprint_markers(
3334
visualization_msgs::msg::MarkerArray & debug_marker_array,
34-
const lanelet::BasicPolygons2d & footprints, const double z);
35+
const lanelet::BasicPolygons2d & footprints, const double z, const size_t prev_nb);
3536
/// @brief add footprint markers to the given marker array
3637
/// @param [inout] debug_marker_array marker array
3738
/// @param [in] current_footprint footprint to turn into a marker
3839
/// @param [in] current_overlapped_lanelets lanelets to turn into markers
3940
/// @param [in] z z value to use for the markers
41+
/// @param [in] prev_nb previous number of markers (used to delete the extra ones)
4042
void add_current_overlap_marker(
4143
visualization_msgs::msg::MarkerArray & debug_marker_array,
4244
const lanelet::BasicPolygon2d & current_footprint,
43-
const lanelet::ConstLanelets & current_overlapped_lanelets, const double z);
45+
const lanelet::ConstLanelets & current_overlapped_lanelets, const double z, const size_t prev_nb);
4446
/// @brief add footprint markers to the given marker array
4547
/// @param [inout] debug_marker_array marker array
4648
/// @param [in] lanelets lanelets to turn into markers
4749
/// @param [in] ns namespace of the markers
4850
/// @param [in] color namespace of the markers
51+
/// @param [in] prev_nb previous number of markers (used to delete the extra ones)
4952
void add_lanelet_markers(
5053
visualization_msgs::msg::MarkerArray & debug_marker_array,
5154
const lanelet::ConstLanelets & lanelets, const std::string & ns,
52-
const std_msgs::msg::ColorRGBA & color);
55+
const std_msgs::msg::ColorRGBA & color, const size_t prev_nb);
56+
/// @brief add ranges markers to the given marker array
57+
/// @param [inout] debug_marker_array marker array
58+
/// @param [in] ranges ranges to turn into markers
59+
/// @param [in] path modified ego path that was used to calculate the ranges
60+
/// @param [in] first_path_idx first idx of ego on the path
61+
/// @param [in] z z value to use for the markers
62+
/// @param [in] prev_nb previous number of markers (used to delete the extra ones)
63+
void add_range_markers(
64+
visualization_msgs::msg::MarkerArray & debug_marker_array, const OverlapRanges & ranges,
65+
const autoware_auto_planning_msgs::msg::PathWithLaneId & path, const size_t first_path_idx,
66+
const double z, const size_t prev_nb);
5367
} // namespace behavior_velocity_planner::out_of_lane::debug
5468

5569
#endif // DEBUG_HPP_

planning/behavior_velocity_out_of_lane_module/src/decisions.cpp

+12-24
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717
#include <lanelet2_extension/utility/utilities.hpp>
1818

1919
#include <algorithm>
20-
#include <limits>
2120
#include <memory>
2221
#include <utility>
2322
#include <vector>
@@ -55,7 +54,8 @@ bool object_is_incoming(
5554

5655
std::optional<std::pair<double, double>> object_time_to_range(
5756
const autoware_auto_perception_msgs::msg::PredictedObject & object, const OverlapRange & range,
58-
const std::shared_ptr<route_handler::RouteHandler> route_handler, const rclcpp::Logger & logger)
57+
const std::shared_ptr<route_handler::RouteHandler> route_handler, const double dist_buffer,
58+
const rclcpp::Logger & logger)
5959
{
6060
// skip the dynamic object if it is not in a lane preceding the overlapped lane
6161
// lane changes are intentionally not considered
@@ -64,8 +64,7 @@ std::optional<std::pair<double, double>> object_time_to_range(
6464
object.kinematics.initial_pose_with_covariance.pose.position.y);
6565
if (!object_is_incoming(object_point, route_handler, range.lane)) return {};
6666

67-
const auto max_deviation = object.shape.dimensions.y + range.inside_distance;
68-
67+
const auto max_deviation = object.shape.dimensions.y + range.inside_distance + dist_buffer;
6968
auto worst_enter_time = std::optional<double>();
7069
auto worst_exit_time = std::optional<double>();
7170

@@ -300,7 +299,8 @@ bool should_not_enter(
300299
// skip objects that are already on the interval
301300
const auto enter_exit_time =
302301
params.objects_use_predicted_paths
303-
? object_time_to_range(object, range, inputs.route_handler, logger)
302+
? object_time_to_range(
303+
object, range, inputs.route_handler, params.objects_dist_buffer, logger)
304304
: object_time_to_range(object, range, inputs, logger);
305305
if (!enter_exit_time) {
306306
RCLCPP_DEBUG(logger, " SKIP (no enter/exit times found)\n");
@@ -309,27 +309,14 @@ bool should_not_enter(
309309

310310
range_times.object.enter_time = enter_exit_time->first;
311311
range_times.object.exit_time = enter_exit_time->second;
312-
if (will_collide_on_range(range_times, params, logger)) return true;
313-
}
314-
return false;
315-
}
316-
317-
OverlapRange find_most_preceding_range(const OverlapRange & range, const DecisionInputs & inputs)
318-
{
319-
OverlapRange preceding_range = range;
320-
bool found_preceding_range = true;
321-
while (found_preceding_range) {
322-
found_preceding_range = false;
323-
for (const auto & other_range : inputs.ranges) {
324-
if (
325-
other_range.entering_path_idx < preceding_range.entering_path_idx &&
326-
other_range.exiting_path_idx >= preceding_range.entering_path_idx) {
327-
preceding_range = other_range;
328-
found_preceding_range = true;
329-
}
312+
if (will_collide_on_range(range_times, params, logger)) {
313+
range.debug.times = range_times;
314+
range.debug.object = object;
315+
return true;
330316
}
331317
}
332-
return preceding_range;
318+
range.debug.times = range_times;
319+
return false;
333320
}
334321

335322
void set_decision_velocity(
@@ -367,6 +354,7 @@ std::vector<Slowdown> calculate_decisions(
367354
for (const auto & range : inputs.ranges) {
368355
if (range.entering_path_idx == 0UL) continue; // skip if we already entered the range
369356
const auto optional_decision = calculate_decision(range, inputs, params, logger);
357+
range.debug.decision = optional_decision;
370358
if (optional_decision) decisions.push_back(*optional_decision);
371359
}
372360
return decisions;

planning/behavior_velocity_out_of_lane_module/src/decisions.hpp

+3-19
Original file line numberDiff line numberDiff line change
@@ -30,16 +30,6 @@
3030

3131
namespace behavior_velocity_planner::out_of_lane
3232
{
33-
struct EnterExitTimes
34-
{
35-
double enter_time;
36-
double exit_time;
37-
};
38-
struct RangeTimes
39-
{
40-
EnterExitTimes ego;
41-
EnterExitTimes object;
42-
};
4333
/// @brief calculate the distance along the ego path between ego and some target path index
4434
/// @param [in] ego_data data related to the ego vehicle
4535
/// @param [in] target_idx target ego path index
@@ -63,13 +53,15 @@ double time_along_path(const EgoData & ego_data, const size_t target_idx);
6353
/// the opposite direction, time at enter > time at exit
6454
std::optional<std::pair<double, double>> object_time_to_range(
6555
const autoware_auto_perception_msgs::msg::PredictedObject & object, const OverlapRange & range,
66-
const std::shared_ptr<route_handler::RouteHandler> route_handler, const rclcpp::Logger & logger);
56+
const std::shared_ptr<route_handler::RouteHandler> route_handler, const double dist_buffer,
57+
const rclcpp::Logger & logger);
6758
/// @brief use the lanelet map to estimate the times when an object will reach the enter and exit
6859
/// points of an overlapping range
6960
/// @param [in] object dynamic object
7061
/// @param [in] range overlapping range
7162
/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route
7263
/// handler, lanelets)
64+
/// @param [in] dist_buffer extra distance used to estimate if a collision will occur on the range
7365
/// @param [in] logger ros logger
7466
/// @return an optional pair (time at enter [s], time at exit [s]). If the dynamic object drives in
7567
/// the opposite direction, time at enter > time at exit.
@@ -93,14 +85,6 @@ bool will_collide_on_range(
9385
bool should_not_enter(
9486
const OverlapRange & range, const DecisionInputs & inputs, const PlannerParam & params,
9587
const rclcpp::Logger & logger);
96-
/// @brief find the most preceding range
97-
/// @details the most preceding range is the first range in a succession of ranges with overlapping
98-
/// enter/exit indexes.
99-
/// @param [in] range range
100-
/// @param [in] inputs information used to take decisions (ranges, ego and objects data, route
101-
/// handler, lanelets)
102-
/// @return most preceding range
103-
OverlapRange find_most_preceding_range(const OverlapRange & range, const DecisionInputs & inputs);
10488
/// @brief set the velocity of a decision (or unset it) based on the distance away from the range
10589
/// @param [out] decision decision to update (either set its velocity or unset the decision)
10690
/// @param [in] distance distance between ego and the range corresponding to the decision

0 commit comments

Comments
 (0)