Autoware.Auto
autoware::perception::filters::filter_node_base::FilterNodeBase Class Referenceabstract

The abstract class used for filter applications. More...

#include <filter_node_base.hpp>

Inheritance diagram for autoware::perception::filters::filter_node_base::FilterNodeBase:
Collaboration diagram for autoware::perception::filters::filter_node_base::FilterNodeBase:

Public Member Functions

 FilterNodeBase (const std::string &filter_name="filter_node_base", const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 The default constructor for the FilterNodeBase class. More...
 
virtual ~FilterNodeBase ()
 

Protected Member Functions

virtual FILTER_NODE_BASE_LOCAL void filter (const sensor_msgs::msg::PointCloud2 &input, sensor_msgs::msg::PointCloud2 &output)=0
 Virtual abstract filter method called by the computePublish method at the arrival of each point cloud message. More...
 
virtual FILTER_NODE_BASE_LOCAL rcl_interfaces::msg::SetParametersResult get_node_parameters (const std::vector< rclcpp::Parameter > &p)=0
 Virtual abstract method for getting parameters for various child classes of the FilterNodeBase. More...
 
FILTER_NODE_BASE_LOCAL bool8_t is_valid (const sensor_msgs::msg::PointCloud2::ConstSharedPtr &cloud)
 Validate a sensor_msgs::msg::PointCloud2 message. More...
 
FILTER_NODE_BASE_PUBLIC void set_param_callback ()
 Binds the param_callback to the OnSetParametersCallbackHandle object. More...
 

Protected Attributes

rclcpp::Subscription< sensor_msgs::msg::PointCloud2 >::SharedPtr sub_input_
 The input PointCloud2 subscriber. More...
 
rclcpp::Publisher< sensor_msgs::msg::PointCloud2 >::SharedPtr pub_output_
 The output PointCloud2 publisher. More...
 
std::string filter_field_name_
 The desired user filter field name. More...
 
std::mutex mutex_
 Mutex used to access to the parameters. More...
 
size_t max_queue_size_
 The maximum queue size. More...
 

Detailed Description

The abstract class used for filter applications.

Constructor & Destructor Documentation

◆ FilterNodeBase()

autoware::perception::filters::filter_node_base::FilterNodeBase::FilterNodeBase ( const std::string &  filter_name = "filter_node_base",
const rclcpp::NodeOptions &  options = rclcpp::NodeOptions() 
)
explicit

The default constructor for the FilterNodeBase class.

Parameters
filter_nameThe name of the node to pass on to rclcpp::Node
optionsAn rclcpp::NodeOptions object to pass on to rclcpp::Node

◆ ~FilterNodeBase()

virtual autoware::perception::filters::filter_node_base::FilterNodeBase::~FilterNodeBase ( )
inlinevirtual

Member Function Documentation

◆ filter()

virtual FILTER_NODE_BASE_LOCAL void autoware::perception::filters::filter_node_base::FilterNodeBase::filter ( const sensor_msgs::msg::PointCloud2 &  input,
sensor_msgs::msg::PointCloud2 &  output 
)
protectedpure virtual

Virtual abstract filter method called by the computePublish method at the arrival of each point cloud message.

Parameters
inputThe input point cloud dataset.
outputThe resultant filtered PointCloud2

◆ get_node_parameters()

virtual FILTER_NODE_BASE_LOCAL rcl_interfaces::msg::SetParametersResult autoware::perception::filters::filter_node_base::FilterNodeBase::get_node_parameters ( const std::vector< rclcpp::Parameter > &  p)
protectedpure virtual

Virtual abstract method for getting parameters for various child classes of the FilterNodeBase.

This method is called in the param_callback method and is triggered when a parameter associated with the node is changed. The node should use the get_param method to retrieve any changed parameters in the node.

Parameters
pVector of rclcpp::Parameters belonging to the node
Returns
rcl_interfaces::msg::SetParametersResult Result of retrieving the parameter

◆ is_valid()

FILTER_NODE_BASE_LOCAL bool8_t autoware::perception::filters::filter_node_base::FilterNodeBase::is_valid ( const sensor_msgs::msg::PointCloud2::ConstSharedPtr &  cloud)
inlineprotected

Validate a sensor_msgs::msg::PointCloud2 message.

Method ensures that the size of the point cloud defined by the width, height and point_step correspond to the data size.

Parameters
cloudInput sensor_msgs::msg::PointCloud2 to be validated
Returns
bool8_t True if the point cloud is valid, false if not

◆ set_param_callback()

void autoware::perception::filters::filter_node_base::FilterNodeBase::set_param_callback ( )
protected

Binds the param_callback to the OnSetParametersCallbackHandle object.

Due to the nature of the OnSetParametersCallbackHandle, this needs to be called after all parameters used by this node have been declared. Therefore this method needs to be called at the end of the constructor in child classes inheriting from FilterNodeBase.

Member Data Documentation

◆ filter_field_name_

std::string autoware::perception::filters::filter_node_base::FilterNodeBase::filter_field_name_
protected

The desired user filter field name.

◆ max_queue_size_

size_t autoware::perception::filters::filter_node_base::FilterNodeBase::max_queue_size_
protected

The maximum queue size.

◆ mutex_

std::mutex autoware::perception::filters::filter_node_base::FilterNodeBase::mutex_
protected

Mutex used to access to the parameters.

◆ pub_output_

rclcpp::Publisher<sensor_msgs::msg::PointCloud2>::SharedPtr autoware::perception::filters::filter_node_base::FilterNodeBase::pub_output_
protected

The output PointCloud2 publisher.

◆ sub_input_

rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr autoware::perception::filters::filter_node_base::FilterNodeBase::sub_input_
protected

The input PointCloud2 subscriber.


The documentation for this class was generated from the following files: