HLR  0.0.1
ObjectInterpreter.hpp
1 #ifndef OBJECTINTERPRETER_HPP
2 #define OBJECTINTERPRETER_HPP
3 
4 #include <vector>
5 #include <boost/circular_buffer.hpp>
6 #include "LidarInterpreter.hpp"
7 #include "Object.hpp"
8 
9 namespace HLR
10 {
11 namespace PointCloud
12 {
19 {
20 public:
26  ObjectInterpreter() = default;
42  std::vector<Object> get_current_objects(
43  const HLR::Vision::CupDetection& detected_cups,
44  const pcl::PointCloud<pcl::PointXYZ>& point_cloud);
45 
63  std::vector<Object> get_changed_objects(
64  const HLR::Vision::CupDetection& detected_cups,
65  const pcl::PointCloud<pcl::PointXYZ>& point_cloud);
66 
67 private:
68  void add_only_changed_objects(const Object& object,
69  std::vector<Object>& changed_objects) const;
70  void merge_objects(const HLR::Vision::CupDetection& detected_cups,
71  const pcl::PointCloud<pcl::PointXYZ>& point_cloud);
72 
73  std::vector<Object> current_objects;
74  boost::circular_buffer<std::vector<Object>> history =
75  boost::circular_buffer<std::vector<Object>>(5);
76  LidarInterpreter lidar_interpreter;
77 };
78 } // namespace PointCloud
79 } // namespace HLR
80 #endif /* OBJECTINTERPRETER_HPP */
Class responsible for merging the world data from the Kinect and the LiDAR.
Definition: ObjectInterpreter.hpp:18
A class for mapping the ROS::Object defined in msg/Object.msg.
Definition: Object.hpp:22
std::vector< Object > get_changed_objects(const HLR::Vision::CupDetection &detected_cups, const pcl::PointCloud< pcl::PointXYZ > &point_cloud)
Returns all the objects visible at this moment that changed since last call of this function...
std::vector< Object > get_current_objects(const HLR::Vision::CupDetection &detected_cups, const pcl::PointCloud< pcl::PointXYZ > &point_cloud)
Returns all the objects visible at this moment.
Collection of detected cups Collection of detected cups where the location of the cups is described i...
Definition: ICupDetector.hpp:17
A class responsible for reading and interpreting the LiDAR data.
Definition: LidarInterpreter.hpp:24