Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
rtabmap_ros::PluginInterface Class Referenceabstract

#include <PluginInterface.h>

Public Member Functions

virtual sensor_msgs::PointCloud2 filterPointCloud (const sensor_msgs::PointCloud2 msg)=0
 
const std::string getName () const
 
void initialize (const std::string name, ros::NodeHandle &nh)
 
bool isEnabled ()
 
 PluginInterface ()
 
virtual ~PluginInterface ()
 

Protected Member Functions

virtual void onInitialize ()
 This is called at the end of initialize(). Override to implement subclass-specific initialization. More...
 

Protected Attributes

bool enabled_
 Currently this var is managed by subclasses. TODO: make this managed by this class and/or container class. More...
 
std::string name_
 
ros::NodeHandle nh_
 

Detailed Description

Definition at line 11 of file PluginInterface.h.

Constructor & Destructor Documentation

◆ PluginInterface()

rtabmap_ros::PluginInterface::PluginInterface ( )

Definition at line 6 of file PluginInterface.cpp.

◆ ~PluginInterface()

virtual rtabmap_ros::PluginInterface::~PluginInterface ( )
inlinevirtual

Definition at line 15 of file PluginInterface.h.

Member Function Documentation

◆ filterPointCloud()

virtual sensor_msgs::PointCloud2 rtabmap_ros::PluginInterface::filterPointCloud ( const sensor_msgs::PointCloud2  msg)
pure virtual

◆ getName()

const std::string rtabmap_ros::PluginInterface::getName ( ) const
inline

Definition at line 17 of file PluginInterface.h.

◆ initialize()

void rtabmap_ros::PluginInterface::initialize ( const std::string  name,
ros::NodeHandle nh 
)

Definition at line 12 of file PluginInterface.cpp.

◆ isEnabled()

bool rtabmap_ros::PluginInterface::isEnabled ( )
inline

Definition at line 22 of file PluginInterface.h.

◆ onInitialize()

virtual void rtabmap_ros::PluginInterface::onInitialize ( )
inlineprotectedvirtual

This is called at the end of initialize(). Override to implement subclass-specific initialization.

Definition at line 34 of file PluginInterface.h.

Member Data Documentation

◆ enabled_

bool rtabmap_ros::PluginInterface::enabled_
protected

Currently this var is managed by subclasses. TODO: make this managed by this class and/or container class.

Definition at line 36 of file PluginInterface.h.

◆ name_

std::string rtabmap_ros::PluginInterface::name_
protected

Definition at line 37 of file PluginInterface.h.

◆ nh_

ros::NodeHandle rtabmap_ros::PluginInterface::nh_
protected

Definition at line 38 of file PluginInterface.h.


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


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40