Skip to content

Commit f28ccd8

Browse files
refactor(detected_object_validation)!: fix namespace and directory structure (#7866)
* refactor: update include paths for detected object filters Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: set proper namespace Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: move utils to be shared Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * refactor: remove unnecessary dependencies in detected_object_validation/package.xml Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * chore: Override functions in pcl_validator.hpp Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * style(pre-commit): autofix * refactor: pcl_validator to obstacle_pointcloud_validator, ogm_validator to occupancy_grid_map_validator Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> --------- Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 094f2e2 commit f28ccd8

File tree

16 files changed

+153
-112
lines changed

16 files changed

+153
-112
lines changed

perception/detected_object_validation/CMakeLists.txt

+10-18
Original file line numberDiff line numberDiff line change
@@ -28,12 +28,8 @@ include_directories(
2828
)
2929

3030
# Generate occupancy grid based validator exe file
31-
set(OCCUPANCY_GRID_BASED_VALIDATOR_SRC
32-
src/occupancy_grid_based_validator.cpp
33-
)
34-
3531
ament_auto_add_library(occupancy_grid_based_validator SHARED
36-
${OCCUPANCY_GRID_BASED_VALIDATOR_SRC}
32+
src/occupancy_grid_map/occupancy_grid_map_validator.cpp
3733
)
3834

3935
target_link_libraries(occupancy_grid_based_validator
@@ -42,12 +38,8 @@ target_link_libraries(occupancy_grid_based_validator
4238
)
4339

4440
# Generate obstacle pointcloud based validator exe file
45-
set(OBSTACLE_POINTCLOUD_BASED_VALIDATOR_SRC
46-
src/obstacle_pointcloud_based_validator.cpp
47-
)
48-
4941
ament_auto_add_library(obstacle_pointcloud_based_validator SHARED
50-
${OBSTACLE_POINTCLOUD_BASED_VALIDATOR_SRC}
42+
src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp
5143
)
5244

5345
target_link_libraries(obstacle_pointcloud_based_validator
@@ -56,32 +48,32 @@ target_link_libraries(obstacle_pointcloud_based_validator
5648
)
5749

5850
ament_auto_add_library(object_lanelet_filter SHARED
59-
src/object_lanelet_filter.cpp
60-
src/utils.cpp
51+
src/lanelet_filter/lanelet_filter.cpp
52+
lib/utils/utils.cpp
6153
)
6254

6355
ament_auto_add_library(object_position_filter SHARED
64-
src/object_position_filter.cpp
65-
src/utils.cpp
56+
src/position_filter/position_filter.cpp
57+
lib/utils/utils.cpp
6658
)
6759

6860
rclcpp_components_register_node(obstacle_pointcloud_based_validator
69-
PLUGIN "obstacle_pointcloud_based_validator::ObstaclePointCloudBasedValidator"
61+
PLUGIN "autoware::detected_object_validation::obstacle_pointcloud::ObstaclePointCloudBasedValidator"
7062
EXECUTABLE obstacle_pointcloud_based_validator_node
7163
)
7264

7365
rclcpp_components_register_node(object_lanelet_filter
74-
PLUGIN "object_lanelet_filter::ObjectLaneletFilterNode"
66+
PLUGIN "autoware::detected_object_validation::lanelet_filter::ObjectLaneletFilterNode"
7567
EXECUTABLE object_lanelet_filter_node
7668
)
7769

7870
rclcpp_components_register_node(object_position_filter
79-
PLUGIN "object_position_filter::ObjectPositionFilterNode"
71+
PLUGIN "autoware::detected_object_validation::position_filter::ObjectPositionFilterNode"
8072
EXECUTABLE object_position_filter_node
8173
)
8274

8375
rclcpp_components_register_node(occupancy_grid_based_validator
84-
PLUGIN "occupancy_grid_based_validator::OccupancyGridBasedValidator"
76+
PLUGIN "autoware::detected_object_validation::occupancy_grid_map::OccupancyGridBasedValidator"
8577
EXECUTABLE occupancy_grid_based_validator_node
8678
)
8779

perception/detected_object_validation/include/detected_object_validation/utils/utils.hpp perception/detected_object_validation/include/autoware/detected_object_validation/utils/utils.hpp

+7-3
Original file line numberDiff line numberDiff line change
@@ -12,12 +12,15 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_
16-
#define DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_
15+
#ifndef AUTOWARE__DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_
16+
#define AUTOWARE__DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_
1717

1818
#include <autoware_perception_msgs/msg/detected_objects.hpp>
1919

2020
#include <cstdint>
21+
22+
namespace autoware::detected_object_validation
23+
{
2124
namespace utils
2225
{
2326
struct FilterTargetLabel
@@ -48,5 +51,6 @@ inline bool hasBoundingBox(const autoware_perception_msgs::msg::DetectedObject &
4851
}
4952

5053
} // namespace utils
54+
} // namespace autoware::detected_object_validation
5155

52-
#endif // DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_
56+
#endif // AUTOWARE__DETECTED_OBJECT_VALIDATION__UTILS__UTILS_HPP_

perception/detected_object_validation/src/utils.cpp perception/detected_object_validation/lib/utils/utils.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,12 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "detected_object_validation/utils/utils.hpp"
15+
#include "autoware/detected_object_validation/utils/utils.hpp"
1616

1717
#include <autoware_perception_msgs/msg/object_classification.hpp>
1818

19+
namespace autoware::detected_object_validation
20+
{
1921
namespace utils
2022
{
2123
using Label = autoware_perception_msgs::msg::ObjectClassification;
@@ -27,4 +29,6 @@ bool FilterTargetLabel::isTarget(const uint8_t label) const
2729
(label == Label::TRAILER && TRAILER) || (label == Label::MOTORCYCLE && MOTORCYCLE) ||
2830
(label == Label::BICYCLE && BICYCLE) || (label == Label::PEDESTRIAN && PEDESTRIAN);
2931
}
32+
3033
} // namespace utils
34+
} // namespace autoware::detected_object_validation

perception/detected_object_validation/package.xml

-3
Original file line numberDiff line numberDiff line change
@@ -22,17 +22,14 @@
2222
<depend>autoware_perception_msgs</depend>
2323
<depend>autoware_test_utils</depend>
2424
<depend>autoware_universe_utils</depend>
25-
<depend>geometry_msgs</depend>
2625
<depend>message_filters</depend>
2726
<depend>nav_msgs</depend>
2827
<depend>object_recognition_utils</depend>
2928
<depend>pcl_conversions</depend>
3029
<depend>rclcpp</depend>
3130
<depend>rclcpp_components</depend>
32-
<depend>tf2</depend>
3331
<depend>tf2_geometry_msgs</depend>
3432
<depend>tf2_ros</depend>
35-
<depend>tier4_perception_msgs</depend>
3633

3734
<test_depend>ament_lint_auto</test_depend>
3835
<test_depend>autoware_lint_common</test_depend>

perception/detected_object_validation/src/object_lanelet_filter.cpp perception/detected_object_validation/src/lanelet_filter/lanelet_filter.cpp

+12-8
Original file line numberDiff line numberDiff line change
@@ -12,20 +12,22 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "detected_object_validation/detected_object_filter/object_lanelet_filter.hpp"
15+
#include "lanelet_filter.hpp"
1616

17-
#include <autoware/universe_utils/geometry/geometry.hpp>
18-
#include <autoware_lanelet2_extension/utility/message_conversion.hpp>
19-
#include <autoware_lanelet2_extension/utility/query.hpp>
20-
#include <object_recognition_utils/object_recognition_utils.hpp>
17+
#include "autoware/universe_utils/geometry/geometry.hpp"
18+
#include "autoware_lanelet2_extension/utility/message_conversion.hpp"
19+
#include "autoware_lanelet2_extension/utility/query.hpp"
20+
#include "object_recognition_utils/object_recognition_utils.hpp"
2121

2222
#include <boost/geometry/algorithms/convex_hull.hpp>
2323
#include <boost/geometry/algorithms/disjoint.hpp>
2424
#include <boost/geometry/algorithms/intersects.hpp>
2525

2626
#include <lanelet2_core/geometry/Polygon.h>
2727

28-
namespace object_lanelet_filter
28+
namespace autoware::detected_object_validation
29+
{
30+
namespace lanelet_filter
2931
{
3032
ObjectLaneletFilterNode::ObjectLaneletFilterNode(const rclcpp::NodeOptions & node_options)
3133
: Node("object_lanelet_filter_node", node_options),
@@ -309,7 +311,9 @@ bool ObjectLaneletFilterNode::isSameDirectionWithLanelets(
309311
return false;
310312
}
311313

312-
} // namespace object_lanelet_filter
314+
} // namespace lanelet_filter
315+
} // namespace autoware::detected_object_validation
313316

314317
#include <rclcpp_components/register_node_macro.hpp>
315-
RCLCPP_COMPONENTS_REGISTER_NODE(object_lanelet_filter::ObjectLaneletFilterNode)
318+
RCLCPP_COMPONENTS_REGISTER_NODE(
319+
autoware::detected_object_validation::lanelet_filter::ObjectLaneletFilterNode)
Original file line numberDiff line numberDiff line change
@@ -12,19 +12,19 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_
16-
#define DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_
15+
#ifndef LANELET_FILTER__LANELET_FILTER_HPP_
16+
#define LANELET_FILTER__LANELET_FILTER_HPP_
1717

18-
#include "detected_object_validation/utils/utils.hpp"
18+
#include "autoware/detected_object_validation/utils/utils.hpp"
19+
#include "autoware/universe_utils/geometry/geometry.hpp"
20+
#include "autoware/universe_utils/ros/debug_publisher.hpp"
21+
#include "autoware/universe_utils/ros/published_time_publisher.hpp"
22+
#include "autoware_lanelet2_extension/utility/utilities.hpp"
1923

20-
#include <autoware/universe_utils/geometry/geometry.hpp>
21-
#include <autoware/universe_utils/ros/debug_publisher.hpp>
22-
#include <autoware/universe_utils/ros/published_time_publisher.hpp>
23-
#include <autoware_lanelet2_extension/utility/utilities.hpp>
2424
#include <rclcpp/rclcpp.hpp>
2525

26-
#include <autoware_map_msgs/msg/lanelet_map_bin.hpp>
27-
#include <autoware_perception_msgs/msg/detected_objects.hpp>
26+
#include "autoware_map_msgs/msg/lanelet_map_bin.hpp"
27+
#include "autoware_perception_msgs/msg/detected_objects.hpp"
2828

2929
#include <lanelet2_core/Forward.h>
3030
#include <tf2_ros/buffer.h>
@@ -33,7 +33,9 @@
3333
#include <memory>
3434
#include <string>
3535

36-
namespace object_lanelet_filter
36+
namespace autoware::detected_object_validation
37+
{
38+
namespace lanelet_filter
3739
{
3840
using autoware::universe_utils::LinearRing2d;
3941
using autoware::universe_utils::MultiPoint2d;
@@ -92,6 +94,7 @@ class ObjectLaneletFilterNode : public rclcpp::Node
9294
std::unique_ptr<autoware::universe_utils::PublishedTimePublisher> published_time_publisher_;
9395
};
9496

95-
} // namespace object_lanelet_filter
97+
} // namespace lanelet_filter
98+
} // namespace autoware::detected_object_validation
9699

