Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 #include "jsk_pcl_ros_utils/polygon_array_wrapper.h"
00037 
00038 namespace jsk_pcl_ros_utils
00039 {
00040   void PolygonArrayWrapper::onInit()
00041   {
00042     ConnectionBasedNodelet::onInit();
00043     pub_polygon_array_ = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_,
00044       "output_polygons", 1);
00045     pub_coefficients_array_
00046       = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_,
00047         "output_coefficients", 1);
00048   }
00049 
00050   void PolygonArrayWrapper::subscribe()
00051   {
00052     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00053     sub_polygon_.subscribe(*pnh_, "input_polygon", 1);
00054     sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
00055     sync_->connectInput(sub_polygon_, sub_coefficients_);
00056     sync_->registerCallback(boost::bind(
00057                               &PolygonArrayWrapper::wrap,
00058                               this, _1, _2));
00059   }
00060 
00061   void PolygonArrayWrapper::unsubscribe()
00062   {
00063     sub_polygon_.unsubscribe();
00064     sub_coefficients_.unsubscribe();
00065   }
00066   
00067   void PolygonArrayWrapper::wrap(
00068     const geometry_msgs::PolygonStamped::ConstPtr& polygon,
00069     const pcl_msgs::ModelCoefficients::ConstPtr& coefficients)
00070   {
00071     jsk_recognition_msgs::PolygonArray array_msg;
00072     array_msg.header = polygon->header;
00073     geometry_msgs::PolygonStamped new_polygon(*polygon);
00074     array_msg.polygons.push_back(new_polygon);
00075     pub_polygon_array_.publish(array_msg);
00076 
00077     jsk_recognition_msgs::ModelCoefficientsArray coefficients_array;
00078     coefficients_array.header = coefficients->header;
00079     pcl_msgs::ModelCoefficients new_coefficients(*coefficients);
00080     coefficients_array.coefficients.push_back(new_coefficients);
00081     pub_coefficients_array_.publish(coefficients_array);
00082   }
00083   
00084 }
00085 
00086 #include <pluginlib/class_list_macros.h>
00087 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::PolygonArrayWrapper, nodelet::Nodelet);