Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
29 changes: 14 additions & 15 deletions pcl_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -83,12 +83,6 @@ target_link_libraries(pcl_ros_tf PUBLIC
#
#

### Declare library for base filter plugin
add_library(pcl_ros_filter
src/pcl_ros/filters/filter.cpp
)
target_link_libraries(pcl_ros_filter pcl_ros_tf ${PCL_LIBRARIES})

### Declare the pcl_ros_filters library
add_library(pcl_ros_filters SHARED
src/pcl_ros/filters/extract_indices.cpp
Expand All @@ -102,7 +96,6 @@ add_library(pcl_ros_filters SHARED
target_link_libraries(pcl_ros_filters PUBLIC
${PCL_LIBRARIES}
${visualization_msgs_TARGETS}
pcl_ros_filter
pcl_ros_tf
rclcpp_components::component
)
Expand Down Expand Up @@ -137,16 +130,23 @@ rclcpp_components_register_node(pcl_ros_filters
class_loader_hide_library_symbols(pcl_ros_filters)
#
### Declare the pcl_ros_segmentation library
#add_library (pcl_ros_segmentation
add_library (pcl_ros_segmentation SHARED
# src/pcl_ros/segmentation/extract_clusters.cpp
# src/pcl_ros/segmentation/extract_polygonal_prism_data.cpp
# src/pcl_ros/segmentation/sac_segmentation.cpp
src/pcl_ros/segmentation/sac_segmentation.cpp
# src/pcl_ros/segmentation/segment_differences.cpp
# src/pcl_ros/segmentation/segmentation.cpp
#)
#target_link_libraries(pcl_ros_segmentation pcl_ros_tf ${Boost_LIBRARIES} ${catkin_LIBRARIES} ${PCL_LIBRARIES})
#add_dependencies(pcl_ros_segmentation ${PROJECT_NAME}_gencfg)
#class_loader_hide_library_symbols(pcl_ros_segmentation)
)
target_link_libraries(pcl_ros_segmentation PUBLIC
${PCL_LIBRARIES}
pcl_ros_tf
rclcpp_components::component
)
rclcpp_components_register_node(pcl_ros_segmentation
PLUGIN "pcl_ros::SACSegmentation"
EXECUTABLE segmentation_sac_node
)
class_loader_hide_library_symbols(pcl_ros_segmentation)
#
### Declare the pcl_ros_surface library
#add_library (pcl_ros_surface
Expand Down Expand Up @@ -290,10 +290,9 @@ install(
pcd_to_pointcloud_lib
# pcl_ros_io
# pcl_ros_features
pcl_ros_filter
pcl_ros_filters
# pcl_ros_surface
# pcl_ros_segmentation
pcl_ros_segmentation
pointcloud_to_pcd_lib
combined_pointcloud_to_pcd_lib
bag_to_pcd_lib
Expand Down
63 changes: 29 additions & 34 deletions pcl_ros/include/pcl_ros/filters/crop_box.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@
#include <pcl/filters/crop_box.h>
#include <vector>
#include <visualization_msgs/msg/marker.hpp>
#include "pcl_ros/filters/filter.hpp"
#include "pcl_ros/pcl_node.hpp"

namespace pcl_ros
{
Expand All @@ -52,49 +52,44 @@ namespace pcl_ros
* \author Radu Bogdan Rusu
* \author Justin Rosen
* \author Marti Morta Garriga
* \author Antonio Brandi
*/
class CropBox : public Filter
class CropBox : public PCLNode<Input<PointCloud2>, Output<PointCloud2, visualization_msgs::msg::Marker>>
{
protected:
/** \brief Call the actual filter.
* \param input the input point cloud dataset
* \param indices the input set of indices to use from \a input
* \param output the resultant filtered dataset
private:
/** \brief The PCL filter implementation used.
*/
inline void
filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output) override;
pcl::CropBox<pcl::PCLPointCloud2> impl_;

/** \brief Parameter callback
* \param params parameter values to set
/** \brief The crop box marker message.
* The marker's cube gets updated whenever the min/max points are changed.
* The header is adjusted with every point cloud callback.
*/
rcl_interfaces::msg::SetParametersResult
config_callback(const std::vector<rclcpp::Parameter> & params);
/** \brief Create publishers for output PointCloud2 data as well as the crop box marker. */
void createPublishers() override;
/** \brief Update the crop box marker msg. */
void update_marker_msg();

OnSetParametersCallbackHandle::SharedPtr callback_handle_;
/** \brief The crop box marker msg publisher for visualization and debugging purposes. */
rclcpp::Publisher<visualization_msgs::msg::Marker>::SharedPtr crop_box_marker_publisher_;
/**
* \brief The crop box marker message.
*
* The marker's cube gets updated whenever the min/max points are changed.
* The header is adjusted with every point cloud callback.
*/
visualization_msgs::msg::Marker crop_box_marker_msg_;

private:
/** \brief The PCL filter implementation used. */
pcl::CropBox<pcl::PCLPointCloud2> impl_;
/** \brief Update the crop box marker msg. */
void updateMarkerMsg();

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
/** \brief Parameter callback
* \param params parameter values to set.
*/
virtual rcl_interfaces::msg::SetParametersResult onParamsChanged(
const std::vector<rclcpp::Parameter> & params) override;

public:
/** \brief Constructor.
* \param options A rclcpp::NodeOptions to be passed to the node.
*/
explicit CropBox(const rclcpp::NodeOptions & options);

/** \brief Calls the actual CropBox PCL filter.
* \param input the input point cloud dataset.
* \param output the resultant filtered dataset.
* \param marker the crop box marker for visualization and debugging purposes.
*/
virtual void compute(
const PointCloud2 & input, PointCloud2 & output,
visualization_msgs::msg::Marker & marker) override;
};
} // namespace pcl_ros

Expand Down
41 changes: 20 additions & 21 deletions pcl_ros/include/pcl_ros/filters/extract_indices.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,43 +41,42 @@
// PCL includes
#include <pcl/filters/extract_indices.h>
#include <vector>
#include "pcl_ros/filters/filter.hpp"
#include "pcl_ros/pcl_node.hpp"

namespace pcl_ros
{
/** \brief @b ExtractIndices extracts a set of indices from a PointCloud as a separate PointCloud.
* \note setFilterFieldName (), setFilterLimits (), and setFilterLimitNegative () are ignored.
* \author Radu Bogdan Rusu
* \author Antonio Brandi
*/
class ExtractIndices : public Filter
class ExtractIndices : public PCLNode<Input<PointCloud2, PointIndices>, Output<PointCloud2>>
{
protected:
/** \brief Call the actual filter.
* \param input the input point cloud dataset
* \param indices the input set of indices to use from \a input
* \param output the resultant filtered dataset
*/
inline void
filter(
const PointCloud2::ConstSharedPtr & input, const IndicesPtr & indices,
PointCloud2 & output) override;
private:
/** \brief The PCL filter implementation used. */
pcl::ExtractIndices<pcl::PCLPointCloud2> impl_;

/** \brief Parameter callback
* \param params parameter values to set
*/
rcl_interfaces::msg::SetParametersResult
config_callback(const std::vector<rclcpp::Parameter> & params);

OnSetParametersCallbackHandle::SharedPtr callback_handle_;

private:
/** \brief The PCL filter implementation used. */
pcl::ExtractIndices<pcl::PCLPointCloud2> impl_;
onParamsChanged(const std::vector<rclcpp::Parameter> & params) override;

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

/** \brief Constructor
* \param options A rclcpp::NodeOptions to be passed to the node.
*/
explicit ExtractIndices(const rclcpp::NodeOptions & options);

/** \brief Calls the actual RadiusOutlierRemoval PCL filter.
* \param input the input point cloud dataset.
* \param indices the input set of indices to use from input.
* \param output the resultant filtered dataset.
*/
virtual void compute(
const PointCloud2 & input, const PointIndices & indices,
PointCloud2 & output) override;

};
} // namespace pcl_ros

Expand Down
167 changes: 0 additions & 167 deletions pcl_ros/include/pcl_ros/filters/filter.hpp

This file was deleted.

Loading