97-
#endif // DETECTED_OBJECT_VALIDATION__DETECTED_OBJECT_FILTER__OBJECT_LANELET_FILTER_HPP_
100+
#endif // LANELET_FILTER__LANELET_FILTER_HPP_
Original file line numberDiff line numberDiff line change
@@ -12,19 +12,21 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_
16-
#define DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_
15+
#ifndef OBSTACLE_POINTCLOUD__DEBUGGER_HPP_
16+
#define OBSTACLE_POINTCLOUD__DEBUGGER_HPP_
1717

1818
#include <rclcpp/rclcpp.hpp>
1919

20-
#include <autoware_perception_msgs/msg/detected_objects.hpp>
20+
#include "autoware_perception_msgs/msg/detected_objects.hpp"
2121
#include <sensor_msgs/msg/point_cloud2.hpp>
2222

2323
#include <pcl/point_cloud.h>
2424
#include <pcl/point_types.h>
2525
#include <pcl_conversions/pcl_conversions.h>
2626

27-
namespace obstacle_pointcloud_based_validator
27+
namespace autoware::detected_object_validation
28+
{
29+
namespace obstacle_pointcloud
2830
{
2931
class Debugger
3032
{
@@ -106,6 +108,8 @@ class Debugger
106108
return pointcloud_xyz;
107109
}
108110
};
109-
} // namespace obstacle_pointcloud_based_validator
110111

