diff --git a/planning/behavior_path_dynamic_avoidance_module/README.md b/planning/behavior_path_dynamic_avoidance_module/README.md index f95587daf3976..7c9c58cd2cf81 100644 --- a/planning/behavior_path_dynamic_avoidance_module/README.md +++ b/planning/behavior_path_dynamic_avoidance_module/README.md @@ -32,7 +32,7 @@ The other, _can be avoided_ denotes whether it can be avoided without risk to th For this purpose, the module judges whether the obstacle can be avoided with satisfying the constraints of lateral acceleration and lateral jerk. For example, the module decides not to avoid an object that is too close or fast in the lateral direction. -### Cuts off the drivable area against the selected obstacles +### Cuts off the drivable area against the selected vehicless For the selected obstacles to be avoided, the module cuts off the drivable area. As inputs to decide the shapes of cut-off polygons, poses of the obstacles are mainly used, assuming they move in parallel to the ego's path, instead of its predicted path. This design arises from that the predicted path of objects is not accurate enough to use the path modifications (at least currently). @@ -46,7 +46,7 @@ We can limit the lateral shift length by `drivable_area_generation.max_lat_offse ![drivable_area_extraction_width](./image/drivable_area_extraction_width.drawio.svg) #### Determination of longitudinal dimension -Then, extracting the same directional and opposite directional obstacles from the drivable area will work as follows, considering TTC (time to collision). +Then, extracting the same directional and opposite directional obstacles from the drivable area will work as follows considering TTC (time to collision). Regarding the same directional obstacles, obstacles whose TTC is negative will be ignored (e.g., The obstacle is in front of the ego, and the obstacle's velocity is larger than the ego's velocity.). @@ -57,7 +57,22 @@ Opposite directional obstacles (Parameter names may differ from implementation) ![opposite_directional_object](./image/opposite_directional_object.svg) ### Cuts off the drivable area against the selected pedestrians -while the +Then, we describe the logic to generate the drivable areas against pedestrians to be avoided. +Objects of this type are considered to have priority right of way over the ego's vehicle while ensuring a minimum safety of the ego's vehicle. +In other words, the module assigns a drivable area to an obstacle with a specific margin based on the predicted paths with specific confidences for a specific time interval, as shown in the following figure. +
+ +
Drivable areas are generated from each pedestrian's predicted paths
+
+ +Apart from polygons for objects, the module also generates another polygon to ensure the ego's safety, i.e., to avoid abrupt steering or significant changes from the path. +This is similar to avoidance against the vehicles and takes precedence over keeping a safe distance from the object to be avoided. +As a result, as shown in the figure below, the polygons around the objects reduced by the secured polygon of the ego are subtracted from the ego's drivable area. +
+ +
Drivable areas are generated from each pedestrian's predicted paths
+
+ ## Example @@ -82,6 +97,7 @@ while the ## Future works + Currently, the path shifting length is limited to 0.5 meters or less by `drivable_area_generation.max_lat_offset_to_avoid`. This is caused by the lack of functionality to work with other modules and the structure of the planning component. Due to this issue, this module can only handle situations where a small avoidance width is sufficient. diff --git a/planning/behavior_path_dynamic_avoidance_module/src/manager.cpp b/planning/behavior_path_dynamic_avoidance_module/src/manager.cpp index cc92c41f02286..baa1c631df8da 100644 --- a/planning/behavior_path_dynamic_avoidance_module/src/manager.cpp +++ b/planning/behavior_path_dynamic_avoidance_module/src/manager.cpp @@ -99,8 +99,8 @@ void DynamicAvoidanceModuleManager::init(rclcpp::Node * node) node->declare_parameter(ns + "crossing_object.min_oncoming_object_vel"); p.max_oncoming_crossing_object_angle = node->declare_parameter(ns + "crossing_object.max_oncoming_object_angle"); - p.max_pedestrians_crossing_vel = - node->declare_parameter(ns + "crossing_object.max_pedestrians_crossing_vel"); + p.max_pedestrian_crossing_vel = + node->declare_parameter(ns + "crossing_object.max_pedestrian_crossing_vel"); p.max_stopped_object_vel = node->declare_parameter(ns + "stopped_object.max_object_vel"); @@ -223,8 +223,8 @@ void DynamicAvoidanceModuleManager::updateModuleParams( parameters, ns + "crossing_object.max_oncoming_object_angle", p->max_oncoming_crossing_object_angle); updateParam( - parameters, ns + "crossing_object.max_pedestrians_crossing_vel", - p->max_pedestrians_crossing_vel); + parameters, ns + "crossing_object.max_pedestrian_crossing_vel", + p->max_pedestrian_crossing_vel); updateParam( parameters, ns + "stopped_object.max_object_vel", p->max_stopped_object_vel);