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 <algorithm>
00037 #include <jsk_pcl_ros_utils/polygon_array_unwrapper.h>
00038 
00039 namespace jsk_pcl_ros_utils
00040 {
00041   void PolygonArrayUnwrapper::onInit()
00042   {
00043     ConnectionBasedNodelet::onInit();
00044     pub_polygon_ = advertise<geometry_msgs::PolygonStamped>(
00045       *pnh_, "output_polygon", 1);
00046     pub_coefficients_
00047       = advertise<pcl_msgs::ModelCoefficients>(
00048         *pnh_,
00049         "output_coefficients", 1);
00050     srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00051     dynamic_reconfigure::Server<Config>::CallbackType f =
00052       boost::bind(&PolygonArrayUnwrapper::configCallback, this, _1, _2);
00053     srv_->setCallback(f);
00054   }
00055 
00056   void PolygonArrayUnwrapper::subscribe()
00057   {
00058     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00059     sub_polygon_.subscribe(*pnh_, "input_polygons", 1);
00060     sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
00061     sync_->connectInput(sub_polygon_, sub_coefficients_);
00062     sync_->registerCallback(boost::bind(
00063                               &PolygonArrayUnwrapper::unwrap,
00064                               this, _1, _2));
00065   }
00066 
00067   void PolygonArrayUnwrapper::unsubscribe()
00068   {
00069     sub_polygon_.unsubscribe();
00070     sub_coefficients_.unsubscribe();
00071   }
00072 
00073   void PolygonArrayUnwrapper::configCallback(Config& config, uint32_t level)
00074   {
00075     boost::mutex::scoped_lock lock(mutex_);
00076     use_likelihood_ = config.use_likelihood;
00077     plane_index_ = (size_t)config.plane_index;
00078   }
00079 
00080   void PolygonArrayUnwrapper::unwrap(
00081     const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons,
00082     const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients)
00083   {
00084     boost::mutex::scoped_lock lock(mutex_);
00085     if (polygons->polygons.size() > 0) {
00086       size_t selected_index = plane_index_;
00087       if (selected_index >= polygons->polygons.size()) {
00088         NODELET_ERROR_THROTTLE(1.0, "plane_index exceeds polygons size");
00089         selected_index = polygons->polygons.size() - 1;
00090       }
00091       if (use_likelihood_) {
00092         
00093         selected_index = std::distance(
00094           polygons->likelihood.begin(),
00095           std::max_element(polygons->likelihood.begin(), polygons->likelihood.end()));
00096       }
00097       geometry_msgs::PolygonStamped polygon_msg = polygons->polygons[selected_index];
00098       pcl_msgs::ModelCoefficients coefficients_msg = coefficients->coefficients[selected_index];
00099       pub_polygon_.publish(polygon_msg);
00100       pub_coefficients_.publish(coefficients_msg);
00101     }
00102   }
00103 }
00104 
00105 #include <pluginlib/class_list_macros.h>
00106 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::PolygonArrayUnwrapper, nodelet::Nodelet);