Move filter() function implementation for all filters (#405)

This commit is contained in:
Andrew Symington 2023-02-22 11:20:09 -08:00 committed by GitHub
parent b52e7a7ab1
commit 3966b71ad6
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
14 changed files with 111 additions and 79 deletions

View File

@ -63,17 +63,7 @@ protected:
inline void
filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output) override
{
std::lock_guard<std::mutex> lock(mutex_);
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, output);
}
PointCloud2 & output) override;
/** \brief Parameter callback
* \param params parameter values to set

View File

@ -61,17 +61,7 @@ protected:
inline void
filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output)
{
std::lock_guard<std::mutex> lock(mutex_);
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, output);
}
PointCloud2 & output) override;
/** \brief Parameter callback
* \param params parameter values to set

View File

@ -60,17 +60,7 @@ protected:
inline void
filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output) override
{
std::lock_guard<std::mutex> lock(mutex_);
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, output);
}
PointCloud2 & output) override;
/** \brief Parameter callback
* \param params parameter values to set

View File

@ -68,19 +68,7 @@ protected:
inline void
filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output)
{
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::ModelCoefficients::Ptr pcl_model(new pcl::ModelCoefficients);
pcl_conversions::toPCL(*(model_), *(pcl_model));
impl_.setModelCoefficients(pcl_model);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, output);
}
PointCloud2 & output) override;
private:
/** \brief A pointer to the vector of model coefficients. */

View File

@ -61,17 +61,7 @@ protected:
inline void
filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output) override
{
std::lock_guard<std::mutex> lock(mutex_);
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, output);
}
PointCloud2 & output) override;
/** \brief Parameter callback
* \param params parameter values to set

View File

@ -67,17 +67,7 @@ protected:
inline void
filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output) override
{
std::lock_guard<std::mutex> lock(mutex_);
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, output);
}
PointCloud2 & output) override;
/** \brief Parameter callback
* \param params parameter values to set

View File

@ -59,17 +59,7 @@ protected:
inline void
filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output) override
{
std::lock_guard<std::mutex> lock(mutex_);
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, output);
}
PointCloud2 & output) override;
/** \brief Parameter callback
* \param params parameter values to set

View File

@ -160,6 +160,21 @@ pcl_ros::CropBox::CropBox(const rclcpp::NodeOptions & options)
subscribe();
}
void
pcl_ros::CropBox::filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output)
{
std::lock_guard<std::mutex> lock(mutex_);
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, output);
}
//////////////////////////////////////////////////////////////////////////////////////////////
rcl_interfaces::msg::SetParametersResult

View File

@ -60,6 +60,21 @@ pcl_ros::ExtractIndices::ExtractIndices(const rclcpp::NodeOptions & options)
subscribe();
}
void
pcl_ros::ExtractIndices::filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output)
{
std::lock_guard<std::mutex> lock(mutex_);
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, output);
}
//////////////////////////////////////////////////////////////////////////////////////////////
rcl_interfaces::msg::SetParametersResult
pcl_ros::ExtractIndices::config_callback(const std::vector<rclcpp::Parameter> & params)

View File

@ -68,6 +68,20 @@ pcl_ros::PassThrough::PassThrough(const rclcpp::NodeOptions & options)
subscribe();
}
void pcl_ros::PassThrough::filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output)
{
std::lock_guard<std::mutex> lock(mutex_);
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, output);
}
//////////////////////////////////////////////////////////////////////////////////////////////
rcl_interfaces::msg::SetParametersResult
pcl_ros::PassThrough::config_callback(const std::vector<rclcpp::Parameter> & params)

View File

@ -80,6 +80,23 @@ pcl_ros::ProjectInliers::ProjectInliers(const rclcpp::NodeOptions & options)
subscribe();
}
void
pcl_ros::ProjectInliers::filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output)
{
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::ModelCoefficients::Ptr pcl_model(new pcl::ModelCoefficients);
pcl_conversions::toPCL(*(model_), *(pcl_model));
impl_.setModelCoefficients(pcl_model);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, output);
}
//////////////////////////////////////////////////////////////////////////////////////////////
void
pcl_ros::ProjectInliers::subscribe()

View File

@ -83,6 +83,21 @@ pcl_ros::RadiusOutlierRemoval::RadiusOutlierRemoval(const rclcpp::NodeOptions &
subscribe();
}
void
pcl_ros::RadiusOutlierRemoval::filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output)
{
std::lock_guard<std::mutex> lock(mutex_);
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, output);
}
//////////////////////////////////////////////////////////////////////////////////////////////
rcl_interfaces::msg::SetParametersResult
pcl_ros::RadiusOutlierRemoval::config_callback(const std::vector<rclcpp::Parameter> & params)

View File

@ -92,6 +92,20 @@ pcl_ros::StatisticalOutlierRemoval::StatisticalOutlierRemoval(const rclcpp::Node
subscribe();
}
void
pcl_ros::StatisticalOutlierRemoval::filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output)
{
std::lock_guard<std::mutex> lock(mutex_);
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, output);
}
//////////////////////////////////////////////////////////////////////////////////////////////
rcl_interfaces::msg::SetParametersResult

View File

@ -89,6 +89,20 @@ pcl_ros::VoxelGrid::VoxelGrid(const rclcpp::NodeOptions & options)
subscribe();
}
void
pcl_ros::VoxelGrid::filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output)
{
std::lock_guard<std::mutex> lock(mutex_);
pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
pcl_conversions::toPCL(*(input), *(pcl_input));
impl_.setInputCloud(pcl_input);
impl_.setIndices(indices);
pcl::PCLPointCloud2 pcl_output;
impl_.filter(pcl_output);
pcl_conversions::moveFromPCL(pcl_output, output);
}
//////////////////////////////////////////////////////////////////////////////////////////////
rcl_interfaces::msg::SetParametersResult