Skip to content

Commit ebb1aaf

Browse files
technolojinpre-commit-ci[bot]
authored and
KhalilSelyan
committed
refactor(euclidean_cluster)!: fix namespace and directory structure (#7887)
* refactor: update include paths for euclidean_cluster code Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> refactor: fix namespace Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> chore: update include paths for euclidean_cluster code Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp> * style(pre-commit): autofix --------- 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 c0f191a commit ebb1aaf

18 files changed

+62
-64
lines changed

perception/detection_by_tracker/src/debugger/debugger.hpp

-3
Original file line numberDiff line numberDiff line change
@@ -17,9 +17,6 @@
1717

1818
#include "autoware/universe_utils/ros/debug_publisher.hpp"
1919
#include "autoware/universe_utils/system/stop_watch.hpp"
20-
#include "euclidean_cluster/euclidean_cluster.hpp"
21-
#include "euclidean_cluster/utils.hpp"
22-
#include "euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp"
2320

2421
#include <rclcpp/rclcpp.hpp>
2522

perception/detection_by_tracker/src/detection_by_tracker_node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -115,7 +115,7 @@ DetectionByTracker::DetectionByTracker(const rclcpp::NodeOptions & node_options)
115115
setMaxSearchRange();
116116

117117
shape_estimator_ = std::make_shared<autoware::shape_estimation::ShapeEstimator>(true, true);
118-
cluster_ = std::make_shared<euclidean_cluster::VoxelGridBasedEuclideanCluster>(
118+
cluster_ = std::make_shared<autoware::euclidean_cluster::VoxelGridBasedEuclideanCluster>(
119119
false, 10, 10000, 0.7, 0.3, 0);
120120
debugger_ = std::make_shared<Debugger>(this);
121121
published_time_publisher_ =
@@ -277,7 +277,7 @@ float DetectionByTracker::optimizeUnderSegmentedObject(
277277
const auto & label = target_object.classification.front().label;
278278

279279
// initialize clustering parameters
280-
euclidean_cluster::VoxelGridBasedEuclideanCluster cluster(
280+
autoware::euclidean_cluster::VoxelGridBasedEuclideanCluster cluster(
281281
false, 4, 10000, initial_cluster_range, initial_voxel_size, 0);
282282

283283
// convert to pcl

perception/detection_by_tracker/src/detection_by_tracker_node.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -15,12 +15,12 @@
1515
#ifndef DETECTION_BY_TRACKER_NODE_HPP_
1616
#define DETECTION_BY_TRACKER_NODE_HPP_
1717

18+
#include "autoware/euclidean_cluster/euclidean_cluster.hpp"
19+
#include "autoware/euclidean_cluster/utils.hpp"
20+
#include "autoware/euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp"
1821
#include "autoware/shape_estimation/shape_estimator.hpp"
1922
#include "autoware/universe_utils/ros/published_time_publisher.hpp"
2023
#include "debugger/debugger.hpp"
21-
#include "euclidean_cluster/euclidean_cluster.hpp"
22-
#include "euclidean_cluster/utils.hpp"
23-
#include "euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp"
2424
#include "tracker/tracker_handler.hpp"
2525
#include "utils/utils.hpp"
2626

@@ -69,7 +69,7 @@ class DetectionByTracker : public rclcpp::Node
6969

7070
TrackerHandler tracker_handler_;
7171
std::shared_ptr<autoware::shape_estimation::ShapeEstimator> shape_estimator_;
72-
std::shared_ptr<euclidean_cluster::EuclideanClusterInterface> cluster_;
72+
std::shared_ptr<autoware::euclidean_cluster::EuclideanClusterInterface> cluster_;
7373
std::shared_ptr<Debugger> debugger_;
7474
std::map<uint8_t, int> max_search_distance_for_merger_;
7575
std::map<uint8_t, int> max_search_distance_for_divider_;

perception/euclidean_cluster/CMakeLists.txt

+14-14
Original file line numberDiff line numberDiff line change
@@ -13,45 +13,45 @@ include_directories(
1313
${PCL_INCLUDE_DIRS}
1414
)
1515

16-
ament_auto_add_library(cluster_lib SHARED
17-
lib/utils.cpp
16+
ament_auto_add_library(${PROJECT_NAME}_lib SHARED
1817
lib/euclidean_cluster.cpp
1918
lib/voxel_grid_based_euclidean_cluster.cpp
19+
lib/utils.cpp
2020
)
2121

22-
target_link_libraries(cluster_lib
22+
target_link_libraries(${PROJECT_NAME}_lib
2323
${PCL_LIBRARIES}
2424
)
2525

26-
target_include_directories(cluster_lib
26+
target_include_directories(${PROJECT_NAME}_lib
2727
PUBLIC
2828
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
2929
$<INSTALL_INTERFACE:include>
3030
)
3131

32-
ament_auto_add_library(euclidean_cluster_node_core SHARED
32+
ament_auto_add_library(${PROJECT_NAME}_node_core SHARED
3333
src/euclidean_cluster_node.cpp
3434
)
35-
target_link_libraries(euclidean_cluster_node_core
35+
target_link_libraries(${PROJECT_NAME}_node_core
3636
${PCL_LIBRARIES}
37-
cluster_lib
37+
${PROJECT_NAME}_lib
3838
)
3939

40-
rclcpp_components_register_node(euclidean_cluster_node_core
41-
PLUGIN "euclidean_cluster::EuclideanClusterNode"
40+
rclcpp_components_register_node(${PROJECT_NAME}_node_core
41+
PLUGIN "autoware::euclidean_cluster::EuclideanClusterNode"
4242
EXECUTABLE euclidean_cluster_node
4343
)
4444

45-
ament_auto_add_library(voxel_grid_based_euclidean_cluster_node_core SHARED
45+
ament_auto_add_library(${PROJECT_NAME}_voxel_grid_node_core SHARED
4646
src/voxel_grid_based_euclidean_cluster_node.cpp
4747
)
48-
target_link_libraries(voxel_grid_based_euclidean_cluster_node_core
48+
target_link_libraries(${PROJECT_NAME}_voxel_grid_node_core
4949
${PCL_LIBRARIES}
50-
cluster_lib
50+
${PROJECT_NAME}_lib
5151
)
5252

53-
rclcpp_components_register_node(voxel_grid_based_euclidean_cluster_node_core
54-
PLUGIN "euclidean_cluster::VoxelGridBasedEuclideanClusterNode"
53+
rclcpp_components_register_node(${PROJECT_NAME}_voxel_grid_node_core
54+
PLUGIN "autoware::euclidean_cluster::VoxelGridBasedEuclideanClusterNode"
5555
EXECUTABLE voxel_grid_based_euclidean_cluster_node
5656
)
5757

perception/euclidean_cluster/include/euclidean_cluster/euclidean_cluster.hpp perception/euclidean_cluster/include/autoware/euclidean_cluster/euclidean_cluster.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -14,14 +14,14 @@
1414

1515
#pragma once
1616

17-
#include "euclidean_cluster/euclidean_cluster_interface.hpp"
18-
#include "euclidean_cluster/utils.hpp"
17+
#include "autoware/euclidean_cluster/euclidean_cluster_interface.hpp"
18+
#include "autoware/euclidean_cluster/utils.hpp"
1919

2020
#include <pcl/point_types.h>
2121

2222
#include <vector>
2323

24-
namespace euclidean_cluster
24+
namespace autoware::euclidean_cluster
2525
{
2626
class EuclideanCluster : public EuclideanClusterInterface
2727
{
@@ -42,4 +42,4 @@ class EuclideanCluster : public EuclideanClusterInterface
4242
float tolerance_;
4343
};
4444

45-
} // namespace euclidean_cluster
45+
} // namespace autoware::euclidean_cluster

perception/euclidean_cluster/include/euclidean_cluster/euclidean_cluster_interface.hpp perception/euclidean_cluster/include/autoware/euclidean_cluster/euclidean_cluster_interface.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424

2525
#include <vector>
2626

27-
namespace euclidean_cluster
27+
namespace autoware::euclidean_cluster
2828
{
2929
class EuclideanClusterInterface
3030
{
@@ -54,4 +54,4 @@ class EuclideanClusterInterface
5454
int max_cluster_size_;
5555
};
5656

57-
} // namespace euclidean_cluster
57+
} // namespace autoware::euclidean_cluster

perception/euclidean_cluster/include/euclidean_cluster/utils.hpp perception/euclidean_cluster/include/autoware/euclidean_cluster/utils.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424

2525
#include <vector>
2626

27-
namespace euclidean_cluster
27+
namespace autoware::euclidean_cluster
2828
{
2929
geometry_msgs::msg::Point getCentroid(const sensor_msgs::msg::PointCloud2 & pointcloud);
3030
void convertPointCloudClusters2Msg(
@@ -37,4 +37,4 @@ void convertPointCloudClusters2Msg(
3737
void convertObjectMsg2SensorMsg(
3838
const tier4_perception_msgs::msg::DetectedObjectsWithFeature & input,
3939
sensor_msgs::msg::PointCloud2 & output);
40-
} // namespace euclidean_cluster
40+
} // namespace autoware::euclidean_cluster

perception/euclidean_cluster/include/euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp perception/euclidean_cluster/include/autoware/euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -14,15 +14,15 @@
1414

1515
#pragma once
1616

17-
#include "euclidean_cluster/euclidean_cluster_interface.hpp"
18-
#include "euclidean_cluster/utils.hpp"
17+
#include "autoware/euclidean_cluster/euclidean_cluster_interface.hpp"
18+
#include "autoware/euclidean_cluster/utils.hpp"
1919

2020
#include <pcl/filters/voxel_grid.h>
2121
#include <pcl/point_types.h>
2222

2323
#include <vector>
2424

25-
namespace euclidean_cluster
25+
namespace autoware::euclidean_cluster
2626
{
2727
class VoxelGridBasedEuclideanCluster : public EuclideanClusterInterface
2828
{
@@ -52,4 +52,4 @@ class VoxelGridBasedEuclideanCluster : public EuclideanClusterInterface
5252
int min_points_number_per_voxel_;
5353
};
5454

55-
} // namespace euclidean_cluster
55+
} // namespace autoware::euclidean_cluster

perception/euclidean_cluster/launch/euclidean_cluster.launch.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ def load_composable_node_param(param_path):
4949

5050
use_low_height_euclidean_component = ComposableNode(
5151
package=pkg,
52-
plugin="euclidean_cluster::EuclideanClusterNode",
52+
plugin="autoware::euclidean_cluster::EuclideanClusterNode",
5353
name=AnonName("euclidean_cluster"),
5454
remappings=[
5555
("input", "low_height/pointcloud"),
@@ -60,7 +60,7 @@ def load_composable_node_param(param_path):
6060

6161
disuse_low_height_euclidean_component = ComposableNode(
6262
package=pkg,
63-
plugin="euclidean_cluster::EuclideanClusterNode",
63+
plugin="autoware::euclidean_cluster::EuclideanClusterNode",
6464
name=AnonName("euclidean_cluster"),
6565
remappings=[
6666
("input", LaunchConfiguration("input_pointcloud")),

perception/euclidean_cluster/launch/voxel_grid_based_euclidean_cluster.launch.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@ def load_composable_node_param(param_path):
4949
use_low_height_euclidean_component = ComposableNode(
5050
package=pkg,
5151
namespace=ns,
52-
plugin="euclidean_cluster::VoxelGridBasedEuclideanClusterNode",
52+
plugin="autoware::euclidean_cluster::VoxelGridBasedEuclideanClusterNode",
5353
name="euclidean_cluster",
5454
remappings=[
5555
("input", "low_height/pointcloud"),
@@ -61,7 +61,7 @@ def load_composable_node_param(param_path):
6161
disuse_low_height_euclidean_component = ComposableNode(
6262
package=pkg,
6363
namespace=ns,
64-
plugin="euclidean_cluster::VoxelGridBasedEuclideanClusterNode",
64+
plugin="autoware::euclidean_cluster::VoxelGridBasedEuclideanClusterNode",
6565
name="euclidean_cluster",
6666
remappings=[
6767
("input", LaunchConfiguration("input_pointcloud")),

perception/euclidean_cluster/lib/euclidean_cluster.cpp

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

15-
#include "euclidean_cluster/euclidean_cluster.hpp"
15+
#include "autoware/euclidean_cluster/euclidean_cluster.hpp"
1616

1717
#include <pcl/kdtree/kdtree.h>
1818
#include <pcl/segmentation/extract_clusters.h>
1919

20-
namespace euclidean_cluster
20+
namespace autoware::euclidean_cluster
2121
{
2222
EuclideanCluster::EuclideanCluster()
2323
{
@@ -93,4 +93,4 @@ bool EuclideanCluster::cluster(
9393
return true;
9494
}
9595

96-
} // namespace euclidean_cluster
96+
} // namespace autoware::euclidean_cluster

perception/euclidean_cluster/lib/utils.cpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -11,15 +11,15 @@
1111
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
14-
#include "euclidean_cluster/utils.hpp"
14+
#include "autoware/euclidean_cluster/utils.hpp"
1515

1616
#include <autoware_perception_msgs/msg/object_classification.hpp>
1717
#include <sensor_msgs/msg/point_field.hpp>
1818
#include <sensor_msgs/point_cloud2_iterator.hpp>
1919
#include <tier4_perception_msgs/msg/detected_object_with_feature.hpp>
2020
#include <tier4_perception_msgs/msg/detected_objects_with_feature.hpp>
2121

22-
namespace euclidean_cluster
22+
namespace autoware::euclidean_cluster
2323
{
2424
geometry_msgs::msg::Point getCentroid(const sensor_msgs::msg::PointCloud2 & pointcloud)
2525
{
@@ -128,4 +128,4 @@ void convertObjectMsg2SensorMsg(
128128
output.height = 1;
129129
output.is_dense = false;
130130
}
131-
} // namespace euclidean_cluster
131+
} // namespace autoware::euclidean_cluster

perception/euclidean_cluster/lib/voxel_grid_based_euclidean_cluster.cpp

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

15-
#include "euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp"
15+
#include "autoware/euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp"
1616

1717
#include <pcl/kdtree/kdtree.h>
1818
#include <pcl/segmentation/extract_clusters.h>
1919

2020
#include <unordered_map>
2121

22-
namespace euclidean_cluster
22+
namespace autoware::euclidean_cluster
2323
{
2424
VoxelGridBasedEuclideanCluster::VoxelGridBasedEuclideanCluster()
2525
{
@@ -166,4 +166,4 @@ bool VoxelGridBasedEuclideanCluster::cluster(
166166
return true;
167167
}
168168

169-
} // namespace euclidean_cluster
169+
} // namespace autoware::euclidean_cluster

perception/euclidean_cluster/src/euclidean_cluster_node.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -14,11 +14,11 @@
1414

1515
#include "euclidean_cluster_node.hpp"
1616

17-
#include "euclidean_cluster/utils.hpp"
17+
#include "autoware/euclidean_cluster/utils.hpp"
1818

1919
#include <vector>
2020

21-
namespace euclidean_cluster
21+
namespace autoware::euclidean_cluster
2222
{
2323
EuclideanClusterNode::EuclideanClusterNode(const rclcpp::NodeOptions & options)
2424
: Node("euclidean_cluster_node", options)
@@ -86,8 +86,8 @@ void EuclideanClusterNode::onPointCloud(
8686
}
8787
}
8888

89-
} // namespace euclidean_cluster
89+
} // namespace autoware::euclidean_cluster
9090

9191
#include <rclcpp_components/register_node_macro.hpp>
9292

93-
RCLCPP_COMPONENTS_REGISTER_NODE(euclidean_cluster::EuclideanClusterNode)
93+
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::euclidean_cluster::EuclideanClusterNode)

perception/euclidean_cluster/src/euclidean_cluster_node.hpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414

1515
#pragma once
1616

17-
#include "euclidean_cluster/euclidean_cluster.hpp"
17+
#include "autoware/euclidean_cluster/euclidean_cluster.hpp"
1818

1919
#include <autoware/universe_utils/ros/debug_publisher.hpp>
2020
#include <autoware/universe_utils/system/stop_watch.hpp>
@@ -26,7 +26,8 @@
2626

2727
#include <chrono>
2828
#include <memory>
29-
namespace euclidean_cluster
29+
30+
namespace autoware::euclidean_cluster
3031
{
3132
class EuclideanClusterNode : public rclcpp::Node
3233
{
@@ -45,4 +46,4 @@ class EuclideanClusterNode : public rclcpp::Node
4546
std::unique_ptr<autoware::universe_utils::DebugPublisher> debug_publisher_;
4647
};
4748

48-
} // namespace euclidean_cluster
49+
} // namespace autoware::euclidean_cluster

perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -14,11 +14,11 @@
1414

1515
#include "voxel_grid_based_euclidean_cluster_node.hpp"
1616

17-
#include "euclidean_cluster/utils.hpp"
17+
#include "autoware/euclidean_cluster/utils.hpp"
1818

1919
#include <vector>
2020

21-
namespace euclidean_cluster
21+
namespace autoware::euclidean_cluster
2222
{
2323
VoxelGridBasedEuclideanClusterNode::VoxelGridBasedEuclideanClusterNode(
2424
const rclcpp::NodeOptions & options)
@@ -89,8 +89,8 @@ void VoxelGridBasedEuclideanClusterNode::onPointCloud(
8989
}
9090
}
9191

92-
} // namespace euclidean_cluster
92+
} // namespace autoware::euclidean_cluster
9393

9494
#include <rclcpp_components/register_node_macro.hpp>
9595

96-
RCLCPP_COMPONENTS_REGISTER_NODE(euclidean_cluster::VoxelGridBasedEuclideanClusterNode)
96+
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::euclidean_cluster::VoxelGridBasedEuclideanClusterNode)

perception/euclidean_cluster/src/voxel_grid_based_euclidean_cluster_node.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414

1515
#pragma once
1616

17-
#include "euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp"
17+
#include "autoware/euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp"
1818

1919
#include <autoware/universe_utils/ros/debug_publisher.hpp>
2020
#include <autoware/universe_utils/system/stop_watch.hpp>
@@ -26,7 +26,7 @@
2626

2727
#include <memory>
2828

29-
namespace euclidean_cluster
29+
namespace autoware::euclidean_cluster
3030
{
3131
class VoxelGridBasedEuclideanClusterNode : public rclcpp::Node
3232
{
@@ -45,4 +45,4 @@ class VoxelGridBasedEuclideanClusterNode : public rclcpp::Node
4545
std::unique_ptr<autoware::universe_utils::DebugPublisher> debug_publisher_;
4646
};
4747

48-
} // namespace euclidean_cluster
48+
} // namespace autoware::euclidean_cluster

0 commit comments

Comments
 (0)