111-
#endif // DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__DEBUGGER_HPP_
112+
} // namespace obstacle_pointcloud
113+
} // namespace autoware::detected_object_validation
114+
115+
#endif // OBSTACLE_POINTCLOUD__DEBUGGER_HPP_

perception/detected_object_validation/src/obstacle_pointcloud_based_validator.cpp perception/detected_object_validation/src/obstacle_pointcloud/obstacle_pointcloud_validator.cpp

+9-5
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,9 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#include "detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp"
15+
#define EIGEN_MPL2_ONLY
16+
17+
#include "obstacle_pointcloud_validator.hpp"
1618

1719
#include <autoware/universe_utils/geometry/boost_polygon_utils.hpp>
1820
#include <object_recognition_utils/object_recognition_utils.hpp>
@@ -25,11 +27,12 @@
2527
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
2628
#endif
2729

28-
#define EIGEN_MPL2_ONLY
2930
#include <Eigen/Core>
3031
#include <Eigen/Geometry>
3132

32-
namespace obstacle_pointcloud_based_validator
33+
namespace autoware::detected_object_validation
34+
{
35+
namespace obstacle_pointcloud
3336
{
3437
namespace bg = boost::geometry;
3538
using Shape = autoware_perception_msgs::msg::Shape;
@@ -369,8 +372,9 @@ void ObstaclePointCloudBasedValidator::onObjectsAndObstaclePointCloud(
369372
"debug/pipeline_latency_ms", pipeline_latency);
370373
}
371374

372-
} // namespace obstacle_pointcloud_based_validator
375+
} // namespace obstacle_pointcloud
376+
} // namespace autoware::detected_object_validation
373377

