Class CropBox

Inheritance Relationships

Base Type

Class Documentation

class CropBox : public pcl_ros::Filter

CropBox is a filter that allows the user to filter all the data inside of a given box.

Author

Radu Bogdan Rusu

Author

Justin Rosen

Author

Marti Morta Garriga

Public Functions

explicit EIGEN_MAKE_ALIGNED_OPERATOR_NEW CropBox(const rclcpp::NodeOptions &options)

Protected Functions

inline virtual void filter(const PointCloud2::ConstSharedPtr &input, const IndicesPtr &indices, PointCloud2 &output) override

Call the actual filter.

Parameters:
  • input – the input point cloud dataset

  • indices – the input set of indices to use from input

  • output – the resultant filtered dataset

rcl_interfaces::msg::SetParametersResult config_callback(const std::vector<rclcpp::Parameter> &params)

Parameter callback.

Parameters:

params – parameter values to set

virtual void createPublishers() override

Create publishers for output PointCloud2 data as well as the crop box marker.

void update_marker_msg()

Update the crop box marker msg.

Protected Attributes

OnSetParametersCallbackHandle::SharedPtr callback_handle_
rclcpp::Publisher<visualization_msgs::msg::Marker>::SharedPtr crop_box_marker_publisher_

The crop box marker msg publisher for visualization and debugging purposes.

visualization_msgs::msg::Marker crop_box_marker_msg_

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.