Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(behavior_velocity_run_out_module): exclude obstacle crossing ego… #1574

Merged
merged 1 commit into from
Oct 9, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions planning/behavior_velocity_run_out_module/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,14 @@ You can choose whether to use this feature by parameter of `use_partition_lanele

![brief](./docs/exclude_obstacles_by_partition.svg)

##### Exclude obstacles that cross the ego vehicle's "cut line"

This module can exclude obstacles that have predicted paths that will cross the back side of the ego vehicle. It excludes obstacles if their predicted path crosses the ego's "cut line". The "cut line" is a virtual line segment that is perpendicular to the ego vehicle and that passes through the ego's base link.

You can choose whether to use this feature by setting the parameter `use_ego_cut_line` to `true` or `false`. The width of the line can be tuned with the parameter `ego_cut_line_length`.

![brief](./docs/ego_cut_line.svg)

#### Collision detection

##### Detect collision with dynamic obstacles
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,14 @@
use_partition_lanelet: true # [-] whether to use partition lanelet map data
suppress_on_crosswalk: true # [-] whether to suppress on crosswalk lanelet:
specify_decel_jerk: false # [-] whether to specify jerk when ego decelerates
use_ego_cut_line: true # [-] filter obstacles that pass the backside of ego: if a dynamic obstacle's predicted path intersects this line, it is ignored
stop_margin: 2.5 # [m] the vehicle decelerates to be able to stop with this margin
passing_margin: 1.1 # [m] the vehicle begins to accelerate if the vehicle's front in predicted position is ahead of the obstacle + this margin
deceleration_jerk: -0.3 # [m/s^3] ego decelerates with this jerk when stopping for obstacles
detection_distance: 45.0 # [m] ahead distance from ego to detect the obstacles
detection_span: 1.0 # [m] calculate collision with this span to reduce calculation time
min_vel_ego_kmph: 3.6 # [km/h] min velocity to calculate time to collision
ego_cut_line_length: 3.0 # The width of the ego's cut line

detection_area:
margin_behind: 0.5 # [m] ahead margin for detection area length
Expand Down
129 changes: 129 additions & 0 deletions planning/behavior_velocity_run_out_module/docs/ego_cut_line.svg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
19 changes: 19 additions & 0 deletions planning/behavior_velocity_run_out_module/src/debug.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,14 @@ void RunOutDebug::pushCollisionPoints(const geometry_msgs::msg::Point & point)
collision_points_.push_back(point_with_height);
}

void RunOutDebug::pushEgoCutLine(const std::vector<geometry_msgs::msg::Point> & line)
{
for (const auto & point : line) {
const auto point_with_height = createPoint(point.x, point.y, height_);
ego_cut_line_.push_back(point_with_height);
}
}

void RunOutDebug::pushCollisionPoints(const std::vector<geometry_msgs::msg::Point> & points)
{
for (const auto & p : points) {
Expand Down Expand Up @@ -160,6 +168,7 @@ void RunOutDebug::clearDebugMarker()
predicted_obstacle_polygons_.clear();
collision_obstacle_polygons_.clear();
travel_time_texts_.clear();
ego_cut_line_.clear();
}

visualization_msgs::msg::MarkerArray RunOutDebug::createVisualizationMarkerArray()
Expand Down Expand Up @@ -265,6 +274,16 @@ visualization_msgs::msg::MarkerArray RunOutDebug::createVisualizationMarkerArray
&msg);
}

if (!ego_cut_line_.empty()) {
auto marker = createDefaultMarker(
"map", current_time, "ego_cut_line", 0, visualization_msgs::msg::Marker::LINE_LIST,
createMarkerScale(0.2, 0.2, 0.2), createMarkerColor(0.7, 0.0, 0.7, 0.999));
for (const auto & p : ego_cut_line_) {
marker.points.push_back(p);
}
msg.markers.push_back(marker);
}

if (!travel_time_texts_.empty()) {
auto marker = createDefaultMarker(
"map", current_time, "travel_time_texts", 0,
Expand Down
2 changes: 2 additions & 0 deletions planning/behavior_velocity_run_out_module/src/debug.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,6 +109,7 @@ class RunOutDebug
void pushPredictedVehiclePolygons(const std::vector<geometry_msgs::msg::Point> & polygon);
void pushPredictedObstaclePolygons(const std::vector<geometry_msgs::msg::Point> & polygon);
void pushCollisionObstaclePolygons(const std::vector<geometry_msgs::msg::Point> & polygon);
void pushEgoCutLine(const std::vector<geometry_msgs::msg::Point> & line);
void pushDetectionAreaPolygons(const Polygon2d & debug_polygon);
void pushMandatoryDetectionAreaPolygons(const Polygon2d & debug_polygon);
void pushTravelTimeTexts(
Expand All @@ -134,6 +135,7 @@ class RunOutDebug
rclcpp::Publisher<PointCloud2>::SharedPtr pub_debug_pointcloud_;
std::vector<geometry_msgs::msg::Point> collision_points_;
std::vector<geometry_msgs::msg::Point> nearest_collision_point_;
std::vector<geometry_msgs::msg::Point> ego_cut_line_;
std::vector<geometry_msgs::msg::Pose> stop_pose_;
std::vector<std::vector<geometry_msgs::msg::Point>> predicted_vehicle_polygons_;
std::vector<std::vector<geometry_msgs::msg::Point>> predicted_obstacle_polygons_;
Expand Down
2 changes: 2 additions & 0 deletions planning/behavior_velocity_run_out_module/src/manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,7 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node)
auto & p = planner_param_.run_out;
p.detection_method = getOrDeclareParameter<std::string>(node, ns + ".detection_method");
p.use_partition_lanelet = getOrDeclareParameter<bool>(node, ns + ".use_partition_lanelet");
p.use_ego_cut_line = getOrDeclareParameter<bool>(node, ns + ".use_ego_cut_line");
p.suppress_on_crosswalk = getOrDeclareParameter<bool>(node, ns + ".suppress_on_crosswalk");
p.specify_decel_jerk = getOrDeclareParameter<bool>(node, ns + ".specify_decel_jerk");
p.stop_margin = getOrDeclareParameter<double>(node, ns + ".stop_margin");
Expand All @@ -66,6 +67,7 @@ RunOutModuleManager::RunOutModuleManager(rclcpp::Node & node)
p.detection_distance = getOrDeclareParameter<double>(node, ns + ".detection_distance");
p.detection_span = getOrDeclareParameter<double>(node, ns + ".detection_span");
p.min_vel_ego_kmph = getOrDeclareParameter<double>(node, ns + ".min_vel_ego_kmph");
p.ego_cut_line_length = getOrDeclareParameter<double>(node, ns + ".ego_cut_line_length");
}

{
Expand Down
Loading
Loading