Skip to content

Commit 4310045

Browse files
authored
feat(intersection, blind_spot): add objects of interest marker (#6201)
Signed-off-by: Mamoru Sobue <mamoru.sobue@tier4.jp>
1 parent d57381b commit 4310045

File tree

3 files changed

+8
-3
lines changed

3 files changed

+8
-3
lines changed

planning/behavior_velocity_blind_spot_module/src/scene.cpp

+3-1
Original file line numberDiff line numberDiff line change
@@ -348,7 +348,7 @@ bool BlindSpotModule::checkObstacleInBlindSpot(
348348
lanelet::LaneletMapConstPtr lanelet_map_ptr, lanelet::routing::RoutingGraphPtr routing_graph_ptr,
349349
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
350350
const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_ptr,
351-
const int closest_idx, const geometry_msgs::msg::Pose & stop_line_pose) const
351+
const int closest_idx, const geometry_msgs::msg::Pose & stop_line_pose)
352352
{
353353
/* get detection area */
354354
if (turn_direction_ == TurnDirection::INVALID) {
@@ -409,6 +409,8 @@ bool BlindSpotModule::checkObstacleInBlindSpot(
409409
exist_in_right_conflict_area || exist_in_opposite_conflict_area;
410410
if (exist_in_detection_area && exist_in_conflict_area) {
411411
debug_data_.conflicting_targets.objects.push_back(object);
412+
setObjectsOfInterestData(
413+
object.kinematics.initial_pose_with_covariance.pose, object.shape, ColorName::RED);
412414
return true;
413415
}
414416
}

planning/behavior_velocity_blind_spot_module/src/scene.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -113,7 +113,7 @@ class BlindSpotModule : public SceneModuleInterface
113113
lanelet::routing::RoutingGraphPtr routing_graph_ptr,
114114
const autoware_auto_planning_msgs::msg::PathWithLaneId & path,
115115
const autoware_auto_perception_msgs::msg::PredictedObjects::ConstSharedPtr objects_ptr,
116-
const int closest_idx, const geometry_msgs::msg::Pose & stop_line_pose) const;
116+
const int closest_idx, const geometry_msgs::msg::Pose & stop_line_pose);
117117

118118
/**
119119
* @brief Create half lanelet

planning/behavior_velocity_intersection_module/src/scene_intersection_collision.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -621,6 +621,9 @@ IntersectionModule::CollisionStatus IntersectionModule::detectCollision(
621621
continue;
622622
}
623623
const auto & unsafe_info = object_info->is_unsafe().value();
624+
setObjectsOfInterestData(
625+
object_info->predicted_object().kinematics.initial_pose_with_covariance.pose,
626+
object_info->predicted_object().shape, ColorName::RED);
624627
// ==========================================================================================
625628
// if ego is over the pass judge lines, then the visualization as "too_late_objects" or
626629
// "misjudge_objects" is more important than that for "unsafe"
@@ -910,7 +913,7 @@ bool IntersectionModule::checkCollision(
910913
}
911914
}
912915
object_ttc_time_array.layout.dim.at(0).size++;
913-
const auto & pos = object.kinematics.initial_pose_with_covariance.pose.position;
916+
const auto & pos = object..position;
914917
const auto & shape = object.shape;
915918
object_ttc_time_array.data.insert(
916919
object_ttc_time_array.data.end(),

0 commit comments

Comments
 (0)