374378
#include <rclcpp_components/register_node_macro.hpp>
375379
RCLCPP_COMPONENTS_REGISTER_NODE(
376-
obstacle_pointcloud_based_validator::ObstaclePointCloudBasedValidator)
380+
autoware::detected_object_validation::obstacle_pointcloud::ObstaclePointCloudBasedValidator)
Original file line numberDiff line numberDiff line change
@@ -13,17 +13,17 @@
1313
// limitations under the License.
1414

1515
// NOLINTNEXTLINE(whitespace/line_length)
16-
#ifndef DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_
16+
#ifndef OBSTACLE_POINTCLOUD__OBSTACLE_POINTCLOUD_VALIDATOR_HPP_
1717
// NOLINTNEXTLINE(whitespace/line_length)
18-
#define DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_
18+
#define OBSTACLE_POINTCLOUD__OBSTACLE_POINTCLOUD_VALIDATOR_HPP_
1919

20-
#include "detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp"
20+
#include "autoware/universe_utils/ros/debug_publisher.hpp"
21+
#include "autoware/universe_utils/ros/published_time_publisher.hpp"
22+
#include "debugger.hpp"
2123

22-
#include <autoware/universe_utils/ros/debug_publisher.hpp>
23-
#include <autoware/universe_utils/ros/published_time_publisher.hpp>
2424
#include <rclcpp/rclcpp.hpp>
2525

26-
#include <autoware_perception_msgs/msg/detected_objects.hpp>
26+
#include "autoware_perception_msgs/msg/detected_objects.hpp"
2727
#include <sensor_msgs/msg/point_cloud2.hpp>
2828

