diff --git a/common/autoware_point_types/include/autoware_point_types/types.hpp b/common/autoware_point_types/include/autoware/point_types/types.hpp similarity index 94% rename from common/autoware_point_types/include/autoware_point_types/types.hpp rename to common/autoware_point_types/include/autoware/point_types/types.hpp index a3b0670280530..0fde62222e276 100644 --- a/common/autoware_point_types/include/autoware_point_types/types.hpp +++ b/common/autoware_point_types/include/autoware/point_types/types.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_POINT_TYPES__TYPES_HPP_ -#define AUTOWARE_POINT_TYPES__TYPES_HPP_ +#ifndef AUTOWARE__POINT_TYPES__TYPES_HPP_ +#define AUTOWARE__POINT_TYPES__TYPES_HPP_ #include @@ -22,7 +22,7 @@ #include #include -namespace autoware_point_types +namespace autoware::point_types { template bool float_eq(const T a, const T b, const T eps = 10e-6) @@ -166,23 +166,23 @@ using PointXYZIRCAEDTGenerator = std::tuple< field_return_type_generator, field_channel_generator, field_azimuth_generator, field_elevation_generator, field_distance_generator, field_time_stamp_generator>; -} // namespace autoware_point_types +} // namespace autoware::point_types POINT_CLOUD_REGISTER_POINT_STRUCT( - autoware_point_types::PointXYZIRC, + autoware::point_types::PointXYZIRC, (float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity, intensity)( std::uint8_t, return_type, return_type)(std::uint16_t, channel, channel)) POINT_CLOUD_REGISTER_POINT_STRUCT( - autoware_point_types::PointXYZIRADRT, + autoware::point_types::PointXYZIRADRT, (float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint16_t, ring, ring)( float, azimuth, azimuth)(float, distance, distance)(std::uint8_t, return_type, return_type)( double, time_stamp, time_stamp)) POINT_CLOUD_REGISTER_POINT_STRUCT( - autoware_point_types::PointXYZIRCAEDT, + autoware::point_types::PointXYZIRCAEDT, (float, x, x)(float, y, y)(float, z, z)(std::uint8_t, intensity, intensity)( std::uint8_t, return_type, return_type)(std::uint16_t, channel, channel)(float, azimuth, azimuth)( float, elevation, elevation)(float, distance, distance)(std::uint32_t, time_stamp, time_stamp)) -#endif // AUTOWARE_POINT_TYPES__TYPES_HPP_ +#endif // AUTOWARE__POINT_TYPES__TYPES_HPP_ diff --git a/common/autoware_point_types/test/test_point_types.cpp b/common/autoware_point_types/test/test_point_types.cpp index 16887ac2aa498..08696a9948f60 100644 --- a/common/autoware_point_types/test/test_point_types.cpp +++ b/common/autoware_point_types/test/test_point_types.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_point_types/types.hpp" +#include "autoware/point_types/types.hpp" #include @@ -20,7 +20,7 @@ TEST(PointEquality, PointXYZI) { - using autoware_point_types::PointXYZI; + using autoware::point_types::PointXYZI; PointXYZI pt0{0, 1, 2, 3}; PointXYZI pt1{0, 1, 2, 3}; @@ -29,7 +29,7 @@ TEST(PointEquality, PointXYZI) TEST(PointEquality, PointXYZIRADRT) { - using autoware_point_types::PointXYZIRADRT; + using autoware::point_types::PointXYZIRADRT; PointXYZIRADRT pt0{0, 1, 2, 3, 4, 5, 6, 7, 8}; PointXYZIRADRT pt1{0, 1, 2, 3, 4, 5, 6, 7, 8}; @@ -38,7 +38,7 @@ TEST(PointEquality, PointXYZIRADRT) TEST(PointEquality, PointXYZIRCAEDT) { - using autoware_point_types::PointXYZIRCAEDT; + using autoware::point_types::PointXYZIRCAEDT; PointXYZIRCAEDT pt0{0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; PointXYZIRCAEDT pt1{0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; @@ -48,19 +48,19 @@ TEST(PointEquality, PointXYZIRCAEDT) TEST(PointEquality, FloatEq) { // test template - EXPECT_TRUE(autoware_point_types::float_eq(1, 1)); - EXPECT_TRUE(autoware_point_types::float_eq(1, 1)); + EXPECT_TRUE(autoware::point_types::float_eq(1, 1)); + EXPECT_TRUE(autoware::point_types::float_eq(1, 1)); // test floating point error - EXPECT_TRUE(autoware_point_types::float_eq(1, 1 + std::numeric_limits::epsilon())); + EXPECT_TRUE(autoware::point_types::float_eq(1, 1 + std::numeric_limits::epsilon())); // test difference of sign - EXPECT_FALSE(autoware_point_types::float_eq(2, -2)); - EXPECT_FALSE(autoware_point_types::float_eq(-2, 2)); + EXPECT_FALSE(autoware::point_types::float_eq(2, -2)); + EXPECT_FALSE(autoware::point_types::float_eq(-2, 2)); // small value difference - EXPECT_FALSE(autoware_point_types::float_eq(2, 2 + 10e-6)); + EXPECT_FALSE(autoware::point_types::float_eq(2, 2 + 10e-6)); // expect same value if epsilon is larger than difference - EXPECT_TRUE(autoware_point_types::float_eq(2, 2 + 10e-6, 10e-5)); + EXPECT_TRUE(autoware::point_types::float_eq(2, 2 + 10e-6, 10e-5)); } diff --git a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp index 06d2acf8a55fc..947ba02402697 100644 --- a/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp +++ b/localization/autoware_landmark_based_localizer/autoware_lidar_marker_localizer/src/lidar_marker_localizer.cpp @@ -14,9 +14,9 @@ #include "lidar_marker_localizer.hpp" +#include #include #include -#include #include #include @@ -338,8 +338,8 @@ std::vector LidarMarkerLocalizer::detect_landmarks( // TODO(YamatoAndo) // Transform sensor_frame to base_link - pcl::PointCloud::Ptr points_ptr( - new pcl::PointCloud); + pcl::PointCloud::Ptr points_ptr( + new pcl::PointCloud); pcl::fromROSMsg(*points_msg_ptr, *points_ptr); if (points_ptr->empty()) { @@ -347,11 +347,11 @@ std::vector LidarMarkerLocalizer::detect_landmarks( return std::vector{}; } - std::vector> ring_points(128); + std::vector> ring_points(128); float min_x = std::numeric_limits::max(); float max_x = std::numeric_limits::lowest(); - for (const autoware_point_types::PointXYZIRC & point : points_ptr->points) { + for (const autoware::point_types::PointXYZIRC & point : points_ptr->points) { ring_points[point.channel].push_back(point); min_x = std::min(min_x, point.x); max_x = std::max(max_x, point.x); @@ -365,12 +365,12 @@ std::vector LidarMarkerLocalizer::detect_landmarks( std::vector min_y(bin_num, std::numeric_limits::max()); // for each channel - for (const pcl::PointCloud & one_ring : ring_points) { + for (const pcl::PointCloud & one_ring : ring_points) { std::vector intensity_sum(bin_num, 0.0); std::vector intensity_num(bin_num, 0); std::vector average_intensity(bin_num, 0.0); - for (const autoware_point_types::PointXYZIRC & point : one_ring.points) { + for (const autoware::point_types::PointXYZIRC & point : one_ring.points) { const int bin_index = static_cast((point.x - min_x) / param_.resolution); intensity_sum[bin_index] += point.intensity; intensity_num[bin_index]++; @@ -507,15 +507,15 @@ sensor_msgs::msg::PointCloud2::SharedPtr LidarMarkerLocalizer::extract_marker_po const geometry_msgs::msg::Pose marker_pose) const { // convert from ROSMsg to PCL - pcl::shared_ptr> points_ptr( - new pcl::PointCloud); + pcl::shared_ptr> points_ptr( + new pcl::PointCloud); pcl::fromROSMsg(*points_msg_ptr, *points_ptr); - pcl::shared_ptr> marker_points_ptr( - new pcl::PointCloud); + pcl::shared_ptr> marker_points_ptr( + new pcl::PointCloud); // extract marker pointcloud - for (const autoware_point_types::PointXYZIRC & point : points_ptr->points) { + for (const autoware::point_types::PointXYZIRC & point : points_ptr->points) { const double xy_distance = std::sqrt( std::pow(point.x - marker_pose.position.x, 2.0) + std::pow(point.y - marker_pose.position.y, 2.0)); @@ -546,8 +546,8 @@ void LidarMarkerLocalizer::save_detected_marker_log( marker_points_msg_sensor_frame_ptr); // convert from ROSMsg to PCL - pcl::shared_ptr> - marker_points_sensor_frame_ptr(new pcl::PointCloud); + pcl::shared_ptr> + marker_points_sensor_frame_ptr(new pcl::PointCloud); pcl::fromROSMsg(*marker_points_msg_sensor_frame_ptr, *marker_points_sensor_frame_ptr); // to csv format diff --git a/perception/autoware_compare_map_segmentation/test/test_distance_based_compare_map_filter.cpp b/perception/autoware_compare_map_segmentation/test/test_distance_based_compare_map_filter.cpp index 3d4ee272d7eaf..2ed66b9875ef8 100644 --- a/perception/autoware_compare_map_segmentation/test/test_distance_based_compare_map_filter.cpp +++ b/perception/autoware_compare_map_segmentation/test/test_distance_based_compare_map_filter.cpp @@ -15,7 +15,7 @@ #include "../src/distance_based_compare_map_filter/node.hpp" #include -#include +#include #include #include @@ -24,8 +24,8 @@ #include using autoware::compare_map_segmentation::DistanceBasedCompareMapFilterComponent; -using autoware_point_types::PointXYZIRC; -using autoware_point_types::PointXYZIRCGenerator; +using autoware::point_types::PointXYZIRC; +using autoware::point_types::PointXYZIRCGenerator; using point_cloud_msg_wrapper::PointCloud2Modifier; using sensor_msgs::msg::PointCloud2; diff --git a/perception/autoware_compare_map_segmentation/test/test_voxel_based_approximate_compare_map_filter.cpp b/perception/autoware_compare_map_segmentation/test/test_voxel_based_approximate_compare_map_filter.cpp index e165efa640d15..816ba7e8174c7 100644 --- a/perception/autoware_compare_map_segmentation/test/test_voxel_based_approximate_compare_map_filter.cpp +++ b/perception/autoware_compare_map_segmentation/test/test_voxel_based_approximate_compare_map_filter.cpp @@ -15,7 +15,7 @@ #include "../src/voxel_based_approximate_compare_map_filter/node.hpp" #include -#include +#include #include #include @@ -24,8 +24,8 @@ #include using autoware::compare_map_segmentation::VoxelBasedApproximateCompareMapFilterComponent; -using autoware_point_types::PointXYZIRC; -using autoware_point_types::PointXYZIRCGenerator; +using autoware::point_types::PointXYZIRC; +using autoware::point_types::PointXYZIRCGenerator; using point_cloud_msg_wrapper::PointCloud2Modifier; using sensor_msgs::msg::PointCloud2; diff --git a/perception/autoware_compare_map_segmentation/test/test_voxel_based_compare_map_filter.cpp b/perception/autoware_compare_map_segmentation/test/test_voxel_based_compare_map_filter.cpp index 654d7443bd8d0..4fa0ab6321f1c 100644 --- a/perception/autoware_compare_map_segmentation/test/test_voxel_based_compare_map_filter.cpp +++ b/perception/autoware_compare_map_segmentation/test/test_voxel_based_compare_map_filter.cpp @@ -15,7 +15,7 @@ #include "../src/voxel_based_compare_map_filter/node.hpp" #include -#include +#include #include #include @@ -24,8 +24,8 @@ #include using autoware::compare_map_segmentation::VoxelBasedCompareMapFilterComponent; -using autoware_point_types::PointXYZIRC; -using autoware_point_types::PointXYZIRCGenerator; +using autoware::point_types::PointXYZIRC; +using autoware::point_types::PointXYZIRCGenerator; using point_cloud_msg_wrapper::PointCloud2Modifier; using sensor_msgs::msg::PointCloud2; diff --git a/perception/autoware_compare_map_segmentation/test/test_voxel_distance_based_compare_map_filter.cpp b/perception/autoware_compare_map_segmentation/test/test_voxel_distance_based_compare_map_filter.cpp index 4440a5eddc426..946eef9bd0a0e 100644 --- a/perception/autoware_compare_map_segmentation/test/test_voxel_distance_based_compare_map_filter.cpp +++ b/perception/autoware_compare_map_segmentation/test/test_voxel_distance_based_compare_map_filter.cpp @@ -15,7 +15,7 @@ #include "../src/voxel_distance_based_compare_map_filter/node.hpp" #include -#include +#include #include #include @@ -24,8 +24,8 @@ #include using autoware::compare_map_segmentation::VoxelDistanceBasedCompareMapFilterComponent; -using autoware_point_types::PointXYZIRC; -using autoware_point_types::PointXYZIRCGenerator; +using autoware::point_types::PointXYZIRC; +using autoware::point_types::PointXYZIRCGenerator; using point_cloud_msg_wrapper::PointCloud2Modifier; using sensor_msgs::msg::PointCloud2; diff --git a/perception/autoware_euclidean_cluster/test/test_voxel_grid_based_euclidean_cluster.cpp b/perception/autoware_euclidean_cluster/test/test_voxel_grid_based_euclidean_cluster.cpp index 7d2edbe0de0d7..759e2b3653868 100644 --- a/perception/autoware_euclidean_cluster/test/test_voxel_grid_based_euclidean_cluster.cpp +++ b/perception/autoware_euclidean_cluster/test/test_voxel_grid_based_euclidean_cluster.cpp @@ -14,7 +14,7 @@ #include "autoware/euclidean_cluster/voxel_grid_based_euclidean_cluster.hpp" -#include +#include #include #include @@ -23,7 +23,7 @@ #include -using autoware_point_types::PointXYZI; +using autoware::point_types::PointXYZI; void setPointCloud2Fields(sensor_msgs::msg::PointCloud2 & pointcloud) { pointcloud.fields.resize(4); diff --git a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp index 03a950f68bbd2..ba3f848a0e9a7 100644 --- a/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp +++ b/perception/autoware_image_projection_based_fusion/src/pointpainting_fusion/node.cpp @@ -14,7 +14,7 @@ #include "autoware/image_projection_based_fusion/pointpainting_fusion/node.hpp" -#include "autoware_point_types/types.hpp" +#include "autoware/point_types/types.hpp" #include #include @@ -293,15 +293,15 @@ void PointPaintingFusionNode::fuseOnSingleImage( // sensor_msgs::msg::PointCloud2 transformed_pointcloud; // tf2::doTransform(painted_pointcloud_msg, transformed_pointcloud, transform_stamped); - const auto x_offset = - painted_pointcloud_msg.fields.at(static_cast(autoware_point_types::PointXYZIRCIndex::X)) - .offset; - const auto y_offset = - painted_pointcloud_msg.fields.at(static_cast(autoware_point_types::PointXYZIRCIndex::Y)) - .offset; - const auto z_offset = - painted_pointcloud_msg.fields.at(static_cast(autoware_point_types::PointXYZIRCIndex::Z)) - .offset; + const auto x_offset = painted_pointcloud_msg.fields + .at(static_cast(autoware::point_types::PointXYZIRCIndex::X)) + .offset; + const auto y_offset = painted_pointcloud_msg.fields + .at(static_cast(autoware::point_types::PointXYZIRCIndex::Y)) + .offset; + const auto z_offset = painted_pointcloud_msg.fields + .at(static_cast(autoware::point_types::PointXYZIRCIndex::Z)) + .offset; const auto class_offset = painted_pointcloud_msg.fields.at(4).offset; const auto p_step = painted_pointcloud_msg.point_step; // projection matrix diff --git a/perception/autoware_image_projection_based_fusion/test/test_utils.cpp b/perception/autoware_image_projection_based_fusion/test/test_utils.cpp index 5fbd313d75dfe..ac179c66dd3d0 100644 --- a/perception/autoware_image_projection_based_fusion/test/test_utils.cpp +++ b/perception/autoware_image_projection_based_fusion/test/test_utils.cpp @@ -13,11 +13,11 @@ // limitations under the License. #include -#include +#include #include -using autoware_point_types::PointXYZI; +using autoware::point_types::PointXYZI; void setPointCloud2Fields(sensor_msgs::msg::PointCloud2 & pointcloud) { diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/voxel_generator.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/voxel_generator.hpp index 9f32c27a8841b..d420da6716cb1 100644 --- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/voxel_generator.hpp +++ b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/preprocess/voxel_generator.hpp @@ -27,7 +27,7 @@ #include #endif -#include +#include #include @@ -39,7 +39,7 @@ namespace autoware::lidar_transfusion { constexpr std::size_t AFF_MAT_SIZE = 16; // 4x4 matrix -constexpr std::size_t MAX_CLOUD_STEP_SIZE = sizeof(autoware_point_types::PointXYZIRCAEDT); +constexpr std::size_t MAX_CLOUD_STEP_SIZE = sizeof(autoware::point_types::PointXYZIRCAEDT); class VoxelGenerator { diff --git a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/ros_utils.hpp b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/ros_utils.hpp index 37b364ecf8a9d..c203693426ab3 100644 --- a/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/ros_utils.hpp +++ b/perception/autoware_lidar_transfusion/include/autoware/lidar_transfusion/ros_utils.hpp @@ -17,7 +17,7 @@ #include "autoware/lidar_transfusion/utils.hpp" -#include +#include #include #include @@ -45,10 +45,10 @@ namespace autoware::lidar_transfusion { using sensor_msgs::msg::PointField; -CHECK_FIELD(0, float, autoware_point_types::PointXYZIRCAEDT, x); -CHECK_FIELD(4, float, autoware_point_types::PointXYZIRCAEDT, y); -CHECK_FIELD(8, float, autoware_point_types::PointXYZIRCAEDT, z); -CHECK_FIELD(12, uint8_t, autoware_point_types::PointXYZIRCAEDT, intensity); +CHECK_FIELD(0, float, autoware::point_types::PointXYZIRCAEDT, x); +CHECK_FIELD(4, float, autoware::point_types::PointXYZIRCAEDT, y); +CHECK_FIELD(8, float, autoware::point_types::PointXYZIRCAEDT, z); +CHECK_FIELD(12, uint8_t, autoware::point_types::PointXYZIRCAEDT, intensity); struct CloudInfo { @@ -64,7 +64,7 @@ struct CloudInfo uint8_t y_count{1}; uint8_t z_count{1}; uint8_t intensity_count{1}; - uint32_t point_step{sizeof(autoware_point_types::PointXYZIRCAEDT)}; + uint32_t point_step{sizeof(autoware::point_types::PointXYZIRCAEDT)}; bool is_bigendian{false}; bool operator!=(const CloudInfo & rhs) const diff --git a/perception/autoware_lidar_transfusion/test/test_voxel_generator.cpp b/perception/autoware_lidar_transfusion/test/test_voxel_generator.cpp index 5a60c206314bf..df546dbde6d97 100644 --- a/perception/autoware_lidar_transfusion/test/test_voxel_generator.cpp +++ b/perception/autoware_lidar_transfusion/test/test_voxel_generator.cpp @@ -18,7 +18,7 @@ #include "autoware/lidar_transfusion/utils.hpp" #include "gtest/gtest.h" -#include +#include #include "sensor_msgs/point_cloud2_iterator.hpp" @@ -52,7 +52,7 @@ void VoxelGeneratorTest::SetUp() // Set up the fields point_cloud_msg_wrapper::PointCloud2Modifier< - autoware_point_types::PointXYZIRCAEDT, autoware_point_types::PointXYZIRCAEDTGenerator> + autoware::point_types::PointXYZIRCAEDT, autoware::point_types::PointXYZIRCAEDTGenerator> modifier{*cloud1_, lidar_frame_}; // Resize the cloud to hold points_per_pointcloud_ points diff --git a/perception/autoware_raindrop_cluster_filter/test/test_low_intensity_cluster_filter.cpp b/perception/autoware_raindrop_cluster_filter/test/test_low_intensity_cluster_filter.cpp index e6d058ef8f437..e7644ce45e443 100644 --- a/perception/autoware_raindrop_cluster_filter/test/test_low_intensity_cluster_filter.cpp +++ b/perception/autoware_raindrop_cluster_filter/test/test_low_intensity_cluster_filter.cpp @@ -15,7 +15,7 @@ #include "../src/low_intensity_cluster_filter_node.hpp" #include -#include +#include #include #include @@ -27,9 +27,9 @@ #include using autoware::low_intensity_cluster_filter::LowIntensityClusterFilter; +using autoware::point_types::PointXYZIRC; +using autoware::point_types::PointXYZIRCGenerator; using autoware_perception_msgs::msg::ObjectClassification; -using autoware_point_types::PointXYZIRC; -using autoware_point_types::PointXYZIRCGenerator; using point_cloud_msg_wrapper::PointCloud2Modifier; using tier4_perception_msgs::msg::DetectedObjectsWithFeature; using tier4_perception_msgs::msg::DetectedObjectWithFeature; @@ -64,7 +64,7 @@ DetectedObjectsWithFeature create_cluster( feature_obj.object.classification.resize(1); feature_obj.object.classification[0].label = label; sensor_msgs::msg::PointCloud2 cluster; - PointCloud2Modifier modifier( + PointCloud2Modifier modifier( cluster, "base_link"); for (int i = 0; i < cluster_size; i++) { PointXYZIRC point; diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp index 977adc59cd7e5..40adad3521f8d 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_and_time_sync_nodelet.hpp @@ -61,7 +61,7 @@ #include // ROS includes -#include "autoware_point_types/types.hpp" +#include "autoware/point_types/types.hpp" #include #include @@ -88,7 +88,7 @@ namespace autoware::pointcloud_preprocessor { -using autoware_point_types::PointXYZIRC; +using autoware::point_types::PointXYZIRC; using point_cloud_msg_wrapper::PointCloud2Modifier; /** \brief @b PointCloudConcatenateDataSynchronizerComponent is a special form of data diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp index b7e0e86ca1d3a..0e959eedae1b6 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/concatenate_data/concatenate_pointclouds.hpp @@ -61,10 +61,10 @@ #include // ROS includes +#include #include #include #include -#include #include #include @@ -86,7 +86,7 @@ namespace autoware::pointcloud_preprocessor { -using autoware_point_types::PointXYZIRC; +using autoware::point_types::PointXYZIRC; using point_cloud_msg_wrapper::PointCloud2Modifier; /** \brief @b PointCloudConcatenationComponent is a special form of data * synchronizer: it listens for a set of input PointCloud messages on the same topic, diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp index cf396e3e3a4be..b5aa9d56a0dfb 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp @@ -15,9 +15,9 @@ #ifndef AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODE_HPP_ #define AUTOWARE__POINTCLOUD_PREPROCESSOR__OUTLIER_FILTER__RING_OUTLIER_FILTER_NODE_HPP_ +#include "autoware/point_types/types.hpp" #include "autoware/pointcloud_preprocessor/filter.hpp" #include "autoware/pointcloud_preprocessor/transform_info.hpp" -#include "autoware_point_types/types.hpp" #include #include @@ -40,9 +40,9 @@ using point_cloud_msg_wrapper::PointCloud2Modifier; class RingOutlierFilterComponent : public autoware::pointcloud_preprocessor::Filter { protected: - using InputPointIndex = autoware_point_types::PointXYZIRCAEDTIndex; - using InputPointType = autoware_point_types::PointXYZIRCAEDT; - using OutputPointType = autoware_point_types::PointXYZIRC; + using InputPointIndex = autoware::point_types::PointXYZIRCAEDTIndex; + using InputPointType = autoware::point_types::PointXYZIRCAEDT; + using OutputPointType = autoware::point_types::PointXYZIRC; virtual void filter( const PointCloud2ConstPtr & input, const IndicesPtr & indices, PointCloud2 & output); diff --git a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp index b02860a6f112e..d36fcb36a7be1 100644 --- a/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp +++ b/sensing/autoware_pointcloud_preprocessor/include/autoware/pointcloud_preprocessor/time_synchronizer/time_synchronizer_node.hpp @@ -61,10 +61,10 @@ #include // ROS includes +#include #include #include #include -#include #include #include @@ -87,7 +87,7 @@ namespace autoware::pointcloud_preprocessor { -using autoware_point_types::PointXYZIRC; +using autoware::point_types::PointXYZIRC; using point_cloud_msg_wrapper::PointCloud2Modifier; // cspell:ignore Yoshi /** \brief @b PointCloudDataSynchronizerComponent is a special form of data diff --git a/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp index 6703eb6b70741..26be762acca43 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/blockage_diag/blockage_diag_node.cpp @@ -14,14 +14,14 @@ #include "autoware/pointcloud_preprocessor/blockage_diag/blockage_diag_node.hpp" -#include "autoware_point_types/types.hpp" +#include "autoware/point_types/types.hpp" #include #include namespace autoware::pointcloud_preprocessor { -using autoware_point_types::PointXYZIRCAEDT; +using autoware::point_types::PointXYZIRCAEDT; using diagnostic_msgs::msg::DiagnosticStatus; BlockageDiagComponent::BlockageDiagComponent(const rclcpp::NodeOptions & options) diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp index d0911f769d3bd..a67c9f7f018e1 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_and_time_sync_nodelet.cpp @@ -481,7 +481,7 @@ void PointCloudConcatenateDataSynchronizerComponent::convertToXYZIRCCloud( { output_ptr->header = input_ptr->header; - PointCloud2Modifier output_modifier{ + PointCloud2Modifier output_modifier{ *output_ptr, input_ptr->header.frame_id}; output_modifier.reserve(input_ptr->width); diff --git a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp index 5e1911c93409d..ba29389b88bf7 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/concatenate_data/concatenate_pointclouds.cpp @@ -311,7 +311,7 @@ void PointCloudConcatenationComponent::convertToXYZIRCCloud( { output_ptr->header = input_ptr->header; - PointCloud2Modifier output_modifier{ + PointCloud2Modifier output_modifier{ *output_ptr, input_ptr->header.frame_id}; output_modifier.reserve(input_ptr->width); diff --git a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp index d3f81473ed06f..a8024e02de2c1 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/dual_return_outlier_filter_node.cpp @@ -14,7 +14,7 @@ #include "autoware/pointcloud_preprocessor/outlier_filter/dual_return_outlier_filter_node.hpp" -#include "autoware_point_types/types.hpp" +#include "autoware/point_types/types.hpp" #include @@ -28,8 +28,8 @@ namespace autoware::pointcloud_preprocessor { -using autoware_point_types::PointXYZIRCAEDT; -using autoware_point_types::ReturnType; +using autoware::point_types::PointXYZIRCAEDT; +using autoware::point_types::ReturnType; using diagnostic_msgs::msg::DiagnosticStatus; DualReturnOutlierFilterComponent::DualReturnOutlierFilterComponent( diff --git a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp index bf140e662440b..59000d71b8ad6 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/outlier_filter/ring_outlier_filter_node.cpp @@ -14,7 +14,7 @@ #include "autoware/pointcloud_preprocessor/outlier_filter/ring_outlier_filter_node.hpp" -#include "autoware_point_types/types.hpp" +#include "autoware/point_types/types.hpp" #include @@ -22,7 +22,7 @@ #include namespace autoware::pointcloud_preprocessor { -using autoware_point_types::PointXYZIRADRT; +using autoware::point_types::PointXYZIRADRT; RingOutlierFilterComponent::RingOutlierFilterComponent(const rclcpp::NodeOptions & options) : Filter("RingOutlierFilter", options) diff --git a/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp b/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp index e34c165383867..5bf5069f1200f 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/time_synchronizer/time_synchronizer_node.cpp @@ -413,7 +413,7 @@ void PointCloudDataSynchronizerComponent::convertToXYZIRCCloud( { output_ptr->header = input_ptr->header; - PointCloud2Modifier output_modifier{ + PointCloud2Modifier output_modifier{ *output_ptr, input_ptr->header.frame_id}; output_modifier.reserve(input_ptr->width); diff --git a/sensing/autoware_pointcloud_preprocessor/src/utility/memory.cpp b/sensing/autoware_pointcloud_preprocessor/src/utility/memory.cpp index 7e265bcfb4960..c1fd55943d13a 100644 --- a/sensing/autoware_pointcloud_preprocessor/src/utility/memory.cpp +++ b/sensing/autoware_pointcloud_preprocessor/src/utility/memory.cpp @@ -14,14 +14,14 @@ #include "autoware/pointcloud_preprocessor/utility/memory.hpp" -#include +#include namespace autoware::pointcloud_preprocessor::utils { bool is_data_layout_compatible_with_point_xyzi(const sensor_msgs::msg::PointCloud2 & input) { - using PointIndex = autoware_point_types::PointXYZIIndex; - using autoware_point_types::PointXYZI; + using PointIndex = autoware::point_types::PointXYZIIndex; + using autoware::point_types::PointXYZI; if (input.fields.size() < 4) { return false; } @@ -51,8 +51,8 @@ bool is_data_layout_compatible_with_point_xyzi(const sensor_msgs::msg::PointClou bool is_data_layout_compatible_with_point_xyzirc(const sensor_msgs::msg::PointCloud2 & input) { - using PointIndex = autoware_point_types::PointXYZIRCIndex; - using autoware_point_types::PointXYZIRC; + using PointIndex = autoware::point_types::PointXYZIRCIndex; + using autoware::point_types::PointXYZIRC; if (input.fields.size() < 6) { return false; } @@ -93,8 +93,8 @@ bool is_data_layout_compatible_with_point_xyzirc(const sensor_msgs::msg::PointCl bool is_data_layout_compatible_with_point_xyziradrt(const sensor_msgs::msg::PointCloud2 & input) { - using PointIndex = autoware_point_types::PointXYZIRADRTIndex; - using autoware_point_types::PointXYZIRADRT; + using PointIndex = autoware::point_types::PointXYZIRADRTIndex; + using autoware::point_types::PointXYZIRADRT; if (input.fields.size() < 9) { return false; } @@ -149,8 +149,8 @@ bool is_data_layout_compatible_with_point_xyziradrt(const sensor_msgs::msg::Poin bool is_data_layout_compatible_with_point_xyzircaedt(const sensor_msgs::msg::PointCloud2 & input) { - using PointIndex = autoware_point_types::PointXYZIRCAEDTIndex; - using autoware_point_types::PointXYZIRCAEDT; + using PointIndex = autoware::point_types::PointXYZIRCAEDTIndex; + using autoware::point_types::PointXYZIRCAEDT; if (input.fields.size() != 10) { return false; }