Skip to content

Commit 85d3f92

Browse files
shmpwkpre-commit-ci[bot]
authored andcommitted
fix(detected_object_validation): consider shoulder lanelet in object lanelet filter (autowarefoundation#5324)
* fix(detected_object_validation): consider shoulder lanelet in object lanelet filter Signed-off-by: Shumpei Wakabayashi <shumpei.wakabayashi@tier4.jp> * style(pre-commit): autofix --------- Signed-off-by: Shumpei Wakabayashi <shumpei.wakabayashi@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
1 parent d23ccf5 commit 85d3f92

File tree

2 files changed

+6
-1
lines changed

2 files changed

+6
-1
lines changed

perception/detected_object_validation/include/detected_object_filter/object_lanelet_filter.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,7 @@ class ObjectLaneletFilterNode : public rclcpp::Node
5353

5454
lanelet::LaneletMapPtr lanelet_map_ptr_;
5555
lanelet::ConstLanelets road_lanelets_;
56+
lanelet::ConstLanelets shoulder_lanelets_;
5657
std::string lanelet_frame_id_;
5758

5859
tf2_ros::Buffer tf_buffer_;

perception/detected_object_validation/src/object_lanelet_filter.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,7 @@ void ObjectLaneletFilterNode::mapCallback(
6969
lanelet::utils::conversion::fromBinMsg(*map_msg, lanelet_map_ptr_);
7070
const lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer(lanelet_map_ptr_);
7171
road_lanelets_ = lanelet::utils::query::roadLanelets(all_lanelets);
72+
shoulder_lanelets_ = lanelet::utils::query::shoulderLanelets(all_lanelets);
7273
}
7374

7475
void ObjectLaneletFilterNode::objectCallback(
@@ -94,7 +95,10 @@ void ObjectLaneletFilterNode::objectCallback(
9495
// calculate convex hull
9596
const auto convex_hull = getConvexHull(transformed_objects);
9697
// get intersected lanelets
97-
lanelet::ConstLanelets intersected_lanelets = getIntersectedLanelets(convex_hull, road_lanelets_);
98+
lanelet::ConstLanelets intersected_road_lanelets =
99+
getIntersectedLanelets(convex_hull, road_lanelets_);
100+
lanelet::ConstLanelets intersected_shoulder_lanelets =
101+
getIntersectedLanelets(convex_hull, shoulder_lanelets_);
98102

99103
// filtering process
100104
for (size_t index = 0; index < transformed_objects.objects.size(); ++index) {

0 commit comments

Comments
 (0)