Public Member Functions | Protected Member Functions | List of all members
MyClass Class Reference
Inheritance diagram for MyClass:
Inheritance graph
[legend]

Public Member Functions

 MyClass (ros::NodeHandle nh)
 
- Public Member Functions inherited from sensor_filters::FilterChainNode< sensor_msgs::PointCloud2 >
 FilterChainNode (const std::string &filterChainNamespace, ros::NodeHandle filterNodeHandle, ros::NodeHandle topicNodeHandle)
 
- Public Member Functions inherited from sensor_filters::FilterChainBase< sensor_msgs::PointCloud2 >
 FilterChainBase ()
 
virtual ~FilterChainBase ()=default
 

Protected Member Functions

bool filter (const sensor_msgs::PointCloud2 &msgIn, sensor_msgs::PointCloud2 &msgOut) override
 
- Protected Member Functions inherited from sensor_filters::FilterChainBase< sensor_msgs::PointCloud2 >
virtual void advertise ()
 
virtual void callbackReference (const sensor_msgs::PointCloud2 &msgIn)
 
virtual void callbackShared (const typename sensor_msgs::PointCloud2 ::ConstPtr &msgIn)
 
virtual void initFilters (const std::string &filterChainNamespace, ros::NodeHandle filterNodeHandle, ros::NodeHandle topicNodeHandle, const bool useSharedPtrMessages, const size_t inputQueueSize, const size_t outputQueueSize)
 
virtual void publishReference (const sensor_msgs::PointCloud2 &msg)
 
virtual void publishShared (const typename sensor_msgs::PointCloud2 ::ConstPtr &msg)
 
virtual void subscribe ()
 

Additional Inherited Members

- Protected Types inherited from sensor_filters::FilterChainBase< sensor_msgs::PointCloud2 >
typedef ros::message_traits::DataType< sensor_msgs::PointCloud2 > DataType
 
- Protected Attributes inherited from sensor_filters::FilterChainBase< sensor_msgs::PointCloud2 >
filters::FilterChain< sensor_msgs::PointCloud2 > filterChain
 
size_t inputQueueSize
 
ros::Subscriber inputSubscriber
 
sensor_msgs::PointCloud2 msg
 
ros::Publisher outputPublisher
 
size_t outputQueueSize
 
ros::NodeHandle topicNodeHandle
 
bool useSharedPtrMessages
 

Detailed Description

Definition at line 12 of file example_custom_chain_node.cpp.

Constructor & Destructor Documentation

◆ MyClass()

MyClass::MyClass ( ros::NodeHandle  nh)
inlineexplicit

Definition at line 15 of file example_custom_chain_node.cpp.

Member Function Documentation

◆ filter()

bool MyClass::filter ( const sensor_msgs::PointCloud2 &  msgIn,
sensor_msgs::PointCloud2 &  msgOut 
)
inlineoverrideprotectedvirtual

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


sensor_filters
Author(s): Martin Pecka
autogenerated on Wed Jun 14 2023 02:09:33