Skip to content

Commit 6dd2339

Browse files
fix(crosswalk): fix calclation distance from the null polygons (#7122)
Signed-off-by: Yuki Takagi <yuki.takagi@tier4.jp>
1 parent 177db15 commit 6dd2339

File tree

1 file changed

+8
-7
lines changed

1 file changed

+8
-7
lines changed

planning/behavior_velocity_crosswalk_module/src/scene_crosswalk.hpp

+8-7
Original file line numberDiff line numberDiff line change
@@ -182,7 +182,7 @@ class CrosswalkModule : public SceneModuleInterface
182182
const rclcpp::Time & now, const geometry_msgs::msg::Point & position, const double vel,
183183
const bool is_ego_yielding, const std::optional<CollisionPoint> & collision_point,
184184
const PlannerParam & planner_param, const lanelet::BasicPolygon2d & crosswalk_polygon,
185-
const bool is_object_on_ego_path)
185+
const bool is_object_away_from_path)
186186
{
187187
const bool is_stopped = vel < planner_param.stop_object_velocity;
188188

@@ -202,7 +202,7 @@ class CrosswalkModule : public SceneModuleInterface
202202
planner_param.timeout_set_for_no_intention_to_walk, distance_to_crosswalk);
203203
const bool intent_to_cross =
204204
(now - *time_to_start_stopped).seconds() < timeout_no_intention_to_walk;
205-
if (is_ego_yielding && !intent_to_cross && !is_object_on_ego_path) {
205+
if (is_ego_yielding && !intent_to_cross && is_object_away_from_path) {
206206
collision_state = CollisionState::IGNORE;
207207
return;
208208
}
@@ -261,15 +261,16 @@ class CrosswalkModule : public SceneModuleInterface
261261
// update current uuids
262262
current_uuids_.push_back(uuid);
263263

264-
const bool is_object_on_ego_path =
265-
boost::geometry::distance(tier4_autoware_utils::fromMsg(position).to_2d(), attention_area) <
266-
0.5;
264+
const bool is_object_away_from_path =
265+
!attention_area.outer().empty() &&
266+
boost::geometry::distance(tier4_autoware_utils::fromMsg(position).to_2d(), attention_area) >
267+
0.5;
267268

268269
// add new object
269270
if (objects.count(uuid) == 0) {
270271
if (
271272
has_traffic_light && planner_param.disable_yield_for_new_stopped_object &&
272-
!is_object_on_ego_path) {
273+
is_object_away_from_path) {
273274
objects.emplace(uuid, ObjectInfo{CollisionState::IGNORE});
274275
} else {
275276
objects.emplace(uuid, ObjectInfo{CollisionState::YIELD});
@@ -279,7 +280,7 @@ class CrosswalkModule : public SceneModuleInterface
279280
// update object state
280281
objects.at(uuid).transitState(
281282
now, position, vel, is_ego_yielding, collision_point, planner_param, crosswalk_polygon,
282-
is_object_on_ego_path);
283+
is_object_away_from_path);
283284
objects.at(uuid).collision_point = collision_point;
284285
objects.at(uuid).position = position;
285286
objects.at(uuid).classification = classification;

0 commit comments

Comments
 (0)