Skip to content

Commit 82d86dc

Browse files
authored
refactor(raindrop_cluster_filter)!: fix namespace and directory structure (#7785)
refactor: namespace fix, move header to src Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent be5bda9 commit 82d86dc

File tree

3 files changed

+18
-17
lines changed

3 files changed

+18
-17
lines changed

perception/raindrop_cluster_filter/CMakeLists.txt

+2-2
Original file line numberDiff line numberDiff line change
@@ -10,11 +10,11 @@ autoware_package()
1010

1111
# Targets
1212
ament_auto_add_library(low_intensity_cluster_filter SHARED
13-
src/low_intensity_cluster_filter.cpp
13+
src/low_intensity_cluster_filter_node.cpp
1414
)
1515

1616
rclcpp_components_register_node(low_intensity_cluster_filter
17-
PLUGIN "low_intensity_cluster_filter::LowIntensityClusterFilter"
17+
PLUGIN "autoware::low_intensity_cluster_filter::LowIntensityClusterFilter"
1818
EXECUTABLE low_intensity_cluster_filter_node)
1919

2020

perception/raindrop_cluster_filter/src/low_intensity_cluster_filter.cpp perception/raindrop_cluster_filter/src/low_intensity_cluster_filter_node.cpp

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

15-
#include "raindrop_cluster_filter/low_intensity_cluster_filter/low_intensity_cluster_filter.hpp"
15+
#include "low_intensity_cluster_filter_node.hpp"
16+
17+
#include "autoware/universe_utils/geometry/geometry.hpp"
1618

17-
#include <autoware/universe_utils/geometry/geometry.hpp>
1819
#include <pcl_ros/transforms.hpp>
1920

2021
#include <sensor_msgs/point_cloud2_iterator.hpp>
2122

2223
#include <pcl_conversions/pcl_conversions.h>
23-
namespace low_intensity_cluster_filter
24+
25+
namespace autoware::low_intensity_cluster_filter
2426
{
2527
LowIntensityClusterFilter::LowIntensityClusterFilter(const rclcpp::NodeOptions & node_options)
2628
: Node("low_intensity_cluster_filter_node", node_options),
@@ -135,7 +137,7 @@ bool LowIntensityClusterFilter::isValidatedCluster(const sensor_msgs::msg::Point
135137
return false;
136138
}
137139

138-
} // namespace low_intensity_cluster_filter
140+
} // namespace autoware::low_intensity_cluster_filter
139141

140142
#include <rclcpp_components/register_node_macro.hpp>
141-
RCLCPP_COMPONENTS_REGISTER_NODE(low_intensity_cluster_filter::LowIntensityClusterFilter)
143+
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::low_intensity_cluster_filter::LowIntensityClusterFilter)
Original file line numberDiff line numberDiff line change
@@ -12,26 +12,25 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15-
#ifndef RAINDROP_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER_HPP_
16-
#define RAINDROP_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER_HPP_
15+
#ifndef LOW_INTENSITY_CLUSTER_FILTER_NODE_HPP_
16+
#define LOW_INTENSITY_CLUSTER_FILTER_NODE_HPP_
1717

18+
#include "autoware/universe_utils/ros/debug_publisher.hpp"
19+
#include "autoware/universe_utils/system/stop_watch.hpp"
1820
#include "detected_object_validation/utils/utils.hpp"
1921

20-
#include <autoware/universe_utils/ros/debug_publisher.hpp>
21-
#include <autoware/universe_utils/system/stop_watch.hpp>
22+
#include <Eigen/Eigen>
2223
#include <rclcpp/rclcpp.hpp>
2324

24-
#include <tier4_perception_msgs/msg/detected_objects_with_feature.hpp>
25+
#include "tier4_perception_msgs/msg/detected_objects_with_feature.hpp"
2526

2627
#include <tf2_ros/buffer.h>
2728
#include <tf2_ros/transform_listener.h>
28-
// #include <tf2_eigen/tf2_eigen.hpp>
29-
#include <Eigen/Eigen>
3029

3130
#include <memory>
3231
#include <string>
3332

34-
namespace low_intensity_cluster_filter
33+
namespace autoware::low_intensity_cluster_filter
3534
{
3635

3736
class LowIntensityClusterFilter : public rclcpp::Node
@@ -73,6 +72,6 @@ class LowIntensityClusterFilter : public rclcpp::Node
7372
std::unique_ptr<autoware::universe_utils::DebugPublisher> debug_publisher_ptr_{nullptr};
7473
};
7574

76-
} // namespace low_intensity_cluster_filter
75+
} // namespace autoware::low_intensity_cluster_filter
7776

78-
#endif // RAINDROP_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER_HPP_
77+
#endif // LOW_INTENSITY_CLUSTER_FILTER_NODE_HPP_

0 commit comments

Comments
 (0)