diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/filter/pointcloud_map_filter.launch.py b/launch/tier4_perception_launch/launch/object_recognition/detection/filter/pointcloud_map_filter.launch.py index 5fa71cd1aa0e9..6c0e5f20b8957 100644 --- a/launch/tier4_perception_launch/launch/object_recognition/detection/filter/pointcloud_map_filter.launch.py +++ b/launch/tier4_perception_launch/launch/object_recognition/detection/filter/pointcloud_map_filter.launch.py @@ -106,7 +106,7 @@ def create_compare_map_pipeline(self): components.append( ComposableNode( package="compare_map_segmentation", - plugin="compare_map_segmentation::VoxelBasedCompareMapFilterComponent", + plugin="autoware::compare_map_segmentation::VoxelBasedCompareMapFilterComponent", name="voxel_based_compare_map_filter", remappings=[ ("input", down_sample_topic), diff --git a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index ba0b058d8c00b..fd38b7bfd6ab3 100644 --- a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -391,7 +391,7 @@ def create_single_frame_outlier_filter_components(input_topic, output_topic, con components.append( ComposableNode( package="compare_map_segmentation", - plugin="compare_map_segmentation::CompareElevationMapFilterComponent", + plugin="autoware::compare_map_segmentation::CompareElevationMapFilterComponent", name="compare_elevation_map_filter", namespace="elevation_map", remappings=[ diff --git a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml index 3deff32d6e297..3c58c8d85b5be 100644 --- a/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml +++ b/launch/tier4_planning_launch/launch/scenario_planning/lane_driving/behavior_planning/behavior_planning.launch.xml @@ -260,7 +260,12 @@ - + diff --git a/perception/compare_map_segmentation/CMakeLists.txt b/perception/compare_map_segmentation/CMakeLists.txt index a76b0fc56e2a0..0a33711e946ef 100644 --- a/perception/compare_map_segmentation/CMakeLists.txt +++ b/perception/compare_map_segmentation/CMakeLists.txt @@ -21,23 +21,23 @@ include_directories( ${GRID_MAP_INCLUDE_DIR} ) -add_library(compare_map_segmentation SHARED - src/distance_based_compare_map_filter_nodelet.cpp - src/voxel_based_approximate_compare_map_filter_nodelet.cpp - src/voxel_based_compare_map_filter_nodelet.cpp - src/voxel_distance_based_compare_map_filter_nodelet.cpp - src/compare_elevation_map_filter_node.cpp - src/voxel_grid_map_loader.cpp +add_library(${PROJECT_NAME} SHARED + src/distance_based_compare_map_filter/node.cpp + src/voxel_based_approximate_compare_map_filter/node.cpp + src/voxel_based_compare_map_filter/node.cpp + src/voxel_distance_based_compare_map_filter/node.cpp + src/compare_elevation_map_filter/node.cpp + src/voxel_grid_map_loader/voxel_grid_map_loader.cpp ) -target_link_libraries(compare_map_segmentation +target_link_libraries(${PROJECT_NAME} pointcloud_preprocessor::pointcloud_preprocessor_filter_base ${Boost_LIBRARIES} ${OpenCV_LIBRARIES} ${PCL_LIBRARIES} ) -ament_target_dependencies(compare_map_segmentation +ament_target_dependencies(${PROJECT_NAME} grid_map_pcl grid_map_ros pcl_conversions @@ -50,7 +50,7 @@ ament_target_dependencies(compare_map_segmentation ) if(OPENMP_FOUND) - set_target_properties(compare_map_segmentation PROPERTIES + set_target_properties(${PROJECT_NAME} PROPERTIES COMPILE_FLAGS ${OpenMP_CXX_FLAGS} LINK_FLAGS ${OpenMP_CXX_FLAGS} ) @@ -58,32 +58,32 @@ endif() # ========== Compare Map Filter ========== # -- Distance Based Compare Map Filter -- -rclcpp_components_register_node(compare_map_segmentation - PLUGIN "compare_map_segmentation::DistanceBasedCompareMapFilterComponent" +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::compare_map_segmentation::DistanceBasedCompareMapFilterComponent" EXECUTABLE distance_based_compare_map_filter_node) # -- Voxel Based Approximate Compare Map Filter -- -rclcpp_components_register_node(compare_map_segmentation - PLUGIN "compare_map_segmentation::VoxelBasedApproximateCompareMapFilterComponent" +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::compare_map_segmentation::VoxelBasedApproximateCompareMapFilterComponent" EXECUTABLE voxel_based_approximate_compare_map_filter_node) # -- Voxel Based Compare Map Filter -- -rclcpp_components_register_node(compare_map_segmentation - PLUGIN "compare_map_segmentation::VoxelBasedCompareMapFilterComponent" +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::compare_map_segmentation::VoxelBasedCompareMapFilterComponent" EXECUTABLE voxel_based_compare_map_filter_node) # -- Voxel Distance Based Compare Map Filter -- -rclcpp_components_register_node(compare_map_segmentation - PLUGIN "compare_map_segmentation::VoxelDistanceBasedCompareMapFilterComponent" +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::compare_map_segmentation::VoxelDistanceBasedCompareMapFilterComponent" EXECUTABLE voxel_distance_based_compare_map_filter_node) # -- Compare Elevation Map Filter -- -rclcpp_components_register_node(compare_map_segmentation - PLUGIN "compare_map_segmentation::CompareElevationMapFilterComponent" +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "autoware::compare_map_segmentation::CompareElevationMapFilterComponent" EXECUTABLE compare_elevation_map_filter_node) install( - TARGETS compare_map_segmentation + TARGETS ${PROJECT_NAME} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION bin diff --git a/perception/compare_map_segmentation/src/compare_elevation_map_filter_node.cpp b/perception/compare_map_segmentation/src/compare_elevation_map_filter/node.cpp similarity index 93% rename from perception/compare_map_segmentation/src/compare_elevation_map_filter_node.cpp rename to perception/compare_map_segmentation/src/compare_elevation_map_filter/node.cpp index 1eadeeb3bec05..e5a19245bc5b1 100644 --- a/perception/compare_map_segmentation/src/compare_elevation_map_filter_node.cpp +++ b/perception/compare_map_segmentation/src/compare_elevation_map_filter/node.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "compare_map_segmentation/compare_elevation_map_filter_node.hpp" +#include "node.hpp" #include #include @@ -33,7 +33,7 @@ #include #include -namespace compare_map_segmentation +namespace autoware::compare_map_segmentation { CompareElevationMapFilterComponent::CompareElevationMapFilterComponent( const rclcpp::NodeOptions & options) @@ -94,7 +94,8 @@ void CompareElevationMapFilterComponent::filter( output.header.stamp = input->header.stamp; output.header.frame_id = output_frame; } -} // namespace compare_map_segmentation +} // namespace autoware::compare_map_segmentation #include -RCLCPP_COMPONENTS_REGISTER_NODE(compare_map_segmentation::CompareElevationMapFilterComponent) +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::compare_map_segmentation::CompareElevationMapFilterComponent) diff --git a/perception/compare_map_segmentation/include/compare_map_segmentation/compare_elevation_map_filter_node.hpp b/perception/compare_map_segmentation/src/compare_elevation_map_filter/node.hpp similarity index 86% rename from perception/compare_map_segmentation/include/compare_map_segmentation/compare_elevation_map_filter_node.hpp rename to perception/compare_map_segmentation/src/compare_elevation_map_filter/node.hpp index 63aad08fe7611..ba2328d862951 100644 --- a/perception/compare_map_segmentation/include/compare_map_segmentation/compare_elevation_map_filter_node.hpp +++ b/perception/compare_map_segmentation/src/compare_elevation_map_filter/node.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef COMPARE_MAP_SEGMENTATION__COMPARE_ELEVATION_MAP_FILTER_NODE_HPP_ -#define COMPARE_MAP_SEGMENTATION__COMPARE_ELEVATION_MAP_FILTER_NODE_HPP_ +#ifndef COMPARE_ELEVATION_MAP_FILTER__NODE_HPP_ +#define COMPARE_ELEVATION_MAP_FILTER__NODE_HPP_ #include "pointcloud_preprocessor/filter.hpp" @@ -29,7 +29,7 @@ #include #include #include -namespace compare_map_segmentation +namespace autoware::compare_map_segmentation { class CompareElevationMapFilterComponent : public pointcloud_preprocessor::Filter { @@ -56,6 +56,6 @@ class CompareElevationMapFilterComponent : public pointcloud_preprocessor::Filte PCL_MAKE_ALIGNED_OPERATOR_NEW explicit CompareElevationMapFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace compare_map_segmentation +} // namespace autoware::compare_map_segmentation -#endif // COMPARE_MAP_SEGMENTATION__COMPARE_ELEVATION_MAP_FILTER_NODE_HPP_ +#endif // COMPARE_ELEVATION_MAP_FILTER__NODE_HPP_ diff --git a/perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp similarity index 94% rename from perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp rename to perception/compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp index 2962ba1e28a75..53183cd7dc3f0 100644 --- a/perception/compare_map_segmentation/src/distance_based_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/distance_based_compare_map_filter/node.cpp @@ -12,7 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "compare_map_segmentation/distance_based_compare_map_filter_nodelet.hpp" +#include "node.hpp" + +#include "autoware/universe_utils/ros/debug_publisher.hpp" +#include "autoware/universe_utils/system/stop_watch.hpp" #include #include @@ -20,7 +23,7 @@ #include -namespace compare_map_segmentation +namespace autoware::compare_map_segmentation { void DistanceBasedStaticMapLoader::onMapCallback( @@ -176,7 +179,8 @@ void DistanceBasedCompareMapFilterComponent::filter( } } -} // namespace compare_map_segmentation +} // namespace autoware::compare_map_segmentation #include -RCLCPP_COMPONENTS_REGISTER_NODE(compare_map_segmentation::DistanceBasedCompareMapFilterComponent) +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::compare_map_segmentation::DistanceBasedCompareMapFilterComponent) diff --git a/perception/compare_map_segmentation/include/compare_map_segmentation/distance_based_compare_map_filter_nodelet.hpp b/perception/compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp similarity index 91% rename from perception/compare_map_segmentation/include/compare_map_segmentation/distance_based_compare_map_filter_nodelet.hpp rename to perception/compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp index 301dc75839f8e..115a73cf0d263 100644 --- a/perception/compare_map_segmentation/include/compare_map_segmentation/distance_based_compare_map_filter_nodelet.hpp +++ b/perception/compare_map_segmentation/src/distance_based_compare_map_filter/node.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef COMPARE_MAP_SEGMENTATION__DISTANCE_BASED_COMPARE_MAP_FILTER_NODELET_HPP_ -#define COMPARE_MAP_SEGMENTATION__DISTANCE_BASED_COMPARE_MAP_FILTER_NODELET_HPP_ +#ifndef DISTANCE_BASED_COMPARE_MAP_FILTER__NODE_HPP_ +#define DISTANCE_BASED_COMPARE_MAP_FILTER__NODE_HPP_ +#include "../voxel_grid_map_loader/voxel_grid_map_loader.hpp" #include "pointcloud_preprocessor/filter.hpp" -#include "voxel_grid_map_loader.hpp" #include // for pcl::isFinite #include @@ -26,7 +26,7 @@ #include #include -namespace compare_map_segmentation +namespace autoware::compare_map_segmentation { typedef typename pcl::Filter::PointCloud PointCloud; @@ -114,8 +114,8 @@ class DistanceBasedCompareMapFilterComponent : public pointcloud_preprocessor::F PCL_MAKE_ALIGNED_OPERATOR_NEW explicit DistanceBasedCompareMapFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace compare_map_segmentation +} // namespace autoware::compare_map_segmentation // clang-format off -#endif // COMPARE_MAP_SEGMENTATION__DISTANCE_BASED_COMPARE_MAP_FILTER_NODELET_HPP_ // NOLINT +#endif // DISTANCE_BASED_COMPARE_MAP_FILTER__NODE_HPP_ // NOLINT // clang-format on diff --git a/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp similarity index 94% rename from perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp rename to perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp index e14ae7d55a1d4..8bc22f8c31184 100644 --- a/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.cpp @@ -12,7 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "compare_map_segmentation/voxel_based_approximate_compare_map_filter_nodelet.hpp" +#include "node.hpp" + +#include "autoware/universe_utils/ros/debug_publisher.hpp" +#include "autoware/universe_utils/system/stop_watch.hpp" #include #include @@ -20,7 +23,7 @@ #include -namespace compare_map_segmentation +namespace autoware::compare_map_segmentation { bool VoxelBasedApproximateStaticMapLoader::is_close_to_map( @@ -145,8 +148,8 @@ void VoxelBasedApproximateCompareMapFilterComponent::filter( } } -} // namespace compare_map_segmentation +} // namespace autoware::compare_map_segmentation #include RCLCPP_COMPONENTS_REGISTER_NODE( - compare_map_segmentation::VoxelBasedApproximateCompareMapFilterComponent) + autoware::compare_map_segmentation::VoxelBasedApproximateCompareMapFilterComponent) diff --git a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_based_approximate_compare_map_filter_nodelet.hpp b/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.hpp similarity index 85% rename from perception/compare_map_segmentation/include/compare_map_segmentation/voxel_based_approximate_compare_map_filter_nodelet.hpp rename to perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.hpp index 3a5e183767620..26b0204210209 100644 --- a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_based_approximate_compare_map_filter_nodelet.hpp +++ b/perception/compare_map_segmentation/src/voxel_based_approximate_compare_map_filter/node.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef COMPARE_MAP_SEGMENTATION__VOXEL_BASED_APPROXIMATE_COMPARE_MAP_FILTER_NODELET_HPP_ // NOLINT -#define COMPARE_MAP_SEGMENTATION__VOXEL_BASED_APPROXIMATE_COMPARE_MAP_FILTER_NODELET_HPP_ // NOLINT +#ifndef VOXEL_BASED_APPROXIMATE_COMPARE_MAP_FILTER__NODE_HPP_ // NOLINT +#define VOXEL_BASED_APPROXIMATE_COMPARE_MAP_FILTER__NODE_HPP_ // NOLINT +#include "../voxel_grid_map_loader/voxel_grid_map_loader.hpp" #include "pointcloud_preprocessor/filter.hpp" -#include "voxel_grid_map_loader.hpp" #include #include @@ -25,7 +25,7 @@ #include #include -namespace compare_map_segmentation +namespace autoware::compare_map_segmentation { class VoxelBasedApproximateStaticMapLoader : public VoxelGridStaticMapLoader @@ -70,8 +70,8 @@ class VoxelBasedApproximateCompareMapFilterComponent : public pointcloud_preproc PCL_MAKE_ALIGNED_OPERATOR_NEW explicit VoxelBasedApproximateCompareMapFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace compare_map_segmentation +} // namespace autoware::compare_map_segmentation // clang-format off -#endif // COMPARE_MAP_SEGMENTATION__VOXEL_BASED_APPROXIMATE_COMPARE_MAP_FILTER_NODELET_HPP_ // NOLINT +#endif // VOXEL_BASED_APPROXIMATE_COMPARE_MAP_FILTER__NODE_HPP_ // NOLINT // clang-format on diff --git a/perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp similarity index 92% rename from perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp rename to perception/compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp index 449ae76181bc6..1861a710cdebd 100644 --- a/perception/compare_map_segmentation/src/voxel_based_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp @@ -12,7 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "compare_map_segmentation/voxel_based_compare_map_filter_nodelet.hpp" +#include "node.hpp" + +#include "autoware/universe_utils/ros/debug_publisher.hpp" +#include "autoware/universe_utils/system/stop_watch.hpp" #include #include @@ -21,7 +24,7 @@ #include #include -namespace compare_map_segmentation +namespace autoware::compare_map_segmentation { using pointcloud_preprocessor::get_param; @@ -106,7 +109,8 @@ void VoxelBasedCompareMapFilterComponent::filter( } } -} // namespace compare_map_segmentation +} // namespace autoware::compare_map_segmentation #include -RCLCPP_COMPONENTS_REGISTER_NODE(compare_map_segmentation::VoxelBasedCompareMapFilterComponent) +RCLCPP_COMPONENTS_REGISTER_NODE( + autoware::compare_map_segmentation::VoxelBasedCompareMapFilterComponent) diff --git a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_based_compare_map_filter_nodelet.hpp b/perception/compare_map_segmentation/src/voxel_based_compare_map_filter/node.hpp similarity index 78% rename from perception/compare_map_segmentation/include/compare_map_segmentation/voxel_based_compare_map_filter_nodelet.hpp rename to perception/compare_map_segmentation/src/voxel_based_compare_map_filter/node.hpp index 692193d13b04f..6e03e5d7a2e09 100644 --- a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_based_compare_map_filter_nodelet.hpp +++ b/perception/compare_map_segmentation/src/voxel_based_compare_map_filter/node.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef COMPARE_MAP_SEGMENTATION__VOXEL_BASED_COMPARE_MAP_FILTER_NODELET_HPP_ -#define COMPARE_MAP_SEGMENTATION__VOXEL_BASED_COMPARE_MAP_FILTER_NODELET_HPP_ +#ifndef VOXEL_BASED_COMPARE_MAP_FILTER__NODE_HPP_ +#define VOXEL_BASED_COMPARE_MAP_FILTER__NODE_HPP_ -#include "compare_map_segmentation/voxel_grid_map_loader.hpp" +#include "../voxel_grid_map_loader/voxel_grid_map_loader.hpp" #include "pointcloud_preprocessor/filter.hpp" #include @@ -24,7 +24,7 @@ #include #include -namespace compare_map_segmentation +namespace autoware::compare_map_segmentation { class VoxelBasedCompareMapFilterComponent : public pointcloud_preprocessor::Filter { @@ -45,6 +45,6 @@ class VoxelBasedCompareMapFilterComponent : public pointcloud_preprocessor::Filt PCL_MAKE_ALIGNED_OPERATOR_NEW explicit VoxelBasedCompareMapFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace compare_map_segmentation +} // namespace autoware::compare_map_segmentation -#endif // COMPARE_MAP_SEGMENTATION__VOXEL_BASED_COMPARE_MAP_FILTER_NODELET_HPP_ +#endif // VOXEL_BASED_COMPARE_MAP_FILTER__NODE_HPP_ diff --git a/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp b/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp similarity index 95% rename from perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp rename to perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp index 0a660bfffd7fb..7fdeb5d8ea163 100644 --- a/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter_nodelet.cpp +++ b/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.cpp @@ -12,7 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "compare_map_segmentation/voxel_distance_based_compare_map_filter_nodelet.hpp" +#include "node.hpp" + +#include "autoware/universe_utils/ros/debug_publisher.hpp" +#include "autoware/universe_utils/system/stop_watch.hpp" #include #include @@ -20,7 +23,7 @@ #include -namespace compare_map_segmentation +namespace autoware::compare_map_segmentation { void VoxelDistanceBasedStaticMapLoader::onMapCallback( @@ -174,8 +177,8 @@ void VoxelDistanceBasedCompareMapFilterComponent::filter( "debug/processing_time_ms", processing_time_ms); } } -} // namespace compare_map_segmentation +} // namespace autoware::compare_map_segmentation #include RCLCPP_COMPONENTS_REGISTER_NODE( - compare_map_segmentation::VoxelDistanceBasedCompareMapFilterComponent) + autoware::compare_map_segmentation::VoxelDistanceBasedCompareMapFilterComponent) diff --git a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_distance_based_compare_map_filter_nodelet.hpp b/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp similarity index 93% rename from perception/compare_map_segmentation/include/compare_map_segmentation/voxel_distance_based_compare_map_filter_nodelet.hpp rename to perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp index 0cfc8a64ab2dd..e0656359f3df2 100644 --- a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_distance_based_compare_map_filter_nodelet.hpp +++ b/perception/compare_map_segmentation/src/voxel_distance_based_compare_map_filter/node.hpp @@ -12,11 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef COMPARE_MAP_SEGMENTATION__VOXEL_DISTANCE_BASED_COMPARE_MAP_FILTER_NODELET_HPP_ // NOLINT -#define COMPARE_MAP_SEGMENTATION__VOXEL_DISTANCE_BASED_COMPARE_MAP_FILTER_NODELET_HPP_ // NOLINT +#ifndef VOXEL_DISTANCE_BASED_COMPARE_MAP_FILTER__NODE_HPP_ // NOLINT +#define VOXEL_DISTANCE_BASED_COMPARE_MAP_FILTER__NODE_HPP_ // NOLINT +#include "../voxel_grid_map_loader/voxel_grid_map_loader.hpp" #include "pointcloud_preprocessor/filter.hpp" -#include "voxel_grid_map_loader.hpp" #include #include @@ -27,7 +27,7 @@ #include #include -namespace compare_map_segmentation +namespace autoware::compare_map_segmentation { typedef typename pcl::Filter::PointCloud PointCloud; @@ -139,8 +139,8 @@ class VoxelDistanceBasedCompareMapFilterComponent : public pointcloud_preprocess PCL_MAKE_ALIGNED_OPERATOR_NEW explicit VoxelDistanceBasedCompareMapFilterComponent(const rclcpp::NodeOptions & options); }; -} // namespace compare_map_segmentation +} // namespace autoware::compare_map_segmentation // clang-format off -#endif // COMPARE_MAP_SEGMENTATION__VOXEL_DISTANCE_BASED_COMPARE_MAP_FILTER_NODELET_HPP_ // NOLINT +#endif // VOXEL_DISTANCE_BASED_COMPARE_MAP_FILTER__NODE_HPP_ // NOLINT // clang-format on diff --git a/perception/compare_map_segmentation/src/voxel_grid_map_loader.cpp b/perception/compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp similarity index 99% rename from perception/compare_map_segmentation/src/voxel_grid_map_loader.cpp rename to perception/compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp index ef3727019c0f4..b011799e5b912 100644 --- a/perception/compare_map_segmentation/src/voxel_grid_map_loader.cpp +++ b/perception/compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.cpp @@ -12,8 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "compare_map_segmentation/voxel_grid_map_loader.hpp" +#include "voxel_grid_map_loader.hpp" +namespace autoware::compare_map_segmentation +{ VoxelGridMapLoader::VoxelGridMapLoader( rclcpp::Node * node, double leaf_size, double downsize_ratio_z_axis, std::string * tf_map_input_frame, std::mutex * mutex) @@ -462,3 +464,5 @@ void VoxelGridDynamicMapLoader::request_update_map(const geometry_msgs::msg::Poi } } } + +} // namespace autoware::compare_map_segmentation diff --git a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_grid_map_loader.hpp b/perception/compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp similarity index 95% rename from perception/compare_map_segmentation/include/compare_map_segmentation/voxel_grid_map_loader.hpp rename to perception/compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp index 21cb19edcd0ec..bc54519a95e47 100644 --- a/perception/compare_map_segmentation/include/compare_map_segmentation/voxel_grid_map_loader.hpp +++ b/perception/compare_map_segmentation/src/voxel_grid_map_loader/voxel_grid_map_loader.hpp @@ -12,12 +12,12 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef COMPARE_MAP_SEGMENTATION__VOXEL_GRID_MAP_LOADER_HPP_ -#define COMPARE_MAP_SEGMENTATION__VOXEL_GRID_MAP_LOADER_HPP_ +#ifndef VOXEL_GRID_MAP_LOADER__VOXEL_GRID_MAP_LOADER_HPP_ +#define VOXEL_GRID_MAP_LOADER__VOXEL_GRID_MAP_LOADER_HPP_ #include -#include +#include "autoware_map_msgs/srv/get_differential_point_cloud_map.hpp" #include #include #include @@ -33,6 +33,8 @@ #include #include +namespace autoware::compare_map_segmentation +{ template double distance3D(const T p1, const U p2) { @@ -138,7 +140,7 @@ class VoxelGridStaticMapLoader : public VoxelGridMapLoader rclcpp::Node * node, double leaf_size, double downsize_ratio_z_axis, std::string * tf_map_input_frame, std::mutex * mutex); virtual void onMapCallback(const sensor_msgs::msg::PointCloud2::ConstSharedPtr map); - virtual bool is_close_to_map(const pcl::PointXYZ & point, const double distance_threshold); + bool is_close_to_map(const pcl::PointXYZ & point, const double distance_threshold) override; }; class VoxelGridDynamicMapLoader : public VoxelGridMapLoader @@ -199,7 +201,7 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader void timer_callback(); bool should_update_map() const; void request_update_map(const geometry_msgs::msg::Point & position); - virtual bool is_close_to_map(const pcl::PointXYZ & point, const double distance_threshold); + bool is_close_to_map(const pcl::PointXYZ & point, const double distance_threshold) override; /** \brief Check if point close to map pointcloud in the */ bool is_close_to_next_map_grid( const pcl::PointXYZ & point, const int current_map_grid_index, const double distance_threshold); @@ -319,4 +321,6 @@ class VoxelGridDynamicMapLoader : public VoxelGridMapLoader } }; -#endif // COMPARE_MAP_SEGMENTATION__VOXEL_GRID_MAP_LOADER_HPP_ +} // namespace autoware::compare_map_segmentation + +#endif // VOXEL_GRID_MAP_LOADER__VOXEL_GRID_MAP_LOADER_HPP_