| Public Member Functions | |
| void | configure (const ecto::tendrils ¶ms, const ecto::tendrils &inputs, const ecto::tendrils &outputs) | 
| int | process (const ecto::tendrils &inputs, const ecto::tendrils &outputs) | 
| Static Public Member Functions | |
| static void | declare_io (const ecto::tendrils ¶ms, ecto::tendrils &inputs, ecto::tendrils &outputs) | 
| static void | declare_params (ecto::tendrils ¶ms) | 
| Private Attributes | |
| ecto::spore< std::vector < std::vector< std::vector < cv::Vec3f > > > > | clusters3d_ | 
| ecto::spore < sensor_msgs::ImageConstPtr > | image_message_ | 
| ecto::spore < object_recognition_msgs::RecognizedObjectArrayConstPtr > | output_msg_ | 
Cell that takes the output of the tabletop pipeline and publishes the clusters nested in a recognizedobjectarray for later fill-up.
Definition at line 55 of file PointCloudMsgAssembler.cpp.
| void object_recognition_clusters::PointCloudMsgAssembler::configure | ( | const ecto::tendrils & | params, | 
| const ecto::tendrils & | inputs, | ||
| const ecto::tendrils & | outputs | ||
| ) |  [inline] | 
Definition at line 70 of file PointCloudMsgAssembler.cpp.
| static void object_recognition_clusters::PointCloudMsgAssembler::declare_io | ( | const ecto::tendrils & | params, | 
| ecto::tendrils & | inputs, | ||
| ecto::tendrils & | outputs | ||
| ) |  [inline, static] | 
Definition at line 60 of file PointCloudMsgAssembler.cpp.
| static void object_recognition_clusters::PointCloudMsgAssembler::declare_params | ( | ecto::tendrils & | params | ) |  [inline, static] | 
Definition at line 57 of file PointCloudMsgAssembler.cpp.
| int object_recognition_clusters::PointCloudMsgAssembler::process | ( | const ecto::tendrils & | inputs, | 
| const ecto::tendrils & | outputs | ||
| ) |  [inline] | 
Definition at line 74 of file PointCloudMsgAssembler.cpp.
| ecto::spore<std::vector<std::vector<std::vector<cv::Vec3f> > > > object_recognition_clusters::PointCloudMsgAssembler::clusters3d_  [private] | 
For each table, a vector of clusters
Definition at line 125 of file PointCloudMsgAssembler.cpp.
| ecto::spore<sensor_msgs::ImageConstPtr> object_recognition_clusters::PointCloudMsgAssembler::image_message_  [private] | 
The image message the initial data is from
Definition at line 123 of file PointCloudMsgAssembler.cpp.
| ecto::spore<object_recognition_msgs::RecognizedObjectArrayConstPtr> object_recognition_clusters::PointCloudMsgAssembler::output_msg_  [private] | 
Pointcloud with the header of the image message
Definition at line 127 of file PointCloudMsgAssembler.cpp.