1 #ifndef OBJECTINTERPRETER_HPP 2 #define OBJECTINTERPRETER_HPP 5 #include <boost/circular_buffer.hpp> 6 #include "LidarInterpreter.hpp" 8 #include <pcl/point_cloud.h> 9 #include <pcl/point_types.h> 46 const pcl::PointCloud<pcl::PointXYZ>& point_cloud);
67 const pcl::PointCloud<pcl::PointXYZ>& point_cloud);
70 void add_only_changed_objects(
const Object&
object,
71 std::vector<Object>& changed_objects)
const;
73 const pcl::PointCloud<pcl::PointXYZ>& point_cloud);
84 std::vector<Object> isolate_objects(
85 const pcl::PointCloud<pcl::PointXYZ>& newest_cloud);
86 std::vector<Object> current_objects;
87 boost::circular_buffer<std::vector<Object>> history =
88 boost::circular_buffer<std::vector<Object>>(5);
Class responsible for merging the world data from the Kinect and the LiDAR.
Definition: ObjectInterpreter.hpp:20
A class for mapping the ROS::Object defined in msg/Object.msg.
Definition: Object.hpp:24
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