pointcloud_screenpoint_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
38 
39 // F/K/A <ray converter>
40 // Haseru Chen, Kei Okada, Yohei Kakiuchi
41 
42 namespace mf = message_filters;
43 
44 namespace jsk_pcl_ros
45 {
46 
48 {
49  ConnectionBasedNodelet::onInit();
50 
51 
52  normals_tree_ = boost::make_shared< pcl::search::KdTree< pcl::PointXYZ > > ();
53  n3d_.setSearchMethod (normals_tree_);
54 
55  dyn_srv_ = boost::make_shared< dynamic_reconfigure::Server< Config > >(*pnh_);
56  dynamic_reconfigure::Server<Config>::CallbackType f =
57  boost::bind(&PointcloudScreenpoint::configCallback, this, _1, _2);
58  dyn_srv_->setCallback(f);
59 
60  srv_ = pnh_->advertiseService(
61  "screen_to_point", &PointcloudScreenpoint::screenpoint_cb, this);
62 
63  pub_points_ = advertise< sensor_msgs::PointCloud2 >(*pnh_, "output", 1);
64  pub_point_ = advertise< geometry_msgs::PointStamped >(*pnh_, "output_point", 1);
65  pub_polygon_ = advertise< geometry_msgs::PolygonStamped >(*pnh_, "output_polygon", 1);
66 
68 }
69 
71 {
72  points_sub_.subscribe(*pnh_, "points", 1);
73  rect_sub_.subscribe(*pnh_, "rect", 1);
74  poly_sub_.subscribe(*pnh_, "poly", 1);
75  point_sub_.subscribe(*pnh_, "point", 1);
76  point_array_sub_.subscribe(*pnh_, "point_array", 1);
77 
78  if (synchronization_)
79  {
81  {
82  async_rect_ = boost::make_shared<
84  async_rect_->connectInput(points_sub_, rect_sub_);
85  async_rect_->registerCallback(
86  boost::bind(&PointcloudScreenpoint::sync_rect_cb, this, _1, _2));
87 
88  async_poly_ = boost::make_shared<
90  async_poly_->connectInput(points_sub_, rect_sub_);
91  async_poly_->registerCallback(
92  boost::bind(&PointcloudScreenpoint::sync_poly_cb, this, _1, _2));
93 
94  async_point_ = boost::make_shared<
96  async_point_->connectInput(points_sub_, point_sub_);
97  async_point_->registerCallback(
98  boost::bind(&PointcloudScreenpoint::sync_point_cb, this, _1, _2));
99 
100  async_point_array_ = boost::make_shared<
103  async_point_array_->registerCallback(
104  boost::bind(&PointcloudScreenpoint::sync_point_array_cb, this, _1, _2));
105  }
106  else
107  {
108  sync_rect_ = boost::make_shared<
110  sync_rect_->connectInput(points_sub_, rect_sub_);
111  sync_rect_->registerCallback(
112  boost::bind(&PointcloudScreenpoint::sync_rect_cb, this, _1, _2));
113 
114  sync_poly_ = boost::make_shared<
116  sync_poly_->connectInput(points_sub_, rect_sub_);
117  sync_poly_->registerCallback(
118  boost::bind(&PointcloudScreenpoint::sync_poly_cb, this, _1, _2));
119 
120  sync_point_ = boost::make_shared<
122  sync_point_->connectInput(points_sub_, point_sub_);
123  sync_point_->registerCallback(
124  boost::bind(&PointcloudScreenpoint::sync_point_cb, this, _1, _2));
125 
126  sync_point_array_ = boost::make_shared<
129  sync_point_array_->registerCallback(
130  boost::bind(&PointcloudScreenpoint::sync_point_array_cb, this, _1, _2));
131  }
132  }
133  else
134  {
136  boost::bind(&PointcloudScreenpoint::points_cb, this, _1));
138  boost::bind(&PointcloudScreenpoint::rect_cb, this, _1));
140  boost::bind(&PointcloudScreenpoint::poly_cb, this, _1));
142  boost::bind(&PointcloudScreenpoint::point_cb, this, _1));
144  boost::bind(&PointcloudScreenpoint::point_array_cb, this, _1));
145  }
146 }
147 
149 {
155 }
156 
157 void PointcloudScreenpoint::configCallback(Config& config, uint32_t level)
158 {
159  boost::mutex::scoped_lock lock(mutex_);
160 
161  bool need_resubscribe = false;
162  if (synchronization_ != config.synchronization ||
163  approximate_sync_ != config.approximate_sync ||
164  queue_size_ != config.queue_size)
165  need_resubscribe = true;
166 
167  synchronization_ = config.synchronization;
168  approximate_sync_ = config.approximate_sync;
169  queue_size_ = config.queue_size;
170  crop_size_ = config.crop_size;
171  timeout_ = config.timeout;
172 
173  if (search_size_ != config.search_size)
174  {
175  search_size_ = config.search_size;
176  n3d_.setKSearch (search_size_);
177  }
178 
179  if (need_resubscribe && isSubscribed())
180  {
181  unsubscribe();
182  subscribe();
183  }
184 }
185 
186 // Service callback functions
188  jsk_recognition_msgs::TransformScreenpoint::Request &req,
189  jsk_recognition_msgs::TransformScreenpoint::Response &res)
190 {
191  NODELET_DEBUG("PointcloudScreenpoint::screenpoint_cb");
192  boost::mutex::scoped_lock lock(mutex_);
193 
194  if ( latest_cloud_.empty() && req.no_update ) {
195  NODELET_ERROR("no point cloud was received");
196  return false;
197  }
198 
199  bool need_unsubscribe = false;
200  if (!points_sub_.getSubscriber()) {
202  boost::bind(&PointcloudScreenpoint::points_cb, this, _1));
203  need_unsubscribe = true;
204  }
205 
206  // wait for cloud
208  ros::Rate r(10);
209  while (ros::ok())
210  {
211  if ( !latest_cloud_.empty() ) break;
212  if ((ros::Time::now() - start).toSec() > timeout_) break;
213  r.sleep();
214  ros::spinOnce();
215  NODELET_INFO_THROTTLE(1.0, "Waiting for point cloud...");
216  }
217 
218  if (need_unsubscribe)
219  {
221  }
222 
223  if (latest_cloud_.empty())
224  {
225  NODELET_ERROR("no point cloud was received");
226  return false;
227  }
228 
229  res.header = latest_cloud_header_;
230 
231  bool ret;
232  float rx, ry, rz;
233  ret = extract_point (latest_cloud_, req.x, req.y, rx, ry, rz);
234  res.point.x = rx; res.point.y = ry; res.point.z = rz;
235 
236  if (!ret) {
237  NODELET_ERROR("Failed to extract point");
238  return false;
239  }
240 
241  // search normal
242  n3d_.setSearchSurface(
243  boost::make_shared<pcl::PointCloud<pcl::PointXYZ > > (latest_cloud_));
244 
245  pcl::PointCloud<pcl::PointXYZ> cloud_;
246  pcl::PointXYZ pt;
247  pt.x = res.point.x;
248  pt.y = res.point.y;
249  pt.z = res.point.z;
250  cloud_.points.resize(0);
251  cloud_.points.push_back(pt);
252 
253  n3d_.setInputCloud (boost::make_shared<pcl::PointCloud<pcl::PointXYZ > > (cloud_));
254  pcl::PointCloud<pcl::Normal> cloud_normals;
255  n3d_.compute (cloud_normals);
256 
257  res.vector.x = cloud_normals.points[0].normal_x;
258  res.vector.y = cloud_normals.points[0].normal_y;
259  res.vector.z = cloud_normals.points[0].normal_z;
260 
261  if((res.point.x * res.vector.x + res.point.y * res.vector.y + res.point.z * res.vector.z) < 0) {
262  res.vector.x *= -1;
263  res.vector.y *= -1;
264  res.vector.z *= -1;
265  }
266 
267  if (pub_point_.getNumSubscribers() > 0) {
268  geometry_msgs::PointStamped ps;
269  ps.header = latest_cloud_header_;
270  ps.point.x = res.point.x;
271  ps.point.y = res.point.y;
272  ps.point.z = res.point.z;
273  pub_point_.publish(ps);
274  }
275 
276  return true;
277 }
278 
279 // Message callback functions
280 void PointcloudScreenpoint::points_cb(const sensor_msgs::PointCloud2::ConstPtr &msg)
281 {
282  NODELET_DEBUG("PointcloudScreenpoint::points_cb, width=%d, height=%d, fields=%ld",
283  msg->width, msg->height, msg->fields.size());
284 
285  latest_cloud_header_ = msg->header;
287 }
288 
289 void PointcloudScreenpoint::point_cb (const geometry_msgs::PointStampedConstPtr& pt_ptr)
290 {
291  if (latest_cloud_.empty())
292  {
293  NODELET_ERROR_THROTTLE(1.0, "no point cloud was received");
294  return;
295  }
296  if (pub_point_.getNumSubscribers() > 0)
297  {
298  geometry_msgs::PointStamped ps;
299  bool ret; float rx, ry, rz;
300  ret = extract_point (latest_cloud_, pt_ptr->point.x, pt_ptr->point.y, rx, ry, rz);
301 
302  if (ret) {
303  ps.point.x = rx; ps.point.y = ry; ps.point.z = rz;
304  ps.header = latest_cloud_header_;
305  pub_point_.publish (ps);
306  }
307  }
308  if (pub_points_.getNumSubscribers() > 0)
309  {
310  int st_x = pt_ptr->point.x - crop_size_;
311  int st_y = pt_ptr->point.y - crop_size_;
312  int ed_x = pt_ptr->point.x + crop_size_;
313  int ed_y = pt_ptr->point.y + crop_size_;
314  sensor_msgs::PointCloud2 out_pts;
315  extract_rect (latest_cloud_, st_x, st_y, ed_x, ed_y, out_pts);
316  pub_points_.publish(out_pts);
317  }
318 }
319 
320 void PointcloudScreenpoint::point_array_cb (const sensor_msgs::PointCloud2ConstPtr& pt_arr_ptr)
321 {
322  if (latest_cloud_.empty())
323  {
324  NODELET_ERROR_THROTTLE(1.0, "no point cloud was received");
325  return;
326  }
327  if (pub_points_.getNumSubscribers() > 0) {
328  pcl::PointCloud<pcl::PointXY>::Ptr point_array_cloud(new pcl::PointCloud<pcl::PointXY>);
329  pcl::fromROSMsg(*pt_arr_ptr, *point_array_cloud);
330  pcl::PointCloud<pcl::PointXYZ>::Ptr result_cloud(new pcl::PointCloud<pcl::PointXYZ>);
331  result_cloud->header = pcl_conversions::toPCL(latest_cloud_header_); // FIXME: if hydro
332  for (size_t i = 0; i < point_array_cloud->points.size(); i++) {
333  pcl::PointXY point = point_array_cloud->points[i];
334  geometry_msgs::PointStamped ps;
335  bool ret; float rx, ry, rz;
336  ret = extract_point (latest_cloud_, point.x, point.y, rx, ry, rz);
337  if (ret) {
338  pcl::PointXYZ point_on_screen;
339  point_on_screen.x = rx;
340  point_on_screen.y = ry;
341  point_on_screen.z = rz;
342  result_cloud->points.push_back(point_on_screen);
343  }
344  }
345  sensor_msgs::PointCloud2::Ptr ros_cloud(new sensor_msgs::PointCloud2);
346  pcl::toROSMsg(*result_cloud, *ros_cloud);
347  ros_cloud->header = latest_cloud_header_;
348  pub_points_.publish(ros_cloud);
349  }
350 }
351 
352 void PointcloudScreenpoint::rect_cb (const geometry_msgs::PolygonStampedConstPtr& array_ptr) {
353  if (latest_cloud_.empty())
354  {
355  NODELET_ERROR_THROTTLE(1.0, "no point cloud was received");
356  return;
357  }
358 
359  int num_pts = array_ptr->polygon.points.size();
360  if ( num_pts < 2) {
361  NODELET_ERROR("Point size must be 2.");
362  return;
363  } else if ( num_pts > 2 ) {
364  NODELET_WARN("Expected point size is 2, got %ld. "
365  "Used first 2 points to compute mid-coords.",
366  array_ptr->polygon.points.size());
367  }
368 
369  int st_x = array_ptr->polygon.points[0].x;
370  int st_y = array_ptr->polygon.points[0].y;
371  int ed_x = array_ptr->polygon.points[1].x;
372  int ed_y = array_ptr->polygon.points[1].y;
373 
374  if (pub_point_.getNumSubscribers() > 0)
375  {
376  geometry_msgs::PointStamped ps;
377  bool ret; float rx, ry, rz;
378  ret = extract_point (latest_cloud_, (st_x + ed_x) / 2, (st_y + ed_y) / 2, rx, ry, rz);
379 
380  if (ret) {
381  ps.point.x = rx; ps.point.y = ry; ps.point.z = rz;
382  ps.header = latest_cloud_header_;
383  pub_point_.publish (ps);
384  }
385  }
386  if (pub_points_.getNumSubscribers() > 0)
387  {
388  sensor_msgs::PointCloud2 out_pts;
389  extract_rect (latest_cloud_, st_x, st_y, ed_x, ed_y, out_pts);
390  pub_points_.publish(out_pts);
391  }
392 }
393 
394 void PointcloudScreenpoint::poly_cb(const geometry_msgs::PolygonStampedConstPtr& array_ptr)
395 {
396  if (latest_cloud_.empty())
397  {
398  NODELET_ERROR_THROTTLE(1.0, "no point cloud was received");
399  return;
400  }
402  {
403  geometry_msgs::PolygonStamped result_polygon;
404  result_polygon.header = latest_cloud_header_;
405  for (size_t i = 0; i < array_ptr->polygon.points.size(); i++) {
406  geometry_msgs::Point32 p = array_ptr->polygon.points[i];
407  float rx, ry, rz;
408  bool ret = extract_point (latest_cloud_, p.x, p.y, rx, ry, rz);
409  if (!ret) {
410  NODELET_ERROR("Failed to project point");
411  continue;
412  }
413  geometry_msgs::Point32 p_projected;
414  p_projected.x = rx;
415  p_projected.y = ry;
416  p_projected.z = rz;
417  result_polygon.polygon.points.push_back(p_projected);
418  }
419  pub_polygon_.publish(result_polygon);
420  }
421 }
422 
424  const sensor_msgs::PointCloud2::ConstPtr& points_ptr,
425  const geometry_msgs::PointStamped::ConstPtr& pt_ptr)
426 {
427  boost::mutex::scoped_lock lock(mutex_);
428  points_cb (points_ptr);
429  point_cb (pt_ptr);
430 }
431 
433  const sensor_msgs::PointCloud2::ConstPtr& points_ptr,
434  const sensor_msgs::PointCloud2::ConstPtr& pt_arr_ptr)
435 {
436  boost::mutex::scoped_lock lock(mutex_);
437  points_cb (points_ptr);
438  point_array_cb(pt_arr_ptr);
439 }
440 
442  const sensor_msgs::PointCloud2::ConstPtr& points_ptr,
443  const geometry_msgs::PolygonStamped::ConstPtr& array_ptr)
444 {
445  boost::mutex::scoped_lock lock(mutex_);
446  points_cb (points_ptr);
447  poly_cb(array_ptr);
448 }
449 
451  const sensor_msgs::PointCloud2::ConstPtr& points_ptr,
452  const geometry_msgs::PolygonStamped::ConstPtr& array_ptr) {
453  boost::mutex::scoped_lock lock(mutex_);
454  points_cb(points_ptr);
455  rect_cb (array_ptr);
456 }
457 
458 bool PointcloudScreenpoint::checkpoint (const pcl::PointCloud< pcl::PointXYZ > &in_pts,
459  int x, int y,
460  float &resx, float &resy, float &resz)
461 {
462  if ((x < 0) || (y < 0) || (x >= in_pts.width) || (y >= in_pts.height)) {
463  NODELET_WARN("Requested point is out of image size. "
464  "point: (%d, %d) size: (%d, %d)",
465  x, y, in_pts.width, in_pts.height);
466  return false;
467  }
468 
469  pcl::PointXYZ p = in_pts.points[in_pts.width * y + x];
470  // search near points
471  NODELET_DEBUG("Request: screenpoint (%d, %d) => (%f, %f, %f)", x, y, p.x, p.y, p.z);
472  //return !(isnan (p.x) || ( (p.x == 0.0) && (p.y == 0.0) && (p.z == 0.0)));
473 
474  if ( !std::isnan (p.x) && ((p.x != 0.0) || (p.y != 0.0) || (p.z == 0.0)) ) {
475  resx = p.x; resy = p.y; resz = p.z;
476  return true;
477  }
478  return false;
479 }
480 
481 bool PointcloudScreenpoint::extract_point(const pcl::PointCloud< pcl::PointXYZ > &in_pts,
482  int reqx, int reqy,
483  float &resx, float &resy, float &resz)
484 {
485  int x, y;
486 
487  x = reqx < 0.0 ? ceil(reqx - 0.5) : floor(reqx + 0.5);
488  y = reqy < 0.0 ? ceil(reqy - 0.5) : floor(reqy + 0.5);
489  NODELET_DEBUG("Request : %d %d", x, y);
490 
491  if (checkpoint (in_pts, x, y, resx, resy, resz)) {
492  return true;
493  } else {
494  for (int n = 1; n < crop_size_; n++) {
495  for (int y2 = 0; y2 <= n; y2++) {
496  int x2 = n - y2;
497  if (checkpoint (in_pts, x + x2, y + y2, resx, resy, resz)) {
498  return true;
499  }
500  if (x2 != 0 && y2 != 0) {
501  if (checkpoint (in_pts, x - x2, y - y2, resx, resy, resz)) {
502  return true;
503  }
504  }
505  if (x2 != 0) {
506  if (checkpoint (in_pts, x - x2, y + y2, resx, resy, resz)) {
507  return true;
508  }
509  }
510  if (y2 != 0) {
511  if (checkpoint (in_pts, x + x2, y - y2, resx, resy, resz)) {
512  return true;
513  }
514  }
515  }
516  }
517  }
518  return false;
519 }
520 
521 void PointcloudScreenpoint::extract_rect (const pcl::PointCloud< pcl::PointXYZ >& in_pts,
522  int st_x, int st_y,
523  int ed_x, int ed_y,
524  sensor_msgs::PointCloud2& out_pts)
525 {
526  sensor_msgs::PointCloud2::Ptr points_ptr(new sensor_msgs::PointCloud2);
527  pcl::toROSMsg(in_pts, *points_ptr);
528 
529  if ( st_x < 0 ) st_x = 0;
530  if ( st_y < 0 ) st_y = 0;
531  if ( ed_x >= points_ptr->width ) ed_x = points_ptr->width -1;
532  if ( ed_y >= points_ptr->height ) ed_y = points_ptr->height -1;
533 
534  int wd = points_ptr->width;
535  int ht = points_ptr->height;
536  int rstep = points_ptr->row_step;
537  int pstep = points_ptr->point_step;
538 
539  out_pts.header = points_ptr->header;
540  out_pts.width = ed_x - st_x + 1;
541  out_pts.height = ed_y - st_y + 1;
542  out_pts.row_step = out_pts.width * pstep;
543  out_pts.point_step = pstep;
544  out_pts.is_bigendian = false;
545  out_pts.fields = points_ptr->fields;
546  out_pts.is_dense = false;
547  out_pts.data.resize(out_pts.row_step * out_pts.height);
548 
549  unsigned char * dst_ptr = &(out_pts.data[0]);
550 
551  for (size_t idx_y = st_y; idx_y <= ed_y; idx_y++) {
552  for (size_t idx_x = st_x; idx_x <= ed_x; idx_x++) {
553  const unsigned char * src_ptr = &(points_ptr->data[idx_y * rstep + idx_x * pstep]);
554  memcpy(dst_ptr, src_ptr, pstep);
555  dst_ptr += pstep;
556  }
557  }
558 }
559 
560 } // namespace jsk_pcl_ros
561 
pcl::NormalEstimation< pcl::PointXYZ, pcl::Normal > n3d_
#define NODELET_ERROR(...)
boost::shared_ptr< mf::Synchronizer< PolygonExactSyncPolicy > > sync_rect_
#define NODELET_WARN(...)
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< mf::Synchronizer< PolygonApproxSyncPolicy > > async_poly_
PointcloudScreenpointConfig Config
GLfloat n[6][3]
void sync_rect_cb(const sensor_msgs::PointCloud2ConstPtr &points_ptr, const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
#define NODELET_ERROR_THROTTLE(rate,...)
mf::Subscriber< geometry_msgs::PointStamped > point_sub_
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
const ros::Subscriber & getSubscriber() const
boost::shared_ptr< mf::Synchronizer< PointApproxSyncPolicy > > async_point_
bool extract_point(const pcl::PointCloud< pcl::PointXYZ > &in_pts, int reqx, int reqy, float &resx, float &resy, float &resz)
void toPCL(const pcl_msgs::PointIndices &pi, pcl::PointIndices &pcl_pi)
boost::shared_ptr< mf::Synchronizer< PointExactSyncPolicy > > sync_point_
void point_array_cb(const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr)
pcl::search::KdTree< pcl::PointXYZ >::Ptr normals_tree_
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::AddColorFromImage, nodelet::Nodelet)
bool checkpoint(const pcl::PointCloud< pcl::PointXYZ > &in_pts, int x, int y, float &resx, float &resy, float &resz)
boost::shared_ptr< ros::NodeHandle > pnh_
boost::shared_ptr< mf::Synchronizer< PolygonExactSyncPolicy > > sync_poly_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > dyn_srv_
ROSCPP_DECL bool ok()
void sync_point_cb(const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const geometry_msgs::PointStamped::ConstPtr &pt_ptr)
mf::Subscriber< geometry_msgs::PolygonStamped > rect_sub_
start
void point_cb(const geometry_msgs::PointStamped::ConstPtr &pt_ptr)
void sync_point_array_cb(const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const sensor_msgs::PointCloud2::ConstPtr &pt_arr_ptr)
virtual void configCallback(Config &config, uint32_t level)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
bool sleep()
bool screenpoint_cb(jsk_recognition_msgs::TransformScreenpoint::Request &req, jsk_recognition_msgs::TransformScreenpoint::Response &res)
#define NODELET_INFO_THROTTLE(rate,...)
mf::Subscriber< sensor_msgs::PointCloud2 > points_sub_
void extract_rect(const pcl::PointCloud< pcl::PointXYZ > &in_pts, int st_x, int st_y, int ed_x, int ed_y, sensor_msgs::PointCloud2 &out_pts)
mf::Subscriber< geometry_msgs::PolygonStamped > poly_sub_
uint32_t getNumSubscribers() const
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void points_cb(const sensor_msgs::PointCloud2::ConstPtr &msg)
void poly_cb(const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
boost::shared_ptr< mf::Synchronizer< PolygonApproxSyncPolicy > > async_rect_
p
pcl::PointCloud< pcl::PointXYZ > latest_cloud_
static Time now()
void rect_cb(const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
void sync_poly_cb(const sensor_msgs::PointCloud2::ConstPtr &points_ptr, const geometry_msgs::PolygonStamped::ConstPtr &array_ptr)
boost::shared_ptr< mf::Synchronizer< PointCloudApproxSyncPolicy > > async_point_array_
ROSCPP_DECL void spinOnce()
#define NODELET_DEBUG(...)
boost::shared_ptr< mf::Synchronizer< PointCloudExactSyncPolicy > > sync_point_array_
mf::Subscriber< sensor_msgs::PointCloud2 > point_array_sub_
Connection registerCallback(const C &callback)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47