00001 /* 00002 * ShapeRecPlotter.h 00003 * 00004 * Author: roberto 00005 * 00006 * This is a modified implementation of the method for online estimation of kinematic structures described in our paper 00007 * "Online Interactive Perception of Articulated Objects with Multi-Level Recursive Estimation Based on Task-Specific Priors" 00008 * (Martín-Martín and Brock, 2014) and the extension to segment, reconstruct and track shapes introduced in our paper 00009 * "An Integrated Approach to Visual Perception of Articulated Objects" (Martín-Martín, Höfer and Brock, 2016) 00010 * This implementation can be used to reproduce the results of the paper and to be applied to new research. 00011 * The implementation allows also to be extended to perceive different information/models or to use additional sources of information. 00012 * A detail explanation of the method and the system can be found in our paper. 00013 * 00014 * If you are using this implementation in your research, please consider citing our work: 00015 * 00016 @inproceedings{martinmartin_ip_iros_2014, 00017 Title = {Online Interactive Perception of Articulated Objects with Multi-Level Recursive Estimation Based on Task-Specific Priors}, 00018 Author = {Roberto {Mart\'in-Mart\'in} and Oliver Brock}, 00019 Booktitle = {Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems}, 00020 Pages = {2494-2501}, 00021 Year = {2014}, 00022 Location = {Chicago, Illinois, USA}, 00023 Note = {http://www.robotics.tu-berlin.de/fileadmin/fg170/Publikationen_pdf/martinmartin_ip_iros_2014.pdf}, 00024 Url = {http://www.robotics.tu-berlin.de/fileadmin/fg170/Publikationen_pdf/martinmartin_ip_iros_2014.pdf}, 00025 Projectname = {Interactive Perception} 00026 } 00027 00028 @inproceedings{martinmartin_hoefer_iros_2016, 00029 Title = {An Integrated Approach to Visual Perception of Articulated Objects}, 00030 Author = {Roberto {Mart\'{i}n-Mart\'{i}n} and Sebastian H\"ofer and Oliver Brock}, 00031 Booktitle = {Proceedings of the IEEE International Conference on Robotics and Automation}, 00032 Pages = {5091 - 5097}, 00033 Year = {2016}, 00034 Doi = {10.1109/ICRA.2016.7487714}, 00035 Location = {Stockholm, Sweden}, 00036 Month = {05}, 00037 Note = {http://www.redaktion.tu-berlin.de/fileadmin/fg170/Publikationen_pdf/martin_hoefer_15_iros_sr_opt.pdf}, 00038 Url = {http://www.redaktion.tu-berlin.de/fileadmin/fg170/Publikationen_pdf/martin_hoefer_15_iros_sr_opt.pdf}, 00039 Url2 = {http://ieeexplore.ieee.org/xpl/articleDetails.jsp?tp=&arnumber=7487714}, 00040 Projectname = {Interactive Perception} 00041 } 00042 * If you have questions or suggestions, contact us: 00043 * roberto.martinmartin@tu-berlin.de 00044 * 00045 * Enjoy! 00046 */ 00047 00048 #ifndef SHAPE_RECONSTRUCTION_PLOTTER_NODE_H_ 00049 #define SHAPE_RECONSTRUCTION_PLOTTER_NODE_H_ 00050 00051 #include <ros/ros.h> 00052 #include <ros/callback_queue.h> 00053 #include <ros/subscriber.h> 00054 #include <image_transport/image_transport.h> 00055 #include <message_filters/subscriber.h> 00056 #include <message_filters/time_synchronizer.h> 00057 #include <message_filters/sync_policies/approximate_time.h> 00058 #include <sensor_msgs/PointCloud2.h> 00059 #include <sensor_msgs/Image.h> 00060 #include <std_msgs/Empty.h> 00061 00062 #include <rosbag/bag.h> 00063 #include <tf/tf.h> 00064 00065 #include "shape_reconstruction/ShapeRecPlotter.h" 00066 #include "shape_reconstruction/ShapeReconstruction.h" 00067 00068 #include <boost/thread.hpp> 00069 00070 #include <omip_common/OMIPTypeDefs.h> 00071 00072 // Dynamic reconfigure includes. 00073 #include <dynamic_reconfigure/server.h> 00074 00075 #include <shape_reconstruction/generate_meshes.h> 00076 00077 #include <pcl_conversions/pcl_conversions.h> 00078 00079 #include <omip_common/OMIPTypeDefs.h> 00080 00081 //ROS and OpenCV 00082 #include <opencv2/core/core.hpp> 00083 #include <camera_info_manager/camera_info_manager.h> 00084 00085 #include <pcl/range_image/range_image_planar.h> 00086 #include <pcl/filters/extract_indices.h> 00087 #include <pcl/common/transforms.h> 00088 #include <pcl/search/search.h> 00089 #include <pcl/search/organized.h> 00090 #include <pcl/search/kdtree.h> 00091 #include <pcl/filters/extract_indices.h> 00092 #include <pcl/filters/voxel_grid.h> 00093 #include <pcl/kdtree/kdtree_flann.h> 00094 00095 #include <omip_common/OMIPUtils.h> 00096 00097 #include <pcl/filters/radius_outlier_removal.h> 00098 00099 #include <pcl/filters/approximate_voxel_grid.h> 00100 00101 #include <pcl/features/normal_3d_omp.h> 00102 #include <pcl/point_types.h> 00103 #include <pcl/io/pcd_io.h> 00104 #include <pcl/kdtree/kdtree_flann.h> 00105 #include <pcl/features/normal_3d.h> 00106 #include <pcl/surface/gp3.h> 00107 #include <pcl/io/vtk_lib_io.h> 00108 00109 #include <pcl/segmentation/supervoxel_clustering.h> 00110 00111 #include <boost/circular_buffer.hpp> 00112 00113 #include "shape_reconstruction/SRUtils.h" 00114 00115 #include <omip_msgs/ShapeModels.h> 00116 00117 #include <tf/transform_listener.h> 00118 00119 namespace omip 00120 { 00121 00122 class ShapeRecPlotter 00123 { 00124 00125 public: 00126 00130 ShapeRecPlotter(); 00131 00135 virtual ~ShapeRecPlotter(); 00136 00137 virtual void InputPCmeasurementCallback(const sensor_msgs::PointCloud2ConstPtr &pc_msg); 00138 00139 void plotShape(); 00140 00141 protected: 00142 00143 00144 ros::NodeHandle _node_handle; 00145 00146 ros::Subscriber _pc_subscriber; 00147 00148 ros::Publisher _pc_publisher; 00149 00150 SRPointCloud::Ptr _current_pc; 00151 00152 tf::TransformListener * _tf_listener; 00153 00154 00155 template<class T> 00156 bool getROSParameter(std::string param_name, T & param_container) 00157 { 00158 if (!(this->_node_handle.getParam(param_name, param_container))) 00159 { 00160 ROS_ERROR_NAMED("ShapeRecPlotter.getROSParameter", "The parameter %s can not be found.", param_name.c_str()); 00161 throw(std::string("[ShapeRecPlotter.getROSParameter] The parameter can not be found. Parameter name: ") + param_name); 00162 return false; 00163 } 00164 else 00165 return true; 00166 } 00167 }; 00168 } 00169 00170 #endif /* FEATURE_TRACKER_NODE_H_ */ 00171