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 #define BOOST_PARAMETER_MAX_ARITY 7
00037 
00038 #include "jsk_pcl_ros_utils/cloud_on_plane.h"
00039 #include <jsk_recognition_utils/pcl_ros_util.h>
00040 
00041 namespace jsk_pcl_ros_utils
00042 {
00043   void CloudOnPlane::onInit()
00044   {
00045     DiagnosticNodelet::onInit();
00046     pcl::console::setVerbosityLevel(pcl::console::L_ALWAYS);
00047     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00048     dynamic_reconfigure::Server<Config>::CallbackType f =
00049       boost::bind (
00050         &CloudOnPlane::configCallback, this, _1, _2);
00051     srv_->setCallback (f);
00052 
00053     pub_ = advertise<jsk_recognition_msgs::BoolStamped>(*pnh_, "output", 1);
00054 
00055     onInitPostProcess();
00056   }
00057 
00058   void CloudOnPlane::subscribe()
00059   {
00060     sub_cloud_.subscribe(*pnh_, "input", 1);
00061     sub_polygon_.subscribe(*pnh_, "input/polygon", 1);
00062     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> > (100);
00063     sync_->connectInput(sub_cloud_, sub_polygon_);
00064     sync_->registerCallback(boost::bind(&CloudOnPlane::predicate, this,
00065                                         _1, _2));
00066   }
00067 
00068   void CloudOnPlane::unsubscribe()
00069   {
00070     sub_cloud_.unsubscribe();
00071     sub_polygon_.unsubscribe();
00072   }
00073 
00074   void CloudOnPlane::configCallback(Config& config, uint32_t level)
00075   {
00076     boost::mutex::scoped_lock lock(mutex_);
00077     distance_thr_ = config.distance_thr;
00078     buf_size_ = config.buf_size;
00079     buffer_.reset(new jsk_recognition_utils::SeriesedBoolean(buf_size_));
00080   }
00081 
00082   void CloudOnPlane::predicate(const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00083                                const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg)
00084   {
00085     boost::mutex::scoped_lock lock(mutex_);
00086     vital_checker_->poke();
00087     
00088     if (!jsk_recognition_utils::isSameFrameId(*cloud_msg, *polygon_msg)) {
00089       NODELET_ERROR("frame_id does not match: cloud: %s, polygon: %s",
00090                         cloud_msg->header.frame_id.c_str(), polygon_msg->header.frame_id.c_str());
00091       return;
00092     }
00093     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
00094     pcl::fromROSMsg(*cloud_msg, *cloud);
00095     
00096     std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> polygons;
00097     for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
00098       polygons.push_back(jsk_recognition_utils::ConvexPolygon::fromROSMsgPtr(polygon_msg->polygons[i].polygon));
00099     }
00100     
00101     for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
00102       jsk_recognition_utils::ConvexPolygon::Ptr poly = polygons[i];
00103       for (size_t j = 0; j < cloud->points.size(); j++) {
00104         Eigen::Vector3f p = cloud->points[j].getVector3fMap();
00105         if (poly->distanceSmallerThan(p, distance_thr_)) {
00106           buffer_->addValue(false);
00107           publishPredicate(cloud_msg->header, !buffer_->isAllTrueFilled());
00108           return;
00109         }
00110       }
00111     }
00112     buffer_->addValue(true);
00113     publishPredicate(cloud_msg->header, !buffer_->isAllTrueFilled());
00114   }
00115 
00116   void CloudOnPlane::publishPredicate(const std_msgs::Header& header,
00117                                       const bool v)
00118   {
00119     jsk_recognition_msgs::BoolStamped bool_stamped;
00120     bool_stamped.header = header;
00121     bool_stamped.data = v;
00122     pub_.publish(bool_stamped);
00123   }
00124 }
00125 
00126 #include <pluginlib/class_list_macros.h>
00127 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros_utils::CloudOnPlane, nodelet::Nodelet);
00128