@@ -182,7 +182,7 @@ class CrosswalkModule : public SceneModuleInterface
182
182
const rclcpp::Time & now, const geometry_msgs::msg::Point & position, const double vel,
183
183
const bool is_ego_yielding, const std::optional<CollisionPoint> & collision_point,
184
184
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 )
186
186
{
187
187
const bool is_stopped = vel < planner_param.stop_object_velocity ;
188
188
@@ -202,7 +202,7 @@ class CrosswalkModule : public SceneModuleInterface
202
202
planner_param.timeout_set_for_no_intention_to_walk , distance_to_crosswalk);
203
203
const bool intent_to_cross =
204
204
(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 ) {
206
206
collision_state = CollisionState::IGNORE;
207
207
return ;
208
208
}
@@ -261,15 +261,16 @@ class CrosswalkModule : public SceneModuleInterface
261
261
// update current uuids
262
262
current_uuids_.push_back (uuid);
263
263
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 ;
267
268
268
269
// add new object
269
270
if (objects.count (uuid) == 0 ) {
270
271
if (
271
272
has_traffic_light && planner_param.disable_yield_for_new_stopped_object &&
272
- !is_object_on_ego_path ) {
273
+ is_object_away_from_path ) {
273
274
objects.emplace (uuid, ObjectInfo{CollisionState::IGNORE});
274
275
} else {
275
276
objects.emplace (uuid, ObjectInfo{CollisionState::YIELD});
@@ -279,7 +280,7 @@ class CrosswalkModule : public SceneModuleInterface
279
280
// update object state
280
281
objects.at (uuid).transitState (
281
282
now, position, vel, is_ego_yielding, collision_point, planner_param, crosswalk_polygon,
282
- is_object_on_ego_path );
283
+ is_object_away_from_path );
283
284
objects.at (uuid).collision_point = collision_point;
284
285
objects.at (uuid).position = position;
285
286
objects.at (uuid).classification = classification;
0 commit comments