Commit 85d3f92 2 people authored and committed
1 parent d23ccf5 commit 85d3f92 Copy full SHA for 85d3f92
File tree 2 files changed +6
-1
lines changed
perception/detected_object_validation
include/detected_object_filter
2 files changed +6
-1
lines changed Original file line number Diff line number Diff line change @@ -53,6 +53,7 @@ class ObjectLaneletFilterNode : public rclcpp::Node
53
53
54
54
lanelet::LaneletMapPtr lanelet_map_ptr_;
55
55
lanelet::ConstLanelets road_lanelets_;
56
+ lanelet::ConstLanelets shoulder_lanelets_;
56
57
std::string lanelet_frame_id_;
57
58
58
59
tf2_ros::Buffer tf_buffer_;
Original file line number Diff line number Diff line change @@ -69,6 +69,7 @@ void ObjectLaneletFilterNode::mapCallback(
69
69
lanelet::utils::conversion::fromBinMsg (*map_msg, lanelet_map_ptr_);
70
70
const lanelet::ConstLanelets all_lanelets = lanelet::utils::query::laneletLayer (lanelet_map_ptr_);
71
71
road_lanelets_ = lanelet::utils::query::roadLanelets (all_lanelets);
72
+ shoulder_lanelets_ = lanelet::utils::query::shoulderLanelets (all_lanelets);
72
73
}
73
74
74
75
void ObjectLaneletFilterNode::objectCallback (
@@ -94,7 +95,10 @@ void ObjectLaneletFilterNode::objectCallback(
94
95
// calculate convex hull
95
96
const auto convex_hull = getConvexHull (transformed_objects);
96
97
// 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_);
98
102
99
103
// filtering process
100
104
for (size_t index = 0 ; index < transformed_objects.objects .size (); ++index ) {
You can’t perform that action at this time.
0 commit comments