2929
#include <message_filters/subscriber.h>
@@ -42,7 +42,10 @@
4242
#include <memory>
4343
#include <optional>
4444
#include <vector>
45-
namespace obstacle_pointcloud_based_validator
45+
46+
namespace autoware::detected_object_validation
47+
{
48+
namespace obstacle_pointcloud
4649
{
4750

4851
struct PointsNumThresholdParam
@@ -91,14 +94,17 @@ class Validator2D : public Validator
9194

9295
pcl::PointCloud<pcl::PointXYZ>::Ptr convertToXYZ(
9396
const pcl::PointCloud<pcl::PointXY>::Ptr & pointcloud_xy);
94-
inline pcl::PointCloud<pcl::PointXYZ>::Ptr getDebugNeighborPointCloud()
97+
inline pcl::PointCloud<pcl::PointXYZ>::Ptr getDebugNeighborPointCloud() override
9598
{
9699
return convertToXYZ(neighbor_pointcloud_);
97100
}
98101

99-
bool setKdtreeInputCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud);
100-
bool validate_object(const autoware_perception_msgs::msg::DetectedObject & transformed_object);
101-
std::optional<float> getMaxRadius(const autoware_perception_msgs::msg::DetectedObject & object);
102+
bool setKdtreeInputCloud(
103+
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud) override;
104+
bool validate_object(
105+
const autoware_perception_msgs::msg::DetectedObject & transformed_object) override;
106+
std::optional<float> getMaxRadius(
107+
const autoware_perception_msgs::msg::DetectedObject & object) override;
102108
std::optional<size_t> getPointCloudWithinObject(
103109
const autoware_perception_msgs::msg::DetectedObject & object,
104110
const pcl::PointCloud<pcl::PointXY>::Ptr neighbor_pointcloud);
@@ -112,13 +118,16 @@ class Validator3D : public Validator
112118

113119
public:
114120
explicit Validator3D(PointsNumThresholdParam & points_num_threshold_param);
115-
inline pcl::PointCloud<pcl::PointXYZ>::Ptr getDebugNeighborPointCloud()
121+
inline pcl::PointCloud<pcl::PointXYZ>::Ptr getDebugNeighborPointCloud() override
116122
{
117123
return neighbor_pointcloud_;
118124
}
119-
bool setKdtreeInputCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud);
120-
bool validate_object(const autoware_perception_msgs::msg::DetectedObject & transformed_object);
121-
std::optional<float> getMaxRadius(const autoware_perception_msgs::msg::DetectedObject & object);
125+
bool setKdtreeInputCloud(
126+
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud) override;
127+
bool validate_object(
128+
const autoware_perception_msgs::msg::DetectedObject & transformed_object) override;
129+
std::optional<float> getMaxRadius(
130+
const autoware_perception_msgs::msg::DetectedObject & object) override;
122131
std::optional<size_t> getPointCloudWithinObject(
123132
const autoware_perception_msgs::msg::DetectedObject & object,
124133
const pcl::PointCloud<pcl::PointXYZ>::Ptr neighbor_pointcloud);
@@ -154,7 +163,9 @@ class ObstaclePointCloudBasedValidator : public rclcpp::Node
154163
const autoware_perception_msgs::msg::DetectedObjects::ConstSharedPtr & input_objects,
155164
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_obstacle_pointcloud);
156165
};
157-
} // namespace obstacle_pointcloud_based_validator
166+
167+
} // namespace obstacle_pointcloud
168+
} // namespace autoware::detected_object_validation
158169

159170
// NOLINTNEXTLINE(whitespace/line_length)
160-
#endif // DETECTED_OBJECT_VALIDATION__OBSTACLE_POINTCLOUD_BASED_VALIDATOR__OBSTACLE_POINTCLOUD_BASED_VALIDATOR_HPP_
171+
#endif // OBSTACLE_POINTCLOUD__OBSTACLE_POINTCLOUD_VALIDATOR_HPP_

0 commit comments

Comments
 (0)