Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(intersection, blind_spot): add objects of interest marker #6201

Merged
merged 1 commit into from
Jan 29, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion planning/behavior_velocity_blind_spot_module/src/scene.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -348,7 +348,7 @@ bool BlindSpotModule::checkObstacleInBlindSpot(
lanelet::LaneletMapConstPtr lanelet_map_ptr, lanelet::routing::RoutingGraphPtr routing_graph_ptr,
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_ptr,
const int closest_idx, const geometry_msgs::msg::Pose & stop_line_pose) const
const int closest_idx, const geometry_msgs::msg::Pose & stop_line_pose)
{
/* get detection area */
if (turn_direction_ == TurnDirection::INVALID) {
Expand Down Expand Up @@ -409,6 +409,8 @@ bool BlindSpotModule::checkObstacleInBlindSpot(
exist_in_right_conflict_area || exist_in_opposite_conflict_area;
if (exist_in_detection_area && exist_in_conflict_area) {
debug_data_.conflicting_targets.objects.push_back(object);
setObjectsOfInterestData(
object.kinematics.initial_pose_with_covariance.pose, object.shape, ColorName::RED);
return true;
}
}
Expand Down
2 changes: 1 addition & 1 deletion planning/behavior_velocity_blind_spot_module/src/scene.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ class BlindSpotModule : public SceneModuleInterface
lanelet::routing::RoutingGraphPtr routing_graph_ptr,
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_ptr,
const int closest_idx, const geometry_msgs::msg::Pose & stop_line_pose) const;
const int closest_idx, const geometry_msgs::msg::Pose & stop_line_pose);

/**
* @brief Create half lanelet
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -621,6 +621,9 @@ IntersectionModule::CollisionStatus IntersectionModule::detectCollision(
continue;
}
const auto & unsafe_info = object_info->is_unsafe().value();
setObjectsOfInterestData(
object_info->predicted_object().kinematics.initial_pose_with_covariance.pose,
object_info->predicted_object().shape, ColorName::RED);
// ==========================================================================================
// if ego is over the pass judge lines, then the visualization as "too_late_objects" or
// "misjudge_objects" is more important than that for "unsafe"
Expand Down Expand Up @@ -910,7 +913,7 @@ bool IntersectionModule::checkCollision(
}
}
object_ttc_time_array.layout.dim.at(0).size++;
const auto & pos = object.kinematics.initial_pose_with_covariance.pose.position;
const auto & pos = object..position;
const auto & shape = object.shape;
object_ttc_time_array.data.insert(
object_ttc_time_array.data.end(),
Expand Down