pointcloud_screenpoint_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include <jsk_topic_tools/log_utils.h>
00037 #include "jsk_pcl_ros/pointcloud_screenpoint.h"
00038 #include <pcl_conversions/pcl_conversions.h>
00039 
00040 // F/K/A <ray converter>
00041 // Haseru Chen, Kei Okada, Yohei Kakiuchi
00042 
00043 void jsk_pcl_ros::PointcloudScreenpoint::onInit()
00044 {
00045   PCLNodelet::onInit();
00046 
00047   queue_size_ = 1;
00048   crop_size_ = 10;
00049   k_ = 16; // todo : this value should be set from parameter.
00050 
00051   pnh_->param ("queue_size", queue_size_, 1);
00052   pnh_->param ("crop_size", crop_size_, 10);
00053   pnh_->param ("search_size", k_, 16);
00054 
00055   pnh_->param ("use_rect", use_rect_, false);
00056   pnh_->param ("use_point", use_point_, false);
00057   pnh_->param ("use_sync", use_sync_, false);
00058   pnh_->param ("use_point_array", use_point_array_, false);
00059   pnh_->param ("use_poly", use_poly_, false);
00060   pnh_->param("publish_points", publish_points_, false);
00061   pnh_->param("publish_point", publish_point_, false);
00062 
00063   srv_ = pnh_->advertiseService("screen_to_point", &PointcloudScreenpoint::screenpoint_cb, this);
00064 
00065   if (publish_point_) {
00066     pub_point_ = pnh_->advertise< geometry_msgs::PointStamped > ("output_point", 1);
00067   }
00068 
00069   if (publish_points_) {
00070     pub_points_ = pnh_->advertise< sensor_msgs::PointCloud2 > ("output", 1);
00071   }
00072 
00073   pub_polygon_ = pnh_->advertise<geometry_msgs::PolygonStamped>("output_polygon", 1);
00074 
00075 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
00076   normals_tree_ = boost::make_shared< pcl::search::KdTree<pcl::PointXYZ> > ();
00077 #else
00078   normals_tree_ = boost::make_shared<pcl::KdTreeFLANN<pcl::PointXYZ> > ();
00079 #endif
00080   n3d_.setKSearch (k_);
00081   n3d_.setSearchMethod (normals_tree_);
00082 
00083   points_sub_.subscribe (*pnh_, "points", queue_size_);
00084 
00085   if (use_rect_) {
00086     rect_sub_.subscribe   (*pnh_, "rect", queue_size_);
00087     if (use_sync_) {
00088       sync_a_rect_ = boost::make_shared < message_filters::Synchronizer< PolygonApproxSyncPolicy > > (queue_size_);
00089       sync_a_rect_->connectInput (points_sub_, rect_sub_);
00090       sync_a_rect_->registerCallback (boost::bind (&PointcloudScreenpoint::callback_rect, this, _1, _2));
00091     } else {
00092       rect_sub_.registerCallback (boost::bind (&PointcloudScreenpoint::rect_cb, this, _1));
00093     }
00094   }
00095   
00096   if (use_poly_) {
00097     poly_sub_.subscribe   (*pnh_, "poly", queue_size_);
00098     if (use_sync_) {
00099       sync_a_poly_ = boost::make_shared < message_filters::Synchronizer< PolygonApproxSyncPolicy > > (queue_size_);
00100       sync_a_poly_->connectInput (points_sub_, rect_sub_);
00101       sync_a_poly_->registerCallback (boost::bind (&PointcloudScreenpoint::callback_poly, this, _1, _2));
00102     } else {
00103       poly_sub_.registerCallback (boost::bind (&PointcloudScreenpoint::poly_cb, this, _1));
00104     }
00105   }
00106 
00107   if (use_point_) {
00108     point_sub_.subscribe  (*pnh_, "point", queue_size_);
00109     if (use_sync_) {
00110       sync_a_point_ = boost::make_shared < message_filters::Synchronizer< PointApproxSyncPolicy > > (queue_size_);
00111       sync_a_point_->connectInput (points_sub_, point_sub_);
00112       sync_a_point_->registerCallback (boost::bind (&PointcloudScreenpoint::callback_point, this, _1, _2));
00113     } else {
00114       point_sub_.registerCallback (boost::bind (&PointcloudScreenpoint::point_cb, this, _1));
00115     }
00116   }
00117 
00118   if (use_point_array_) {
00119     point_array_sub_.subscribe(*pnh_, "point_array", queue_size_);
00120     if (use_sync_) {
00121       sync_a_point_array_ = boost::make_shared < message_filters::Synchronizer< PointCloudApproxSyncPolicy > > (queue_size_);
00122       sync_a_point_array_->connectInput (points_sub_, point_array_sub_);
00123       sync_a_point_array_->registerCallback (boost::bind (&PointcloudScreenpoint::callback_point_array, this, _1, _2));
00124     } else {
00125       point_array_sub_.registerCallback (boost::bind (&PointcloudScreenpoint::point_array_cb, this, _1));
00126     }
00127   }
00128 
00129   points_sub_.registerCallback (boost::bind (&PointcloudScreenpoint::points_cb, this, _1));
00130 }
00131 
00132 
00133 bool jsk_pcl_ros::PointcloudScreenpoint::checkpoint (pcl::PointCloud< pcl::PointXYZ > &in_pts, int x, int y,
00134                                                      float &resx, float &resy, float &resz)  {
00135   if ((x < 0) || (y < 0) || (x >= in_pts.width) || (y >= in_pts.height)) {
00136     ROS_WARN("Requested point is out of image size.  point: (%d, %d)  size: (%d, %d)", x, y, in_pts.width, in_pts.height);
00137     return false;
00138   }
00139   pcl::PointXYZ p = in_pts.points[in_pts.width * y + x];
00140   // search near points
00141   ROS_INFO("Request: screenpoint (%d, %d) => (%f, %f, %f)", x, y, p.x, p.y, p.z);
00142   //return !(isnan (p.x) || ( (p.x == 0.0) && (p.y == 0.0) && (p.z == 0.0)));
00143 
00144   if ( !std::isnan (p.x) && ((p.x != 0.0) || (p.y != 0.0) || (p.z == 0.0)) ) {
00145     resx = p.x; resy = p.y; resz = p.z;
00146     return true;
00147   }
00148   return false;
00149 }
00150 
00151 bool jsk_pcl_ros::PointcloudScreenpoint::extract_point (pcl::PointCloud< pcl::PointXYZ > &in_pts, int reqx, int reqy,
00152                                                         float &resx, float &resy, float &resz) {
00153   int x, y;
00154 
00155   x = reqx < 0.0 ? ceil(reqx - 0.5) : floor(reqx + 0.5);
00156   y = reqy < 0.0 ? ceil(reqy - 0.5) : floor(reqy + 0.5);
00157   ROS_INFO("Request : %d %d", x, y);
00158 
00159   if (checkpoint (in_pts, x, y, resx, resy, resz)) {
00160     return true;
00161   } else {
00162     for (int n = 1; n < crop_size_; n++) {
00163       for (int y2 = 0; y2 <= n; y2++) {
00164         int x2 = n - y2;
00165         if (checkpoint (in_pts, x + x2, y + y2, resx, resy, resz)) {
00166           return true;
00167         }
00168         if (x2 != 0 && y2 != 0) {
00169           if (checkpoint (in_pts, x - x2, y - y2, resx, resy, resz)) {
00170             return true;
00171           }
00172         }
00173         if (x2 != 0) {
00174           if (checkpoint (in_pts, x - x2, y + y2, resx, resy, resz)) {
00175             return true;
00176           }
00177         }
00178         if (y2 != 0) {
00179           if (checkpoint (in_pts, x + x2, y - y2, resx, resy, resz)) {
00180             return true;
00181           }
00182         }
00183       }
00184     }
00185   }
00186   return false;
00187 }
00188 
00189 bool jsk_pcl_ros::PointcloudScreenpoint::screenpoint_cb (jsk_recognition_msgs::TransformScreenpoint::Request &req,
00190                                                          jsk_recognition_msgs::TransformScreenpoint::Response &res)
00191 {
00192   ROS_DEBUG("PointcloudScreenpoint::screenpoint_cb");
00193   boost::mutex::scoped_lock lock(this->mutex_callback_);
00194   if ( pts_.points.size() == 0 ) {
00195     ROS_ERROR("no point cloud was received");
00196     return false;
00197   }
00198 
00199   res.header = header_;
00200 
00201   bool ret;
00202   float rx, ry, rz;
00203   ret = extract_point (pts_, req.x, req.y, rx, ry, rz);
00204   res.point.x = rx; res.point.y = ry; res.point.z = rz;
00205 
00206   if (!ret) {
00207     return false;
00208   }
00209 
00210   // search normal
00211   n3d_.setSearchSurface(boost::make_shared<pcl::PointCloud<pcl::PointXYZ > > (pts_));
00212 
00213   pcl::PointCloud<pcl::PointXYZ> cloud_;
00214   pcl::PointXYZ pt;
00215   pt.x = res.point.x;
00216   pt.y = res.point.y;
00217   pt.z = res.point.z;
00218   cloud_.points.resize(0);
00219   cloud_.points.push_back(pt);
00220 
00221   n3d_.setInputCloud (boost::make_shared<pcl::PointCloud<pcl::PointXYZ > > (cloud_));
00222   pcl::PointCloud<pcl::Normal> cloud_normals;
00223   n3d_.compute (cloud_normals);
00224 
00225   res.vector.x = cloud_normals.points[0].normal_x;
00226   res.vector.y = cloud_normals.points[0].normal_y;
00227   res.vector.z = cloud_normals.points[0].normal_z;
00228 
00229   if((res.point.x * res.vector.x + res.point.y * res.vector.y + res.point.z * res.vector.z) < 0) {
00230     res.vector.x *= -1;
00231     res.vector.y *= -1;
00232     res.vector.z *= -1;
00233   }
00234 
00235   if (publish_point_) {
00236     geometry_msgs::PointStamped ps;
00237     ps.header = header_;
00238     ps.point.x = res.point.x;
00239     ps.point.y = res.point.y;
00240     ps.point.z = res.point.z;
00241     pub_point_.publish(ps);
00242   }
00243 
00244   return true;
00245 }
00246 
00247 void jsk_pcl_ros::PointcloudScreenpoint::points_cb(const sensor_msgs::PointCloud2ConstPtr &msg) {
00248   //ROS_DEBUG("PointcloudScreenpoint::points_cb");
00249   //boost::mutex::scoped_lock lock(this->mutex_callback_);
00250   header_ = msg->header;
00251   pcl::fromROSMsg (*msg, pts_);
00252 }
00253 
00254 void jsk_pcl_ros::PointcloudScreenpoint::extract_rect (const sensor_msgs::PointCloud2ConstPtr& points_ptr,
00255                                                        int st_x, int st_y, int ed_x, int ed_y) {
00256   if ( st_x < 0 ) st_x = 0;
00257   if ( st_y < 0 ) st_y = 0;
00258   if ( ed_x >= points_ptr->width ) ed_x = points_ptr->width -1;
00259   if ( ed_y >= points_ptr->height ) ed_y = points_ptr->height -1;
00260 
00261   int wd = points_ptr->width;
00262   int ht = points_ptr->height;
00263   int rstep = points_ptr->row_step;
00264   int pstep = points_ptr->point_step;
00265 
00266   sensor_msgs::PointCloud2 pt;
00267   pt.header = points_ptr->header;
00268   pt.width = ed_x - st_x + 1;
00269   pt.height = ed_y - st_y + 1;
00270   pt.row_step = pt.width * pstep;
00271   pt.point_step = pstep;
00272   pt.is_bigendian = false;
00273   pt.fields = points_ptr->fields;
00274   pt.is_dense = false;
00275   pt.data.resize(pt.row_step * pt.height);
00276 
00277   unsigned char * dst_ptr = &(pt.data[0]);
00278 
00279   for (size_t idx_y = st_y; idx_y <= ed_y; idx_y++) {
00280     for (size_t idx_x = st_x; idx_x <= ed_x; idx_x++) {
00281       const unsigned char * src_ptr = &(points_ptr->data[idx_y * rstep + idx_x * pstep]);
00282       memcpy(dst_ptr, src_ptr, pstep);
00283       dst_ptr += pstep;
00284     }
00285   }
00286 
00287   pub_points_.publish (pt);
00288 }
00289 
00290 void jsk_pcl_ros::PointcloudScreenpoint::point_cb (const geometry_msgs::PointStampedConstPtr& pt_ptr) {
00291   if (publish_point_) {
00292     geometry_msgs::PointStamped ps;
00293     bool ret; float rx, ry, rz;
00294     ret = extract_point (pts_, pt_ptr->point.x, pt_ptr->point.y, rx, ry, rz);
00295 
00296     if (ret) {
00297       ps.point.x = rx; ps.point.y = ry; ps.point.z = rz;
00298       ps.header = header_;
00299       pub_point_.publish (ps);
00300     }
00301   }
00302 }
00303 
00304 void jsk_pcl_ros::PointcloudScreenpoint::callback_point (const sensor_msgs::PointCloud2ConstPtr& points_ptr,
00305                                                          const geometry_msgs::PointStampedConstPtr& pt_ptr) {
00306   point_cb (pt_ptr);
00307 
00308   if (publish_points_) {
00309     int st_x = pt_ptr->point.x - crop_size_;
00310     int st_y = pt_ptr->point.y - crop_size_;
00311     int ed_x = pt_ptr->point.x + crop_size_;
00312     int ed_y = pt_ptr->point.y + crop_size_;
00313 
00314     extract_rect (points_ptr, st_x, st_y, ed_x, ed_y);
00315   }
00316 }
00317 
00318 void jsk_pcl_ros::PointcloudScreenpoint::point_array_cb (const sensor_msgs::PointCloud2ConstPtr& pt_arr_ptr) {
00319   if (publish_points_) {
00320     pcl::PointCloud<pcl::PointXY>::Ptr point_array_cloud(new pcl::PointCloud<pcl::PointXY>);
00321     pcl::fromROSMsg(*pt_arr_ptr, *point_array_cloud);
00322     pcl::PointCloud<pcl::PointXYZ>::Ptr result_cloud(new pcl::PointCloud<pcl::PointXYZ>);
00323     result_cloud->header = pcl_conversions::toPCL(header_); // if hydro
00324     for (size_t i = 0; i < point_array_cloud->points.size(); i++) {
00325       pcl::PointXY point = point_array_cloud->points[i];
00326       geometry_msgs::PointStamped ps;
00327       bool ret; float rx, ry, rz;
00328       ret = extract_point (pts_, point.x, point.y, rx, ry, rz);
00329       if (ret) {
00330         pcl::PointXYZ point_on_screen;
00331         point_on_screen.x = rx;
00332         point_on_screen.y = ry;
00333         point_on_screen.z = rz;
00334         result_cloud->points.push_back(point_on_screen);
00335       }
00336     }
00337     sensor_msgs::PointCloud2::Ptr ros_cloud(new sensor_msgs::PointCloud2);
00338     pcl::toROSMsg(*result_cloud, *ros_cloud);
00339     ros_cloud->header = header_;
00340     pub_points_.publish(ros_cloud);
00341   }
00342 }
00343 void jsk_pcl_ros::PointcloudScreenpoint::callback_point_array (const sensor_msgs::PointCloud2ConstPtr& points_ptr,
00344                                                                const sensor_msgs::PointCloud2ConstPtr& pt_arr_ptr) {
00345   point_array_cb(pt_arr_ptr);
00346 }
00347 
00348 void jsk_pcl_ros::PointcloudScreenpoint::rect_cb (const geometry_msgs::PolygonStampedConstPtr& array_ptr) {
00349   if (array_ptr->polygon.points.size() > 1) {
00350     int st_x = array_ptr->polygon.points[0].x;
00351     int st_y = array_ptr->polygon.points[0].y;
00352     int ed_x = array_ptr->polygon.points[1].x;
00353     int ed_y = array_ptr->polygon.points[1].y;
00354     if (publish_point_) {
00355       geometry_msgs::PointStamped ps;
00356       bool ret; float rx, ry, rz;
00357       ret = extract_point (pts_, (st_x + ed_x) / 2, (st_y + ed_y) / 2, rx, ry, rz);
00358 
00359       if (ret) {
00360         ps.point.x = rx; ps.point.y = ry; ps.point.z = rz;
00361         ps.header = header_;
00362         pub_point_.publish (ps);
00363       }
00364     }
00365   }
00366 }
00367 
00368 void jsk_pcl_ros::PointcloudScreenpoint::poly_cb(const geometry_msgs::PolygonStampedConstPtr& array_ptr) {
00369   // publish polygon
00370   geometry_msgs::PolygonStamped result_polygon;
00371   result_polygon.header = header_;
00372   for (size_t i = 0; i < array_ptr->polygon.points.size(); i++) {
00373     geometry_msgs::Point32 p = array_ptr->polygon.points[i];
00374     float rx, ry, rz;
00375     bool ret = extract_point (pts_, p.x, p.y, rx, ry, rz);
00376     if (!ret) {
00377       NODELET_ERROR("Failed to project point");
00378       return;
00379     }
00380     geometry_msgs::Point32 p_projected;
00381     p_projected.x = rx;
00382     p_projected.y = ry;
00383     p_projected.z = rz;
00384     result_polygon.polygon.points.push_back(p_projected);
00385   }
00386   pub_polygon_.publish(result_polygon);
00387 }
00388 
00389 void jsk_pcl_ros::PointcloudScreenpoint::callback_poly(const sensor_msgs::PointCloud2ConstPtr& points_ptr,
00390                                                        const geometry_msgs::PolygonStampedConstPtr& array_ptr) {
00391   poly_cb(array_ptr);
00392 }
00393 
00394 
00395 
00396 void jsk_pcl_ros::PointcloudScreenpoint::callback_rect(const sensor_msgs::PointCloud2ConstPtr& points_ptr,
00397                                                        const geometry_msgs::PolygonStampedConstPtr& array_ptr) {
00398   if (array_ptr->polygon.points.size() > 1) {
00399     int st_x = array_ptr->polygon.points[0].x;
00400     int st_y = array_ptr->polygon.points[0].y;
00401     int ed_x = array_ptr->polygon.points[1].x;
00402     int ed_y = array_ptr->polygon.points[1].y;
00403 
00404     rect_cb (array_ptr);
00405 
00406     if (publish_points_) {
00407       extract_rect (points_ptr, st_x, st_y, ed_x, ed_y);
00408     }
00409   }
00410 }
00411 
00412 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::PointcloudScreenpoint, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:50