Skip to content

Commit

Permalink
fix: modify build error of point cloud filters in rolling (tier4#804)
Browse files Browse the repository at this point in the history
* fix(pointcloud_preprocessor): modify build error in rolling

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* fix(ground_segmentation): modify build error in rolling

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* fix(compare_map_segmentation): modify build error in rolling

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* fix(occupancy_grid_map_outlier_filter): modify build error in rolling

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* fix(euclidean_cluster): modify build error in rolling

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* fix(detection_by_tracker): modify build error in rolling

Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>

* ci(pre-commit): autofix

Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
  • Loading branch information
2 people authored and boyali committed Oct 3, 2022
1 parent ef22b9c commit 974cee7
Show file tree
Hide file tree
Showing 41 changed files with 97 additions and 41 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ class CompareElevationMapFilterComponent : public pointcloud_preprocessor::Filte
void elevationMapCallback(const grid_map_msgs::msg::GridMap::ConstSharedPtr elevation_map);

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit CompareElevationMapFilterComponent(const rclcpp::NodeOptions & options);
};
} // namespace compare_map_segmentation
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class DistanceBasedCompareMapFilterComponent : public pointcloud_preprocessor::F
rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector<rclcpp::Parameter> & p);

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit DistanceBasedCompareMapFilterComponent(const rclcpp::NodeOptions & options);
};
} // namespace compare_map_segmentation
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ class VoxelBasedApproximateCompareMapFilterComponent : public pointcloud_preproc
rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector<rclcpp::Parameter> & p);

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit VoxelBasedApproximateCompareMapFilterComponent(const rclcpp::NodeOptions & options);
};
} // namespace compare_map_segmentation
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ class VoxelBasedCompareMapFilterComponent : public pointcloud_preprocessor::Filt
rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector<rclcpp::Parameter> & p);

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit VoxelBasedCompareMapFilterComponent(const rclcpp::NodeOptions & options);
};
} // namespace compare_map_segmentation
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class VoxelDistanceBasedCompareMapFilterComponent : public pointcloud_preprocess
rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector<rclcpp::Parameter> & p);

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit VoxelDistanceBasedCompareMapFilterComponent(const rclcpp::NodeOptions & options);
};
} // namespace compare_map_segmentation
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ void DistanceBasedCompareMapFilterComponent::input_target_callback(const PointCl
{
pcl::PointCloud<pcl::PointXYZ> map_pcl;
pcl::fromROSMsg<pcl::PointXYZ>(*map, map_pcl);
const auto map_pcl_ptr = boost::make_shared<const pcl::PointCloud<pcl::PointXYZ>>(map_pcl);
const auto map_pcl_ptr = pcl::make_shared<pcl::PointCloud<pcl::PointXYZ>>(map_pcl);

boost::mutex::scoped_lock lock(mutex_);
map_ptr_ = map_pcl_ptr;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ void VoxelBasedApproximateCompareMapFilterComponent::input_target_callback(
{
pcl::PointCloud<pcl::PointXYZ> map_pcl;
pcl::fromROSMsg<pcl::PointXYZ>(*map, map_pcl);
const auto map_pcl_ptr = boost::make_shared<const pcl::PointCloud<pcl::PointXYZ>>(map_pcl);
const auto map_pcl_ptr = pcl::make_shared<pcl::PointCloud<pcl::PointXYZ>>(map_pcl);

boost::mutex::scoped_lock lock(mutex_);
set_map_in_voxel_grid_ = true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -239,7 +239,7 @@ void VoxelBasedCompareMapFilterComponent::input_target_callback(const PointCloud
{
pcl::PointCloud<pcl::PointXYZ> map_pcl;
pcl::fromROSMsg<pcl::PointXYZ>(*map, map_pcl);
const auto map_pcl_ptr = boost::make_shared<const pcl::PointCloud<pcl::PointXYZ>>(map_pcl);
const auto map_pcl_ptr = pcl::make_shared<pcl::PointCloud<pcl::PointXYZ>>(map_pcl);

boost::mutex::scoped_lock lock(mutex_);
set_map_in_voxel_grid_ = true;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ void VoxelDistanceBasedCompareMapFilterComponent::input_target_callback(
{
pcl::PointCloud<pcl::PointXYZ> map_pcl;
pcl::fromROSMsg<pcl::PointXYZ>(*map, map_pcl);
const auto map_pcl_ptr = boost::make_shared<const pcl::PointCloud<pcl::PointXYZ>>(map_pcl);
const auto map_pcl_ptr = pcl::make_shared<pcl::PointCloud<pcl::PointXYZ>>(map_pcl);

boost::mutex::scoped_lock lock(mutex_);
tf_input_frame_ = map_pcl_ptr->header.frame_id;
Expand Down
2 changes: 1 addition & 1 deletion perception/detection_by_tracker/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ endif()
find_package(ament_cmake_auto REQUIRED)

### Find PCL Dependencies
find_package(PCL REQUIRED QUIET COMPONENTS common search filters segmentation)
find_package(PCL REQUIRED)

### Find Eigen Dependencies
find_package(eigen3_cmake_module REQUIRED)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,13 @@
#include <tf2/LinearMath/Transform.h>
#include <tf2/convert.h>
#include <tf2/transform_datatypes.h>

#ifdef USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#else
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif

#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,13 @@
#include <tf2/LinearMath/Transform.h>
#include <tf2/convert.h>
#include <tf2/transform_datatypes.h>

#ifdef USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#else
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif

#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

Expand Down
2 changes: 1 addition & 1 deletion perception/euclidean_cluster/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

find_package(ament_cmake_auto REQUIRED)
find_package(PCL REQUIRED QUIET COMPONENTS common search filters segmentation)
find_package(PCL REQUIRED)
ament_auto_find_build_dependencies()


Expand Down
11 changes: 6 additions & 5 deletions perception/ground_segmentation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,11 +32,12 @@ ament_auto_find_build_dependencies()

include_directories(
include
${Boost_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${GRID_MAP_INCLUDE_DIR}
SYSTEM
${Boost_INCLUDE_DIRS}
${PCL_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${GRID_MAP_INCLUDE_DIR}
)

ament_auto_add_library(ground_segmentation SHARED
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,13 @@
#include <pcl/segmentation/sac_segmentation.h>
#include <pcl_conversions/pcl_conversions.h>
#include <tf2/transform_datatypes.h>

#ifdef USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
#include <tf2_eigen/tf2_eigen.h>
#else
#include <tf2_eigen/tf2_eigen.hpp>
#endif

#include <tf2_ros/transform_listener.h>

#include <chrono>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,13 @@
#include <pcl/filters/voxel_grid.h>
#include <pcl_conversions/pcl_conversions.h>
#include <tf2/transform_datatypes.h>

#ifdef USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
#include <tf2_eigen/tf2_eigen.h>
#else
#include <tf2_eigen/tf2_eigen.hpp>
#endif

#include <tf2_ros/transform_listener.h>

#include <chrono>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,13 @@
#include <pcl/filters/voxel_grid.h>
#include <pcl_conversions/pcl_conversions.h>
#include <tf2/transform_datatypes.h>

#ifdef USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
#include <tf2_eigen/tf2_eigen.h>
#else
#include <tf2_eigen/tf2_eigen.hpp>
#endif

#include <tf2_ros/transform_listener.h>

#include <string>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
#include <pcl_ros/transforms.hpp>

#include <pcl/common/centroid.h>
#include <tf2_eigen/tf2_eigen.h>

#include <limits>
#include <random>
Expand Down Expand Up @@ -187,7 +186,7 @@ void RANSACGroundFilterComponent::extractPointsIndices(
{
pcl::ExtractIndices<PointType> extract_ground;
extract_ground.setInputCloud(in_cloud_ptr);
extract_ground.setIndices(boost::make_shared<pcl::PointIndices>(in_indices));
extract_ground.setIndices(pcl::make_shared<pcl::PointIndices>(in_indices));

extract_ground.setNegative(false); // true removes the indices, false leaves only the indices
extract_ground.filter(*out_only_indices_cloud_ptr);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -297,7 +297,7 @@ void RayGroundFilterComponent::ExtractPointsIndices(
{
pcl::ExtractIndices<PointType_> extract_ground;
extract_ground.setInputCloud(in_cloud_ptr);
extract_ground.setIndices(boost::make_shared<pcl::PointIndices>(in_indices));
extract_ground.setIndices(pcl::make_shared<pcl::PointIndices>(in_indices));

extract_ground.setNegative(false); // true removes the indices, false leaves only the indices
extract_ground.filter(*out_only_indices_cloud_ptr);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
#include <message_filters/synchronizer.h>
#include <pcl/filters/extract_indices.h>
#include <pcl/filters/radius_outlier_removal.h>
#include <pcl/search/kdtree.h>
#include <tf2_ros/buffer.h>
#include <tf2_ros/message_filter.h>
#include <tf2_ros/transform_listener.h>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,12 @@

#include <pcl/point_types.h>
#include <pcl_conversions/pcl_conversions.h>

#ifdef USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
#include <tf2_eigen/tf2_eigen.h>
#else
#include <tf2_eigen/tf2_eigen.hpp>
#endif

#include <algorithm>
#include <memory>
Expand Down Expand Up @@ -103,7 +108,7 @@ RadiusSearch2dfilter::RadiusSearch2dfilter(rclcpp::Node & node)
node.declare_parameter("radius_search_2d_filter.min_points_and_distance_ratio", 400.0f);
min_points_ = node.declare_parameter("radius_search_2d_filter.min_points", 4);
max_points_ = node.declare_parameter("radius_search_2d_filter.max_points", 70);
kd_tree_ = boost::make_shared<pcl::search::KdTree<pcl::PointXY>>(false);
kd_tree_ = pcl::make_shared<pcl::search::KdTree<pcl::PointXY>>(false);
}

void RadiusSearch2dfilter::filter(
Expand Down
7 changes: 7 additions & 0 deletions sensing/pointcloud_preprocessor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,13 @@ if(OPENMP_FOUND)
)
endif()

# workaround to allow deprecated header to build on both galactic and rolling
if(${tf2_geometry_msgs_VERSION} VERSION_LESS 0.18.0)
target_compile_definitions(pointcloud_preprocessor_filter PRIVATE
USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
)
endif()

# ========== Concatenate data ==========
rclcpp_components_register_node(pointcloud_preprocessor_filter
PLUGIN "pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ class BlockageDiagComponent : public pointcloud_preprocessor::Filter
std::string lidar_model_;

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit BlockageDiagComponent(const rclcpp::NodeOptions & options);
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,8 @@ class PointCloudConcatenateDataSynchronizerComponent : public rclcpp::Node
sensor_msgs::msg::PointCloud2::SharedPtr & output_ptr);
void setPeriod(const int64_t new_period);
void cloud_callback(
const sensor_msgs::msg::PointCloud2::SharedPtr & input_ptr, const std::string & topic_name);
const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_ptr,
const std::string & topic_name);
void twist_callback(const autoware_auto_vehicle_msgs::msg::VelocityReport::ConstSharedPtr input);
void timer_callback();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ class CropBoxFilterComponent : public pointcloud_preprocessor::Filter
rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector<rclcpp::Parameter> & p);

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit CropBoxFilterComponent(const rclcpp::NodeOptions & options);
};
} // namespace pointcloud_preprocessor
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,13 @@

#include <tf2/convert.h>
#include <tf2/transform_datatypes.h>

#ifdef USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#else
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#endif

#include <tf2_ros/buffer.h>
#include <tf2_ros/transform_listener.h>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ class ApproximateDownsampleFilterComponent : public pointcloud_preprocessor::Fil
double voxel_size_z_;

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit ApproximateDownsampleFilterComponent(const rclcpp::NodeOptions & options);
};
} // namespace pointcloud_preprocessor
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ class RandomDownsampleFilterComponent : public pointcloud_preprocessor::Filter
rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector<rclcpp::Parameter> & p);

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit RandomDownsampleFilterComponent(const rclcpp::NodeOptions & options);
};
} // namespace pointcloud_preprocessor
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ class VoxelGridDownsampleFilterComponent : public pointcloud_preprocessor::Filte
rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector<rclcpp::Parameter> & p);

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit VoxelGridDownsampleFilterComponent(const rclcpp::NodeOptions & options);
};
} // namespace pointcloud_preprocessor
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -124,6 +124,7 @@ class Filter : public rclcpp::Node
using ApproximateTimeSyncPolicy =
message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud2, PointIndices>>;

PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit Filter(
const std::string & filter_name = "pointcloud_preprocessor_filter",
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
Expand Down Expand Up @@ -264,9 +265,6 @@ class Filter : public rclcpp::Node
void input_indices_callback(const PointCloud2ConstPtr cloud, const PointIndicesConstPtr indices);

void setupTF();

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
};
} // namespace pointcloud_preprocessor

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ class DualReturnOutlierFilterComponent : public pointcloud_preprocessor::Filter
float max_distance_;

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit DualReturnOutlierFilterComponent(const rclcpp::NodeOptions & options);
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class RadiusSearch2DOutlierFilterComponent : public pointcloud_preprocessor::Fil
rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector<rclcpp::Parameter> & p);

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit RadiusSearch2DOutlierFilterComponent(const rclcpp::NodeOptions & options);
};
} // namespace pointcloud_preprocessor
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,7 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter
}

public:
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit RingOutlierFilterComponent(const rclcpp::NodeOptions & options);
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ class VoxelGridOutlierFilterComponent : public pointcloud_preprocessor::Filter
pcl::VoxelGrid<pcl::PointXYZ> voxel_filter;

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit VoxelGridOutlierFilterComponent(const rclcpp::NodeOptions & option);
};
} // namespace pointcloud_preprocessor
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ class PassThroughFilterComponent : public pointcloud_preprocessor::Filter
rcl_interfaces::msg::SetParametersResult paramCallback(const std::vector<rclcpp::Parameter> & p);

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit PassThroughFilterComponent(const rclcpp::NodeOptions & options);
};
} // namespace pointcloud_preprocessor
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ class PassThroughFilterUInt16Component : public pointcloud_preprocessor::Filter
pcl::PassThroughUInt16<pcl::PCLPointCloud2> impl_;

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
PCL_MAKE_ALIGNED_OPERATOR_NEW
explicit PassThroughFilterUInt16Component(const rclcpp::NodeOptions & options);
};
} // namespace pointcloud_preprocessor
Expand Down
Loading

0 comments on commit 974cee7

Please sign in to comment.