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_ros
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_ros
43 
44 #endif // PLUGIN_INTERFACE_H_
45 
virtual sensor_msgs::PointCloud2 filterPointCloud(const sensor_msgs::PointCloud2 msg)=0
virtual void onInitialize()
This is called at the end of initialize(). Override to implement subclass-specific initialization...
bool enabled_
Currently this var is managed by subclasses. TODO: make this managed by this class and/or container c...
const std::string getName() const
void initialize(const std::string name, ros::NodeHandle &nh)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19