rapid
A ROS robotics library.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Pages
pose_estimation_heat_mapper.h
Go to the documentation of this file.
1 #ifndef _RAPID_PERCEPTION_POSE_ESTIMATION_HEAT_MAPPER_H_
2 #define _RAPID_PERCEPTION_POSE_ESTIMATION_HEAT_MAPPER_H_
3 
4 #include <string>
5 
6 #include "Eigen/Core"
7 #include "pcl/point_cloud.h"
8 #include "pcl/point_types.h"
9 #include "pcl/PointIndices.h"
10 #include "ros/ros.h"
11 
12 namespace rapid {
13 namespace perception {
14 // Base class for a heat mapper for pose estimation.
15 // All heat mappers get a debug flag and a point cloud publisher.
16 // The scene, object, parameters, etc. are passed into subclasses.
18  public:
21 
22  // Generates a heatmap, represented as a list of indices into the cloud
23  // representing the scene and a parallel list of "importance" scores.
24  virtual void Compute(pcl::PointCloud<pcl::PointXYZRGB>::Ptr heatmap,
25  Eigen::VectorXd* importances) = 0;
26 
27  virtual void set_scene(pcl::PointCloud<pcl::PointXYZRGB>::Ptr scene) = 0;
28  virtual void set_object(pcl::PointCloud<pcl::PointXYZRGB>::Ptr object) = 0;
29  void set_name(const std::string& val);
30  void set_debug(bool val);
31  void set_heatmap_publisher(const ros::Publisher& pub);
32  std::string name();
33 
34  protected:
35  std::string name_;
36  bool debug_;
37  ros::Publisher heatmap_pub_;
38 };
39 } // namespace perception
40 } // namespace rapid
41 
42 #endif // _RAPID_PERCEPTION_POSE_ESTIMATION_HEAT_MAPPER_H_
void set_name(const std::string &val)
virtual void set_object(pcl::PointCloud< pcl::PointXYZRGB >::Ptr object)=0
void set_heatmap_publisher(const ros::Publisher &pub)
virtual void Compute(pcl::PointCloud< pcl::PointXYZRGB >::Ptr heatmap, Eigen::VectorXd *importances)=0
virtual void set_scene(pcl::PointCloud< pcl::PointXYZRGB >::Ptr scene)=0