Skip to content

Commit

Permalink
feat(crosswalk): add interset makers (autowarefoundation#5967)
Browse files Browse the repository at this point in the history
add interest makers

Signed-off-by: Yuki Takagi <[email protected]>
  • Loading branch information
yuki-takagi-66 authored Dec 27, 2023
1 parent 4e0503b commit 2eb8dfb
Show file tree
Hide file tree
Showing 2 changed files with 25 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -873,7 +873,7 @@ Polygon2d CrosswalkModule::getAttentionArea(
std::optional<StopFactor> CrosswalkModule::checkStopForStuckVehicles(
const PathWithLaneId & ego_path, const std::vector<PredictedObject> & objects,
const std::vector<geometry_msgs::msg::Point> & path_intersects,
const std::optional<geometry_msgs::msg::Pose> & stop_pose) const
const std::optional<geometry_msgs::msg::Pose> & stop_pose)
{
const auto & p = planner_param_;

Expand Down Expand Up @@ -938,6 +938,10 @@ std::optional<StopFactor> CrosswalkModule::checkStopForStuckVehicles(
continue;
}

setObjectsOfInterestData(
object.kinematics.initial_pose_with_covariance.pose, object.shape, ColorName::RED);

// early return may not appropriate because the nearest in range object should be handled
return createStopFactor(*feasible_stop_pose, {obj_pos});
}
}
Expand Down Expand Up @@ -1018,11 +1022,29 @@ void CrosswalkModule::updateObjectState(
has_traffic_light, collision_point, object.classification.front().label, planner_param_,
crosswalk_.polygon2d().basicPolygon());

const auto collision_state = object_info_manager_.getCollisionState(obj_uuid);
if (collision_point) {
const auto collision_state = object_info_manager_.getCollisionState(obj_uuid);
debug_data_.collision_points.push_back(
std::make_tuple(obj_uuid, *collision_point, collision_state));
}

const auto getLabelColor = [](const auto collision_state) {
if (collision_state == CollisionState::YIELD) {
return ColorName::RED;
} else if (
collision_state == CollisionState::EGO_PASS_FIRST ||
collision_state == CollisionState::EGO_PASS_LATER) {
return ColorName::GREEN;
} else if (collision_state == CollisionState::IGNORE) {
return ColorName::GRAY;
} else {
return ColorName::AMBER;
}
};

setObjectsOfInterestData(
object.kinematics.initial_pose_with_covariance.pose, object.shape,
getLabelColor(collision_state));
}
object_info_manager_.finalize();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -331,7 +331,7 @@ class CrosswalkModule : public SceneModuleInterface
std::optional<StopFactor> checkStopForStuckVehicles(
const PathWithLaneId & ego_path, const std::vector<PredictedObject> & objects,
const std::vector<geometry_msgs::msg::Point> & path_intersects,
const std::optional<geometry_msgs::msg::Pose> & stop_pose) const;
const std::optional<geometry_msgs::msg::Pose> & stop_pose);

std::optional<double> findEgoPassageDirectionAlongPath(
const PathWithLaneId & sparse_resample_path) const;
Expand Down

0 comments on commit 2eb8dfb

Please sign in to comment.