attention_clipper_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 #define BOOST_PARAMETER_MAX_ARITY 7
39 #include <opencv2/opencv.hpp>
40 #include <cv_bridge/cv_bridge.h>
42 #include <pcl_ros/transforms.h>
47 #include <algorithm>
48 #include <set>
49 
50 #if ( CV_MAJOR_VERSION >= 4)
51 #include <opencv2/imgproc/imgproc_c.h>
52 #endif
53 
54 namespace jsk_pcl_ros
55 {
57  {
58  DiagnosticNodelet::onInit();
60  pnh_->param("negative", negative_, false);
61  pnh_->param("use_multiple_attention", use_multiple_attention_, false);
63  Eigen::Affine3f pose = Eigen::Affine3f::Identity();
64  std::vector<double> initial_pos;
66  "initial_pos",
67  initial_pos))
68  {
69  pose.translation() = Eigen::Vector3f(initial_pos[0],
70  initial_pos[1],
71  initial_pos[2]);
72  }
73 
74  std::vector<double> initial_rot;
76  "initial_rot",
77  initial_rot))
78  {
79  pose = pose
80  * Eigen::AngleAxisf(initial_rot[0],
81  Eigen::Vector3f::UnitX())
82  * Eigen::AngleAxisf(initial_rot[1],
83  Eigen::Vector3f::UnitY())
84  * Eigen::AngleAxisf(initial_rot[2],
85  Eigen::Vector3f::UnitZ());
86  }
87 
88  // parameter
89  // backward compatibility
90  double dimension_x, dimension_y, dimension_z;
91  pnh_->param("dimension_x", dimension_x, 0.1);
92  pnh_->param("dimension_y", dimension_y, 0.1);
93  pnh_->param("dimension_z", dimension_z, 0.1);
94  dimensions_.push_back(Eigen::Vector3f(dimension_x,
95  dimension_y,
96  dimension_z));
97  std::string frame_id;
98  pnh_->param("frame_id", frame_id, std::string("base_link"));
99  frame_id_list_.push_back(frame_id);
100  pose_list_.push_back(pose);
101  }
102  else { // multiple interst
103  // ~initial_pos_list
104  // -> [[0, 0, 0], ...]
105  std::vector<std::vector<double> > initial_pos_list;
106  std::vector<std::vector<double> > initial_rot_list;
107  std::vector<std::vector<double> > dimensions;
108  jsk_topic_tools::readVectorParameter(*pnh_, "initial_pos_list",
109  initial_pos_list);
110  jsk_topic_tools::readVectorParameter(*pnh_, "initial_rot_list",
111  initial_rot_list);
112  jsk_topic_tools::readVectorParameter(*pnh_, "dimensions", dimensions);
114  if (initial_pos_list.size() != 0) {
115  initializePoseList(initial_pos_list.size());
116  for (size_t i = 0; i < initial_pos_list.size(); i++) {
117  if (initial_pos_list[i].size() != 3) {
118  NODELET_FATAL("element of ~initial_pos_list should be [x, y, z]");
119  return;
120  }
121  pose_list_[i].translation() = Eigen::Vector3f(initial_pos_list[i][0],
122  initial_pos_list[i][1],
123  initial_pos_list[i][2]);
124  }
125  }
126  // ~initial_rot_list
127  // -> [[0, 0, 0], ...]
128  if (initial_rot_list.size() != 0) {
129  // error check
130  if (initial_pos_list.size() != 0 &&
131  initial_rot_list.size() != initial_pos_list.size()) {
133  "the size of ~initial_pos_list and ~initial_rot_list are different");
134  return;
135  }
136  if (initial_pos_list.size() == 0) {
137  initializePoseList(initial_rot_list.size());
138  }
139  for (size_t i = 0; i < initial_rot_list.size(); i++) {
140  if (initial_rot_list[i].size() != 3) {
141  NODELET_FATAL("element of ~initial_rot_list should be [rx, ry, rz]");
142  return;
143  }
144  pose_list_[i] = pose_list_[i]
145  * Eigen::AngleAxisf(initial_rot_list[i][0],
146  Eigen::Vector3f::UnitX())
147  * Eigen::AngleAxisf(initial_rot_list[i][1],
148  Eigen::Vector3f::UnitY())
149  * Eigen::AngleAxisf(initial_rot_list[i][2],
150  Eigen::Vector3f::UnitZ());
151  }
152  }
153  // ~dimensions
154  // -> [[x, y, z], [x, y, z] ...]
155  if (dimensions.size() != 0) {
156  // error check
157  if (pose_list_.size() != 0 &&
158  pose_list_.size() != dimensions.size()) {
160  "the size of ~dimensions and ~initial_pos_list or ~initial_rot_list are different");
161  return;
162  }
163  if (pose_list_.size() == 0) {
164  initializePoseList(dimensions.size());
165  }
166  for (size_t i = 0; i < dimensions.size(); i++) {
167  dimensions_.push_back(Eigen::Vector3f(dimensions[i][0],
168  dimensions[i][1],
169  dimensions[i][2]));
170  }
171  }
172 
173  // ~prefixes
174  // -> [left_hand, right_hand ...]
175  if (prefixes_.size() != 0) {
176  // error check
177  if (prefixes_.size() != dimensions.size()) {
179  "the size of ~prefixes and ~dimensions are different");
180  return;
181  }
182  for(int i = 0; i < prefixes_.size(); i++){
183  multiple_pub_indices_.push_back(advertise<PCLIndicesMsg>(*pnh_, prefixes_[i]+std::string("/point_indices"), 1));
184  }
185  }
186 
188  }
189  pub_camera_info_ = advertise<sensor_msgs::CameraInfo>(*pnh_, "output", 1);
191  = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, "output/box_array", 1);
192  pub_mask_ = advertise<sensor_msgs::Image>(*pnh_, "output/mask", 1);
193  pub_indices_ = advertise<PCLIndicesMsg>(*pnh_, "output/point_indices", 1);
194  pub_cluster_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output/cluster_point_indices", 1);
195 
197  }
198 
200  {
201  pose_list_.resize(num);
202  for (size_t i = 0; i < pose_list_.size(); i++) {
203  pose_list_[i].setIdentity();
204  }
205  }
206 
208  {
209  sub_ = pnh_->subscribe("input", 1, &AttentionClipper::clip, this);
210  sub_points_ = pnh_->subscribe("input/points", 1,
213  sub_pose_ = pnh_->subscribe("input/pose",
215  sub_box_ = pnh_->subscribe("input/box",
217  }
218  else {
219  sub_pose_ = pnh_->subscribe("input/pose_array",
221  sub_box_ = pnh_->subscribe("input/box_array",
223  }
224  }
225 
227  {
228  sub_.shutdown();
231  sub_box_.shutdown();
232  }
233 
235  {
236  jsk_recognition_utils::Vertices nonoffsetted_vertices;
237  nonoffsetted_vertices.push_back(
238  Eigen::Vector3f(-dimension[0]/2, -dimension[1]/2, -dimension[2]/2));
239  nonoffsetted_vertices.push_back(
240  Eigen::Vector3f(-dimension[0]/2, -dimension[1]/2, dimension[2]/2));
241  nonoffsetted_vertices.push_back(
242  Eigen::Vector3f(-dimension[0]/2, dimension[1]/2, -dimension[2]/2));
243  nonoffsetted_vertices.push_back(
244  Eigen::Vector3f(-dimension[0]/2, dimension[1]/2, dimension[2]/2));
245  nonoffsetted_vertices.push_back(
246  Eigen::Vector3f(dimension[0]/2, -dimension[1]/2, -dimension[2]/2));
247  nonoffsetted_vertices.push_back(
248  Eigen::Vector3f(dimension[0]/2, -dimension[1]/2, dimension[2]/2));
249  nonoffsetted_vertices.push_back(
250  Eigen::Vector3f(dimension[0]/2, dimension[1]/2, -dimension[2]/2));
251  nonoffsetted_vertices.push_back(
252  Eigen::Vector3f(dimension[0]/2, dimension[1]/2, dimension[2]/2));
253  return nonoffsetted_vertices;
254  }
255 
256  // callback only for one interaction
258  const geometry_msgs::PoseStamped::ConstPtr& pose)
259  {
260  boost::mutex::scoped_lock lock(mutex_);
261  frame_id_list_[0] = pose->header.frame_id;
262  tf::poseMsgToEigen(pose->pose, pose_list_[0]);
263  }
264 
266  const jsk_recognition_msgs::BoundingBox::ConstPtr& box)
267  {
268  boost::mutex::scoped_lock lock(mutex_);
269  dimensions_[0][0] = box->dimensions.x;
270  dimensions_[0][1] = box->dimensions.y;
271  dimensions_[0][2] = box->dimensions.z;
272  frame_id_list_[0] = box->header.frame_id;
273  tf::poseMsgToEigen(box->pose, pose_list_[0]);
274  }
275 
276  // callback for multiple interactions
278  const geometry_msgs::PoseArray::ConstPtr& pose_array)
279  {
280  boost::mutex::scoped_lock lock(mutex_);
281  // resize
282  initializePoseList(pose_array->poses.size());
283  frame_id_list_.resize(pose_array->poses.size());
284  std::fill(frame_id_list_.begin(), frame_id_list_.end(),
285  pose_array->header.frame_id);
286  for (size_t i = 0; i < pose_list_.size(); i++) {
287  tf::poseMsgToEigen(pose_array->poses[i], pose_list_[i]);
288  }
289  }
290 
292  const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& box_array)
293  {
294  boost::mutex::scoped_lock lock(mutex_);
295  initializePoseList(box_array->boxes.size());
296  frame_id_list_.resize(box_array->boxes.size());
297  dimensions_.resize(box_array->boxes.size());
298  for (size_t i = 0; i < pose_list_.size(); i++) {
299  tf::poseMsgToEigen(box_array->boxes[i].pose, pose_list_[i]);
300  frame_id_list_[i] = box_array->boxes[i].header.frame_id;
301  dimensions_[i] = Eigen::Vector3f(box_array->boxes[i].dimensions.x,
302  box_array->boxes[i].dimensions.y,
303  box_array->boxes[i].dimensions.z);
304  }
305  }
306 
308  const std_msgs::Header& header)
309  {
310  jsk_recognition_msgs::BoundingBoxArray box_array;
311  box_array.header.frame_id = header.frame_id;
312  box_array.header.stamp = header.stamp;
313  for (size_t i = 0; i < pose_list_.size(); i++) {
314  jsk_recognition_msgs::BoundingBox box;
315  box.header = header;
318  box_array.boxes.push_back(box);
319  }
320  pub_bounding_box_array_.publish(box_array);
321  }
322 
324  const sensor_msgs::CameraInfo::ConstPtr& msg,
325  std::vector<cv::Point2d>& points,
326  cv::Mat& mask)
327  {
328  double min_u, min_v, max_u, max_v;
329  min_u = msg->width;
330  min_v = msg->height;
331  max_u = max_v = 0;
332  for (size_t i = 0; i < points.size(); i++) {
333  cv::Point2d uv(points[i]);
334  // check limit
335  if (uv.x < 0) {
336  uv.x = 0;
337  }
338  if (uv.y < 0) {
339  uv.y = 0;
340  }
341  if (uv.x > msg->width) {
342  uv.x = msg->width;
343  }
344 
345  if (uv.y > msg->height) {
346  uv.y = msg->height;
347  }
348  if (min_u > uv.x) {
349  min_u = uv.x;
350  }
351  if (max_u < uv.x) {
352  max_u = uv.x;
353  }
354  if (min_v > uv.y) {
355  min_v = uv.y;
356  }
357 
358  if (max_v < uv.y) {
359  max_v = uv.y;
360  }
361  }
362  // now we have min/max of u/v
363  cv::Rect raw_roi(min_u, min_v, (max_u - min_u), (max_v - min_v));
364  cv::Rect original(0, 0, msg->width, msg->height);
365  cv::Rect roi_region = raw_roi & original;
366  sensor_msgs::CameraInfo roi(*msg);
367  roi.roi.x_offset = roi_region.x;
368  roi.roi.y_offset = roi_region.y;
369  roi.roi.width = roi_region.width;
370  roi.roi.height = roi_region.height;
371  roi.roi.do_rectify = true;
373  // mask computation
374  mask = cv::Mat::zeros(msg->height, msg->width, CV_8UC1);
375  cv::Size roi_size(roi_region.width, roi_region.height);
376  cv::Rect roi_rect(cv::Point(roi_region.x, roi_region.y), roi_size);
377  const cv::Scalar white(255);
378  cv::rectangle(mask, roi_rect, white, CV_FILLED);
379  }
380 
382  const sensor_msgs::PointCloud2::ConstPtr& msg)
383  {
384  boost::mutex::scoped_lock lock(mutex_);
385  NODELET_DEBUG("clipPointcloud");
386  vital_checker_->poke();
387  try {
388  // 1. transform pointcloud
389  // 2. crop by boundingbox
390  // 3. publish indices
391  pcl::PointIndices::Ptr all_indices (new pcl::PointIndices);
392  jsk_recognition_msgs::ClusterPointIndices cluster_indices_msg;
393  std::map<std::string, tf::StampedTransform> transforms;
394  transformed_pose_list_.clear();
395  for (size_t i = 0; i < pose_list_.size(); i++) {
396  std::string frame_id = frame_id_list_[i];
397  // check transform cache
398  if (transforms.find(frame_id) == transforms.end()) {
400  /*listener=*/tf_listener_,
401  /*to_frame=*/frame_id, // box origin
402  /*from_frame=*/msg->header.frame_id, // sensor origin
403  /*time=*/msg->header.stamp,
404  /*duration=*/ros::Duration(1.0));
405  transforms[frame_id] = new_transform; // sensor to box
406  }
407  tf::StampedTransform tf_transform = transforms[frame_id];
408  Eigen::Affine3f transform;
409  tf::transformTFToEigen(tf_transform, transform);
410  pcl::PointCloud<pcl::PointXYZ>::Ptr
411  cloud(new pcl::PointCloud<pcl::PointXYZ>);
412  pcl::fromROSMsg(*msg, *cloud);
413 
414  Eigen::Affine3f transformed_box_pose = transform * pose_list_[i];
415  transformed_pose_list_.push_back(transformed_box_pose);
416 
417  pcl::PointIndices::Ptr indices (new pcl::PointIndices);
418  jsk_recognition_msgs::BoundingBox bbox_msg;
419  bbox_msg.header.frame_id = cloud->header.frame_id;
420  tf::poseEigenToMsg(transformed_box_pose, bbox_msg.pose);
421  bbox_msg.dimensions.x = dimensions_[i][0];
422  bbox_msg.dimensions.y = dimensions_[i][1];
423  bbox_msg.dimensions.z = dimensions_[i][2];
424  jsk_recognition_utils::cropPointCloud<pcl::PointXYZ>(cloud, bbox_msg, &(indices->indices));
425 
426  // indices->indices may include NaN and inf points
427  // https://github.com/jsk-ros-pkg/jsk_recognition/issues/888
428  pcl::PointIndices non_nan_indices;
429  for (size_t j = 0; j < indices->indices.size(); j++) {
430  pcl::PointXYZ p = cloud->points[indices->indices[j]];
431  if (pcl_isfinite(p.x) && pcl_isfinite(p.y) && pcl_isfinite(p.z)) {
432  non_nan_indices.indices.push_back(indices->indices[j]);
433  }
434  }
435  PCLIndicesMsg indices_msg;
436  pcl_conversions::fromPCL(non_nan_indices, indices_msg);
437  cluster_indices_msg.cluster_indices.push_back(indices_msg);
438  if(prefixes_.size()){
439  indices_msg.header = msg->header;
440  multiple_pub_indices_[i].publish(indices_msg);
441  }
442 
443  all_indices = jsk_recognition_utils::addIndices(*all_indices, non_nan_indices);
444  }
445  if (negative_) {
446  // Publish indices which is NOT inside of box.
447  pcl::PointIndices::Ptr tmp_indices (new pcl::PointIndices);
448  std::set<int> positive_indices(all_indices->indices.begin(), all_indices->indices.end());
449  for (size_t i = 0; i < msg->width * msg->height; i++) {
450  if (positive_indices.find(i) == positive_indices.end()) {
451  tmp_indices->indices.push_back(i);
452  }
453  }
454  all_indices = tmp_indices;
455  }
456  PCLIndicesMsg indices_msg;
457  pcl_conversions::fromPCL(*all_indices, indices_msg);
458  cluster_indices_msg.header = indices_msg.header = msg->header;
459  pub_indices_.publish(indices_msg);
460  pub_cluster_indices_.publish(cluster_indices_msg);
461  publishBoundingBox(msg->header);
462  }
463  catch (std::runtime_error &e) {
464  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
465  }
466  }
467 
468  void AttentionClipper::clip(const sensor_msgs::CameraInfo::ConstPtr& msg)
469  {
470  boost::mutex::scoped_lock lock(mutex_);
471  vital_checker_->poke();
472  // resolve tf for all interest
473  try {
475  cv::Mat all_mask_image = cv::Mat::zeros(msg->height, msg->width, CV_8UC1);
476  bool model_success_p = model.fromCameraInfo(msg);
477  if (!model_success_p) {
478  ROS_ERROR("failed to create camera model");
479  return;
480  }
481  for (size_t i = 0; i < pose_list_.size(); i++) {
482  std::string frame_id = frame_id_list_[i];
483  tf_listener_->waitForTransform(frame_id,
484  msg->header.frame_id,
485  msg->header.stamp,
486  ros::Duration(1.0));
487  Eigen::Affine3f offset = pose_list_[i];
488  if (tf_listener_->canTransform(msg->header.frame_id,
489  frame_id,
490  msg->header.stamp)) {
491  tf::StampedTransform transform; // header -> frame_id_
492  tf_listener_->lookupTransform(frame_id, msg->header.frame_id,
493  msg->header.stamp, transform);
494  Eigen::Affine3f eigen_transform;
495  tf::transformTFToEigen(transform, eigen_transform);
498  for (size_t i = 0; i < original_vertices.size(); i++) {
499  vertices.push_back(eigen_transform.inverse()
500  * (offset * original_vertices[i]));
501  }
502  std::vector<cv::Point2d> local_points;
503  for (size_t i = 0; i < vertices.size(); i++) {
504  cv::Point3d p(vertices[i][0], vertices[i][1], vertices[i][2]);
505  cv::Point2d uv = model.project3dToPixel(p);
506  local_points.push_back(uv);
507  }
508  cv::Mat mask_image;
509  computeROI(msg, local_points, mask_image);
510  all_mask_image = all_mask_image | mask_image;
511  }
512  }
513  // publish
514  cv_bridge::CvImage mask_bridge(msg->header,
516  all_mask_image);
517  pub_mask_.publish(mask_bridge.toImageMsg());
518  //publishBoundingBox(msg->header);
519  }
520  catch (std::runtime_error &e) {
521  NODELET_ERROR("[%s] Transform error: %s", __PRETTY_FUNCTION__, e.what());
522  }
523  }
524 }
525 
virtual void boxArrayCallback(const jsk_recognition_msgs::BoundingBoxArray::ConstPtr &box)
virtual jsk_recognition_utils::Vertices cubeVertices(Eigen::Vector3f &dimension)
std::vector< Eigen::Affine3f > pose_list_
std::vector< ros::Publisher > multiple_pub_indices_
char * white
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
virtual void poseCallback(const geometry_msgs::PoseStamped::ConstPtr &pose)
void pointFromVectorToXYZ(const FromT &p, ToT &msg)
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
tf::StampedTransform lookupTransformWithDuration(tf::TransformListener *listener, const std::string &to_frame, const std::string &from_frame, const ros::Time &stamp, ros::Duration duration)
virtual void clipPointcloud(const sensor_msgs::PointCloud2::ConstPtr &msg)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void publishBoundingBox(const std_msgs::Header &header)
pose
virtual void boxCallback(const jsk_recognition_msgs::BoundingBox::ConstPtr &box)
bool canTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, std::string *error_msg=NULL) const
virtual void computeROI(const sensor_msgs::CameraInfo::ConstPtr &msg, std::vector< cv::Point2d > &points, cv::Mat &mask)
bool readVectorParameter(ros::NodeHandle &nh, const std::string &param_name, std::vector< double > &result)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
size
virtual void poseArrayCallback(const geometry_msgs::PoseArray::ConstPtr &pose)
std::vector< std::string > frame_id_list_
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
boost::shared_ptr< ros::NodeHandle > pnh_
virtual void initializePoseList(size_t num)
std::vector< int > addIndices(const std::vector< int > &a, const std::vector< int > &b)
tf::TransformListener * tf_listener_
std::vector< Eigen::Affine3f > transformed_pose_list_
jsk_recognition_utils::Vertices dimensions_
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
virtual void clip(const sensor_msgs::CameraInfo::ConstPtr &msg)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::AttentionClipper, nodelet::Nodelet)
p
cv::Point2d project3dToPixel(const cv::Point3d &xyz) const
static tf::TransformListener * getInstance()
#define NODELET_FATAL(...)
pcl::PointIndices PCLIndicesMsg
cloud
std::vector< std::string > prefixes_
#define ROS_ERROR(...)
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const
std_msgs::Header fromPCL(const pcl::PCLHeader &pcl_header)


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