PluginInterface.h
Go to the documentation of this file.
1 #ifndef PLUGIN_INTERFACE_H_
2 #define PLUGIN_INTERFACE_H_
3 
4 #include <ros/ros.h>
5 #include <string>
6 #include <sensor_msgs/PointCloud2.h>
7 
8 namespace rtabmap_odom
9 {
10 
12 {
13 public:
15  virtual ~PluginInterface() {}
16 
17  const std::string getName() const
18  {
19  return name_;
20  }
21 
22  bool isEnabled() {
23  return enabled_;
24  }
25 
26  void initialize(const std::string name, ros::NodeHandle & nh);
27 
28  virtual sensor_msgs::PointCloud2 filterPointCloud(const sensor_msgs::PointCloud2 msg) = 0;
29 
30 protected:
34  virtual void onInitialize() {}
35 
36  bool enabled_;
37  std::string name_;
39 
40 };
41 
42 } // namespace rtabmap_odom
43 
44 #endif // PLUGIN_INTERFACE_H_
45 
rtabmap_odom
Definition: OdometryROS.h:57
name
rtabmap_odom::PluginInterface::name_
std::string name_
Definition: PluginInterface.h:37
ros.h
rtabmap_odom::PluginInterface::filterPointCloud
virtual sensor_msgs::PointCloud2 filterPointCloud(const sensor_msgs::PointCloud2 msg)=0
rtabmap_odom::PluginInterface
Definition: PluginInterface.h:11
rtabmap_odom::PluginInterface::~PluginInterface
virtual ~PluginInterface()
Definition: PluginInterface.h:15
rtabmap_odom::PluginInterface::nh_
ros::NodeHandle nh_
Definition: PluginInterface.h:38
rtabmap_odom::PluginInterface::enabled_
bool enabled_
Currently this var is managed by subclasses. TODO: make this managed by this class and/or container c...
Definition: PluginInterface.h:36
rtabmap_odom::PluginInterface::onInitialize
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization.
Definition: PluginInterface.h:34
rtabmap_odom::PluginInterface::getName
const std::string getName() const
Definition: PluginInterface.h:17
rtabmap_odom::PluginInterface::isEnabled
bool isEnabled()
Definition: PluginInterface.h:22
rtabmap_odom::PluginInterface::PluginInterface
PluginInterface()
Definition: PluginInterface.cpp:6
rtabmap_odom::PluginInterface::initialize
void initialize(const std::string name, ros::NodeHandle &nh)
Definition: PluginInterface.cpp:12
ros::NodeHandle


rtabmap_odom
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:42:24