Skip to content

Commit

Permalink
refactor: namespace fix, move header to src
Browse files Browse the repository at this point in the history
Signed-off-by: Taekjin LEE <[email protected]>
  • Loading branch information
technolojin committed Jul 3, 2024
1 parent 9b50ae2 commit 4522419
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 17 deletions.
4 changes: 2 additions & 2 deletions perception/raindrop_cluster_filter/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,11 @@ autoware_package()

# Targets
ament_auto_add_library(low_intensity_cluster_filter SHARED
src/low_intensity_cluster_filter.cpp
src/low_intensity_cluster_filter_node.cpp
)

rclcpp_components_register_node(low_intensity_cluster_filter
PLUGIN "low_intensity_cluster_filter::LowIntensityClusterFilter"
PLUGIN "autoware::low_intensity_cluster_filter::LowIntensityClusterFilter"
EXECUTABLE low_intensity_cluster_filter_node)


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,15 +12,17 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include "raindrop_cluster_filter/low_intensity_cluster_filter/low_intensity_cluster_filter.hpp"
#include "low_intensity_cluster_filter_node.hpp"

#include "autoware/universe_utils/geometry/geometry.hpp"

#include <autoware/universe_utils/geometry/geometry.hpp>
#include <pcl_ros/transforms.hpp>

#include <sensor_msgs/point_cloud2_iterator.hpp>

#include <pcl_conversions/pcl_conversions.h>
namespace low_intensity_cluster_filter

namespace autoware::low_intensity_cluster_filter
{
LowIntensityClusterFilter::LowIntensityClusterFilter(const rclcpp::NodeOptions & node_options)
: Node("low_intensity_cluster_filter_node", node_options),
Expand Down Expand Up @@ -135,7 +137,7 @@ bool LowIntensityClusterFilter::isValidatedCluster(const sensor_msgs::msg::Point
return false;
}

} // namespace low_intensity_cluster_filter
} // namespace autoware::low_intensity_cluster_filter

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(low_intensity_cluster_filter::LowIntensityClusterFilter)
RCLCPP_COMPONENTS_REGISTER_NODE(autoware::low_intensity_cluster_filter::LowIntensityClusterFilter)

Check warning on line 143 in perception/raindrop_cluster_filter/src/low_intensity_cluster_filter_node.cpp

View check run for this annotation

Codecov / codecov/patch

perception/raindrop_cluster_filter/src/low_intensity_cluster_filter_node.cpp#L143

Added line #L143 was not covered by tests
Original file line number Diff line number Diff line change
Expand Up @@ -12,26 +12,25 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RAINDROP_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER_HPP_
#define RAINDROP_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER_HPP_
#ifndef LOW_INTENSITY_CLUSTER_FILTER_NODE_HPP_
#define LOW_INTENSITY_CLUSTER_FILTER_NODE_HPP_

#include "autoware/universe_utils/ros/debug_publisher.hpp"
#include "autoware/universe_utils/system/stop_watch.hpp"
#include "detected_object_validation/utils/utils.hpp"

#include <autoware/universe_utils/ros/debug_publisher.hpp>
#include <autoware/universe_utils/system/stop_watch.hpp>
#include <Eigen/Eigen>
#include <rclcpp/rclcpp.hpp>

#include <tier4_perception_msgs/msg/detected_objects_with_feature.hpp>
#include "tier4_perception_msgs/msg/detected_objects_with_feature.hpp"

#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>
// #include <tf2_eigen/tf2_eigen.hpp>
#include <Eigen/Eigen>

#include <memory>
#include <string>

namespace low_intensity_cluster_filter
namespace autoware::low_intensity_cluster_filter
{

class LowIntensityClusterFilter : public rclcpp::Node
Expand Down Expand Up @@ -73,6 +72,6 @@ class LowIntensityClusterFilter : public rclcpp::Node
std::unique_ptr<autoware::universe_utils::DebugPublisher> debug_publisher_ptr_{nullptr};
};

} // namespace low_intensity_cluster_filter
} // namespace autoware::low_intensity_cluster_filter

#endif // RAINDROP_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER__LOW_INTENSITY_CLUSTER_FILTER_HPP_
#endif // LOW_INTENSITY_CLUSTER_FILTER_NODE_HPP_

0 comments on commit 4522419

Please sign in to comment.