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_pcl_ros/pointcloud_screenpoint.h>
00037 #include <pcl_conversions/pcl_conversions.h>
00038 
00039 // F/K/A <ray converter>
00040 // Haseru Chen, Kei Okada, Yohei Kakiuchi
00041 
00042 namespace mf = message_filters;
00043 
00044 namespace jsk_pcl_ros
00045 {
00046 
00047 void PointcloudScreenpoint::onInit()
00048 {
00049   ConnectionBasedNodelet::onInit();
00050 
00051 
00052   normals_tree_ = boost::make_shared< pcl::search::KdTree< pcl::PointXYZ > > ();
00053   n3d_.setSearchMethod (normals_tree_);
00054 
00055   dyn_srv_ = boost::make_shared< dynamic_reconfigure::Server< Config > >(*pnh_);
00056   dynamic_reconfigure::Server<Config>::CallbackType f =
00057       boost::bind(&PointcloudScreenpoint::configCallback, this, _1, _2);
00058   dyn_srv_->setCallback(f);
00059 
00060   srv_ = pnh_->advertiseService(
00061       "screen_to_point", &PointcloudScreenpoint::screenpoint_cb, this);
00062 
00063   pub_points_  = advertise< sensor_msgs::PointCloud2 >(*pnh_, "output", 1);
00064   pub_point_   = advertise< geometry_msgs::PointStamped >(*pnh_, "output_point", 1);
00065   pub_polygon_ = advertise< geometry_msgs::PolygonStamped >(*pnh_, "output_polygon", 1);
00066 
00067   onInitPostProcess();
00068 }
00069 
00070 void PointcloudScreenpoint::subscribe()
00071 {
00072   points_sub_.subscribe(*pnh_, "points", 1);
00073   rect_sub_.subscribe(*pnh_, "rect", 1);
00074   poly_sub_.subscribe(*pnh_, "poly", 1);
00075   point_sub_.subscribe(*pnh_, "point", 1);
00076   point_array_sub_.subscribe(*pnh_, "point_array", 1);
00077 
00078   if (synchronization_)
00079   {
00080     if (approximate_sync_)
00081     {
00082       async_rect_ = boost::make_shared<
00083         mf::Synchronizer<PolygonApproxSyncPolicy> >(queue_size_);
00084       async_rect_->connectInput(points_sub_, rect_sub_);
00085       async_rect_->registerCallback(
00086           boost::bind(&PointcloudScreenpoint::sync_rect_cb, this, _1, _2));
00087 
00088       async_poly_ = boost::make_shared<
00089         mf::Synchronizer<PolygonApproxSyncPolicy> >(queue_size_);
00090       async_poly_->connectInput(points_sub_, rect_sub_);
00091       async_poly_->registerCallback(
00092           boost::bind(&PointcloudScreenpoint::sync_poly_cb, this, _1, _2));
00093 
00094       async_point_ = boost::make_shared<
00095         mf::Synchronizer<PointApproxSyncPolicy> >(queue_size_);
00096       async_point_->connectInput(points_sub_, point_sub_);
00097       async_point_->registerCallback(
00098           boost::bind(&PointcloudScreenpoint::sync_point_cb, this, _1, _2));
00099 
00100       async_point_array_ = boost::make_shared<
00101         mf::Synchronizer<PointCloudApproxSyncPolicy> >(queue_size_);
00102       async_point_array_->connectInput(points_sub_, point_array_sub_);
00103       async_point_array_->registerCallback(
00104           boost::bind(&PointcloudScreenpoint::sync_point_array_cb, this, _1, _2));
00105     }
00106     else
00107     {
00108       sync_rect_ = boost::make_shared<
00109         mf::Synchronizer<PolygonExactSyncPolicy> >(queue_size_);
00110       sync_rect_->connectInput(points_sub_, rect_sub_);
00111       sync_rect_->registerCallback(
00112           boost::bind(&PointcloudScreenpoint::sync_rect_cb, this, _1, _2));
00113 
00114       sync_poly_ = boost::make_shared<
00115         mf::Synchronizer<PolygonExactSyncPolicy> >(queue_size_);
00116       sync_poly_->connectInput(points_sub_, rect_sub_);
00117       sync_poly_->registerCallback(
00118           boost::bind(&PointcloudScreenpoint::sync_poly_cb, this, _1, _2));
00119 
00120       sync_point_ = boost::make_shared<
00121         mf::Synchronizer<PointExactSyncPolicy> >(queue_size_);
00122       sync_point_->connectInput(points_sub_, point_sub_);
00123       sync_point_->registerCallback(
00124           boost::bind(&PointcloudScreenpoint::sync_point_cb, this, _1, _2));
00125 
00126       sync_point_array_ = boost::make_shared<
00127         mf::Synchronizer<PointCloudExactSyncPolicy> >(queue_size_);
00128       sync_point_array_->connectInput(points_sub_, point_array_sub_);
00129       sync_point_array_->registerCallback(
00130           boost::bind(&PointcloudScreenpoint::sync_point_array_cb, this, _1, _2));
00131     }
00132   }
00133   else
00134   {
00135     points_sub_.registerCallback(
00136         boost::bind(&PointcloudScreenpoint::points_cb, this, _1));
00137     rect_sub_.registerCallback(
00138         boost::bind(&PointcloudScreenpoint::rect_cb, this, _1));
00139     poly_sub_.registerCallback(
00140         boost::bind(&PointcloudScreenpoint::poly_cb, this, _1));
00141     point_sub_.registerCallback(
00142         boost::bind(&PointcloudScreenpoint::point_cb, this, _1));
00143     point_array_sub_.registerCallback(
00144         boost::bind(&PointcloudScreenpoint::point_array_cb, this, _1));
00145   }
00146 }
00147 
00148 void PointcloudScreenpoint::unsubscribe()
00149 {
00150   points_sub_.unsubscribe();
00151   rect_sub_.unsubscribe();
00152   poly_sub_.unsubscribe();
00153   point_sub_.unsubscribe();
00154   point_array_sub_.unsubscribe();
00155 }
00156 
00157 void PointcloudScreenpoint::configCallback(Config& config, uint32_t level)
00158 {
00159   boost::mutex::scoped_lock lock(mutex_);
00160 
00161   bool need_resubscribe = false;
00162   if (synchronization_ != config.synchronization ||
00163       approximate_sync_ != config.approximate_sync ||
00164       queue_size_ != config.queue_size)
00165     need_resubscribe = true;
00166 
00167   synchronization_ = config.synchronization;
00168   approximate_sync_ = config.approximate_sync;
00169   queue_size_ = config.queue_size;
00170   crop_size_ = config.crop_size;
00171   timeout_ = config.timeout;
00172 
00173   if (search_size_ != config.search_size)
00174   {
00175     search_size_ = config.search_size;
00176     n3d_.setKSearch (search_size_);
00177   }
00178 
00179   if (need_resubscribe && isSubscribed())
00180   {
00181     unsubscribe();
00182     subscribe();
00183   }
00184 }
00185 
00186 // Service callback functions
00187 bool PointcloudScreenpoint::screenpoint_cb (
00188     jsk_recognition_msgs::TransformScreenpoint::Request &req,
00189     jsk_recognition_msgs::TransformScreenpoint::Response &res)
00190 {
00191   NODELET_DEBUG("PointcloudScreenpoint::screenpoint_cb");
00192   boost::mutex::scoped_lock lock(mutex_);
00193 
00194   if ( latest_cloud_.empty() && req.no_update ) {
00195     NODELET_ERROR("no point cloud was received");
00196     return false;
00197   }
00198 
00199   bool need_unsubscribe = false;
00200   if (!points_sub_.getSubscriber()) {
00201     points_sub_.registerCallback(
00202         boost::bind(&PointcloudScreenpoint::points_cb, this, _1));
00203     need_unsubscribe = true;
00204   }
00205 
00206   // wait for cloud
00207   ros::Time start = ros::Time::now();
00208   ros::Rate r(10);
00209   while (ros::ok())
00210   {
00211     if ( !latest_cloud_.empty() ) break;
00212     if ((ros::Time::now() - start).toSec() > timeout_) break;
00213     r.sleep();
00214     ros::spinOnce();
00215     NODELET_INFO_THROTTLE(1.0, "Waiting for point cloud...");
00216   }
00217 
00218   if (need_unsubscribe)
00219   {
00220     points_sub_.unsubscribe();
00221   }
00222 
00223   if (latest_cloud_.empty())
00224   {
00225     NODELET_ERROR("no point cloud was received");
00226     return false;
00227   }
00228 
00229   res.header = latest_cloud_header_;
00230 
00231   bool ret;
00232   float rx, ry, rz;
00233   ret = extract_point (latest_cloud_, req.x, req.y, rx, ry, rz);
00234   res.point.x = rx; res.point.y = ry; res.point.z = rz;
00235 
00236   if (!ret) {
00237     NODELET_ERROR("Failed to extract point");
00238     return false;
00239   }
00240 
00241   // search normal
00242   n3d_.setSearchSurface(
00243       boost::make_shared<pcl::PointCloud<pcl::PointXYZ > > (latest_cloud_));
00244 
00245   pcl::PointCloud<pcl::PointXYZ> cloud_;
00246   pcl::PointXYZ pt;
00247   pt.x = res.point.x;
00248   pt.y = res.point.y;
00249   pt.z = res.point.z;
00250   cloud_.points.resize(0);
00251   cloud_.points.push_back(pt);
00252 
00253   n3d_.setInputCloud (boost::make_shared<pcl::PointCloud<pcl::PointXYZ > > (cloud_));
00254   pcl::PointCloud<pcl::Normal> cloud_normals;
00255   n3d_.compute (cloud_normals);
00256 
00257   res.vector.x = cloud_normals.points[0].normal_x;
00258   res.vector.y = cloud_normals.points[0].normal_y;
00259   res.vector.z = cloud_normals.points[0].normal_z;
00260 
00261   if((res.point.x * res.vector.x + res.point.y * res.vector.y + res.point.z * res.vector.z) < 0) {
00262     res.vector.x *= -1;
00263     res.vector.y *= -1;
00264     res.vector.z *= -1;
00265   }
00266 
00267   if (pub_point_.getNumSubscribers() > 0) {
00268     geometry_msgs::PointStamped ps;
00269     ps.header = latest_cloud_header_;
00270     ps.point.x = res.point.x;
00271     ps.point.y = res.point.y;
00272     ps.point.z = res.point.z;
00273     pub_point_.publish(ps);
00274   }
00275 
00276   return true;
00277 }
00278 
00279 // Message callback functions
00280 void PointcloudScreenpoint::points_cb(const sensor_msgs::PointCloud2::ConstPtr &msg)
00281 {
00282   NODELET_DEBUG("PointcloudScreenpoint::points_cb, width=%d, height=%d, fields=%ld",
00283                 msg->width, msg->height, msg->fields.size());
00284 
00285   latest_cloud_header_ = msg->header;
00286   pcl::fromROSMsg (*msg, latest_cloud_);
00287 }
00288 
00289 void PointcloudScreenpoint::point_cb (const geometry_msgs::PointStampedConstPtr& pt_ptr)
00290 {
00291   if (latest_cloud_.empty())
00292   {
00293     NODELET_ERROR_THROTTLE(1.0, "no point cloud was received");
00294     return;
00295   }
00296   if (pub_point_.getNumSubscribers() > 0)
00297   {
00298     geometry_msgs::PointStamped ps;
00299     bool ret; float rx, ry, rz;
00300     ret = extract_point (latest_cloud_, pt_ptr->point.x, pt_ptr->point.y, rx, ry, rz);
00301 
00302     if (ret) {
00303       ps.point.x = rx; ps.point.y = ry; ps.point.z = rz;
00304       ps.header = latest_cloud_header_;
00305       pub_point_.publish (ps);
00306     }
00307   }
00308   if (pub_points_.getNumSubscribers() > 0)
00309   {
00310     int st_x = pt_ptr->point.x - crop_size_;
00311     int st_y = pt_ptr->point.y - crop_size_;
00312     int ed_x = pt_ptr->point.x + crop_size_;
00313     int ed_y = pt_ptr->point.y + crop_size_;
00314     sensor_msgs::PointCloud2 out_pts;
00315     extract_rect (latest_cloud_, st_x, st_y, ed_x, ed_y, out_pts);
00316     pub_points_.publish(out_pts);
00317   }
00318 }
00319 
00320 void PointcloudScreenpoint::point_array_cb (const sensor_msgs::PointCloud2ConstPtr& pt_arr_ptr)
00321 {
00322   if (latest_cloud_.empty())
00323   {
00324     NODELET_ERROR_THROTTLE(1.0, "no point cloud was received");
00325     return;
00326   }
00327   if (pub_points_.getNumSubscribers() > 0) {
00328     pcl::PointCloud<pcl::PointXY>::Ptr point_array_cloud(new pcl::PointCloud<pcl::PointXY>);
00329     pcl::fromROSMsg(*pt_arr_ptr, *point_array_cloud);
00330     pcl::PointCloud<pcl::PointXYZ>::Ptr result_cloud(new pcl::PointCloud<pcl::PointXYZ>);
00331     result_cloud->header = pcl_conversions::toPCL(latest_cloud_header_); // FIXME: if hydro
00332     for (size_t i = 0; i < point_array_cloud->points.size(); i++) {
00333       pcl::PointXY point = point_array_cloud->points[i];
00334       geometry_msgs::PointStamped ps;
00335       bool ret; float rx, ry, rz;
00336       ret = extract_point (latest_cloud_, point.x, point.y, rx, ry, rz);
00337       if (ret) {
00338         pcl::PointXYZ point_on_screen;
00339         point_on_screen.x = rx;
00340         point_on_screen.y = ry;
00341         point_on_screen.z = rz;
00342         result_cloud->points.push_back(point_on_screen);
00343       }
00344     }
00345     sensor_msgs::PointCloud2::Ptr ros_cloud(new sensor_msgs::PointCloud2);
00346     pcl::toROSMsg(*result_cloud, *ros_cloud);
00347     ros_cloud->header = latest_cloud_header_;
00348     pub_points_.publish(ros_cloud);
00349   }
00350 }
00351 
00352 void PointcloudScreenpoint::rect_cb (const geometry_msgs::PolygonStampedConstPtr& array_ptr) {
00353   if (latest_cloud_.empty())
00354   {
00355     NODELET_ERROR_THROTTLE(1.0, "no point cloud was received");
00356     return;
00357   }
00358 
00359   int num_pts = array_ptr->polygon.points.size();
00360   if ( num_pts < 2) {
00361     NODELET_ERROR("Point size must be 2.");
00362     return;
00363   } else if ( num_pts > 2 ) {
00364     NODELET_WARN("Expected point size is 2, got %ld. "
00365                  "Used first 2 points to compute mid-coords.",
00366                  array_ptr->polygon.points.size());
00367   }
00368 
00369   int st_x = array_ptr->polygon.points[0].x;
00370   int st_y = array_ptr->polygon.points[0].y;
00371   int ed_x = array_ptr->polygon.points[1].x;
00372   int ed_y = array_ptr->polygon.points[1].y;
00373 
00374   if (pub_point_.getNumSubscribers() > 0)
00375   {
00376     geometry_msgs::PointStamped ps;
00377     bool ret; float rx, ry, rz;
00378     ret = extract_point (latest_cloud_, (st_x + ed_x) / 2, (st_y + ed_y) / 2, rx, ry, rz);
00379 
00380     if (ret) {
00381       ps.point.x = rx; ps.point.y = ry; ps.point.z = rz;
00382       ps.header = latest_cloud_header_;
00383       pub_point_.publish (ps);
00384     }
00385   }
00386   if (pub_points_.getNumSubscribers() > 0)
00387   {
00388     sensor_msgs::PointCloud2 out_pts;
00389     extract_rect (latest_cloud_, st_x, st_y, ed_x, ed_y, out_pts);
00390     pub_points_.publish(out_pts);
00391   }
00392 }
00393 
00394 void PointcloudScreenpoint::poly_cb(const geometry_msgs::PolygonStampedConstPtr& array_ptr)
00395 {
00396   if (latest_cloud_.empty())
00397   {
00398     NODELET_ERROR_THROTTLE(1.0, "no point cloud was received");
00399     return;
00400   }
00401   if (pub_polygon_.getNumSubscribers() > 0)
00402   {
00403     geometry_msgs::PolygonStamped result_polygon;
00404     result_polygon.header = latest_cloud_header_;
00405     for (size_t i = 0; i < array_ptr->polygon.points.size(); i++) {
00406       geometry_msgs::Point32 p = array_ptr->polygon.points[i];
00407       float rx, ry, rz;
00408       bool ret = extract_point (latest_cloud_, p.x, p.y, rx, ry, rz);
00409       if (!ret) {
00410         NODELET_ERROR("Failed to project point");
00411         continue;
00412       }
00413       geometry_msgs::Point32 p_projected;
00414       p_projected.x = rx;
00415       p_projected.y = ry;
00416       p_projected.z = rz;
00417       result_polygon.polygon.points.push_back(p_projected);
00418     }
00419     pub_polygon_.publish(result_polygon);
00420   }
00421 }
00422 
00423 void PointcloudScreenpoint::sync_point_cb (
00424     const sensor_msgs::PointCloud2::ConstPtr& points_ptr,
00425     const geometry_msgs::PointStamped::ConstPtr& pt_ptr)
00426 {
00427   boost::mutex::scoped_lock lock(mutex_);
00428   points_cb (points_ptr);
00429   point_cb (pt_ptr);
00430 }
00431 
00432 void PointcloudScreenpoint::sync_point_array_cb (
00433     const sensor_msgs::PointCloud2::ConstPtr& points_ptr,
00434     const sensor_msgs::PointCloud2::ConstPtr& pt_arr_ptr)
00435 {
00436   boost::mutex::scoped_lock lock(mutex_);
00437   points_cb (points_ptr);
00438   point_array_cb(pt_arr_ptr);
00439 }
00440 
00441 void PointcloudScreenpoint::sync_poly_cb(
00442     const sensor_msgs::PointCloud2::ConstPtr& points_ptr,
00443     const geometry_msgs::PolygonStamped::ConstPtr& array_ptr)
00444 {
00445   boost::mutex::scoped_lock lock(mutex_);
00446   points_cb (points_ptr);
00447   poly_cb(array_ptr);
00448 }
00449 
00450 void PointcloudScreenpoint::sync_rect_cb(
00451     const sensor_msgs::PointCloud2::ConstPtr& points_ptr,
00452     const geometry_msgs::PolygonStamped::ConstPtr& array_ptr) {
00453   boost::mutex::scoped_lock lock(mutex_);
00454   points_cb(points_ptr);
00455   rect_cb (array_ptr);
00456 }
00457 
00458 bool PointcloudScreenpoint::checkpoint (const pcl::PointCloud< pcl::PointXYZ > &in_pts,
00459                                         int x, int y,
00460                                         float &resx, float &resy, float &resz)
00461 {
00462   if ((x < 0) || (y < 0) || (x >= in_pts.width) || (y >= in_pts.height)) {
00463     NODELET_WARN("Requested point is out of image size. "
00464              "point: (%d, %d)  size: (%d, %d)",
00465              x, y, in_pts.width, in_pts.height);
00466     return false;
00467   }
00468 
00469   pcl::PointXYZ p = in_pts.points[in_pts.width * y + x];
00470   // search near points
00471   NODELET_DEBUG("Request: screenpoint (%d, %d) => (%f, %f, %f)", x, y, p.x, p.y, p.z);
00472   //return !(isnan (p.x) || ( (p.x == 0.0) && (p.y == 0.0) && (p.z == 0.0)));
00473 
00474   if ( !std::isnan (p.x) && ((p.x != 0.0) || (p.y != 0.0) || (p.z == 0.0)) ) {
00475     resx = p.x; resy = p.y; resz = p.z;
00476     return true;
00477   }
00478   return false;
00479 }
00480 
00481 bool PointcloudScreenpoint::extract_point(const pcl::PointCloud< pcl::PointXYZ > &in_pts,
00482                                           int reqx, int reqy,
00483                                           float &resx, float &resy, float &resz)
00484 {
00485   int x, y;
00486 
00487   x = reqx < 0.0 ? ceil(reqx - 0.5) : floor(reqx + 0.5);
00488   y = reqy < 0.0 ? ceil(reqy - 0.5) : floor(reqy + 0.5);
00489   NODELET_DEBUG("Request : %d %d", x, y);
00490 
00491   if (checkpoint (in_pts, x, y, resx, resy, resz)) {
00492     return true;
00493   } else {
00494     for (int n = 1; n < crop_size_; n++) {
00495       for (int y2 = 0; y2 <= n; y2++) {
00496         int x2 = n - y2;
00497         if (checkpoint (in_pts, x + x2, y + y2, resx, resy, resz)) {
00498           return true;
00499         }
00500         if (x2 != 0 && y2 != 0) {
00501           if (checkpoint (in_pts, x - x2, y - y2, resx, resy, resz)) {
00502             return true;
00503           }
00504         }
00505         if (x2 != 0) {
00506           if (checkpoint (in_pts, x - x2, y + y2, resx, resy, resz)) {
00507             return true;
00508           }
00509         }
00510         if (y2 != 0) {
00511           if (checkpoint (in_pts, x + x2, y - y2, resx, resy, resz)) {
00512             return true;
00513           }
00514         }
00515       }
00516     }
00517   }
00518   return false;
00519 }
00520 
00521 void PointcloudScreenpoint::extract_rect (const pcl::PointCloud< pcl::PointXYZ >& in_pts,
00522                                           int st_x, int st_y,
00523                                           int ed_x, int ed_y,
00524                                           sensor_msgs::PointCloud2& out_pts)
00525 {
00526   sensor_msgs::PointCloud2::Ptr points_ptr(new sensor_msgs::PointCloud2);
00527   pcl::toROSMsg(in_pts, *points_ptr);
00528 
00529   if ( st_x < 0 ) st_x = 0;
00530   if ( st_y < 0 ) st_y = 0;
00531   if ( ed_x >= points_ptr->width ) ed_x = points_ptr->width -1;
00532   if ( ed_y >= points_ptr->height ) ed_y = points_ptr->height -1;
00533 
00534   int wd = points_ptr->width;
00535   int ht = points_ptr->height;
00536   int rstep = points_ptr->row_step;
00537   int pstep = points_ptr->point_step;
00538 
00539   out_pts.header = points_ptr->header;
00540   out_pts.width = ed_x - st_x + 1;
00541   out_pts.height = ed_y - st_y + 1;
00542   out_pts.row_step = out_pts.width * pstep;
00543   out_pts.point_step = pstep;
00544   out_pts.is_bigendian = false;
00545   out_pts.fields = points_ptr->fields;
00546   out_pts.is_dense = false;
00547   out_pts.data.resize(out_pts.row_step * out_pts.height);
00548 
00549   unsigned char * dst_ptr = &(out_pts.data[0]);
00550 
00551   for (size_t idx_y = st_y; idx_y <= ed_y; idx_y++) {
00552     for (size_t idx_x = st_x; idx_x <= ed_x; idx_x++) {
00553       const unsigned char * src_ptr = &(points_ptr->data[idx_y * rstep + idx_x * pstep]);
00554       memcpy(dst_ptr, src_ptr, pstep);
00555       dst_ptr += pstep;
00556     }
00557   }
00558 }
00559 
00560 } // namespace jsk_pcl_ros
00561 
00562 #include <pluginlib/class_list_macros.h>
00563 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::PointcloudScreenpoint, nodelet::Nodelet)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:41:44