Skip to content

Commit

Permalink
fix(crosswalk): fix calclation distance from the null polygons (#7122)
Browse files Browse the repository at this point in the history
Signed-off-by: Yuki Takagi <[email protected]>
  • Loading branch information
yuki-takagi-66 authored May 27, 2024
1 parent 177db15 commit 6dd2339
Showing 1 changed file with 8 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ class CrosswalkModule : public SceneModuleInterface
const rclcpp::Time & now, const geometry_msgs::msg::Point & position, const double vel,
const bool is_ego_yielding, const std::optional<CollisionPoint> & collision_point,
const PlannerParam & planner_param, const lanelet::BasicPolygon2d & crosswalk_polygon,
const bool is_object_on_ego_path)
const bool is_object_away_from_path)
{
const bool is_stopped = vel < planner_param.stop_object_velocity;

Expand All @@ -202,7 +202,7 @@ class CrosswalkModule : public SceneModuleInterface
planner_param.timeout_set_for_no_intention_to_walk, distance_to_crosswalk);
const bool intent_to_cross =
(now - *time_to_start_stopped).seconds() < timeout_no_intention_to_walk;
if (is_ego_yielding && !intent_to_cross && !is_object_on_ego_path) {
if (is_ego_yielding && !intent_to_cross && is_object_away_from_path) {
collision_state = CollisionState::IGNORE;
return;
}
Expand Down Expand Up @@ -261,15 +261,16 @@ class CrosswalkModule : public SceneModuleInterface
// update current uuids
current_uuids_.push_back(uuid);

const bool is_object_on_ego_path =
boost::geometry::distance(tier4_autoware_utils::fromMsg(position).to_2d(), attention_area) <
0.5;
const bool is_object_away_from_path =
!attention_area.outer().empty() &&
boost::geometry::distance(tier4_autoware_utils::fromMsg(position).to_2d(), attention_area) >
0.5;

// add new object
if (objects.count(uuid) == 0) {
if (
has_traffic_light && planner_param.disable_yield_for_new_stopped_object &&
!is_object_on_ego_path) {
is_object_away_from_path) {
objects.emplace(uuid, ObjectInfo{CollisionState::IGNORE});
} else {
objects.emplace(uuid, ObjectInfo{CollisionState::YIELD});
Expand All @@ -279,7 +280,7 @@ class CrosswalkModule : public SceneModuleInterface
// update object state
objects.at(uuid).transitState(
now, position, vel, is_ego_yielding, collision_point, planner_param, crosswalk_polygon,
is_object_on_ego_path);
is_object_away_from_path);
objects.at(uuid).collision_point = collision_point;
objects.at(uuid).position = position;
objects.at(uuid).classification = classification;
Expand Down

0 comments on commit 6dd2339

Please sign in to comment.