depth_image_creator_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/or 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 
36 #include <cv_bridge/cv_bridge.h>
38 #include <jsk_topic_tools/rosparam_utils.h>
41 
43 
45  NODELET_INFO("[%s::onInit]", getName().c_str());
46  ConnectionBasedNodelet::onInit();
48  // scale_depth
49  pnh_->param("scale_depth", scale_depth, 1.0);
50  ROS_INFO("scale_depth : %f", scale_depth);
51 
52  // use fixed transform
53  pnh_->param("use_fixed_transform", use_fixed_transform, false);
54  ROS_INFO("use_fixed_transform : %d", use_fixed_transform);
55 
56  pnh_->param("use_service", use_service, false);
57  ROS_INFO("use_service : %d", use_service);
58 
59  pnh_->param("use_asynchronous", use_asynchronous, false);
60  ROS_INFO("use_asynchronous : %d", use_asynchronous);
61 
62  pnh_->param("use_approximate", use_approximate, false);
63  ROS_INFO("use_approximate : %d", use_approximate);
64 
65  pnh_->param("fill_value", fill_value, std::numeric_limits<float>::quiet_NaN());
66  ROS_INFO("fill_value : %f", fill_value);
67  pnh_->param("organize_cloud", organize_cloud_, false);
68  ROS_INFO("organize_cloud : %d", organize_cloud_);
69 
70  pnh_->param("info_throttle", info_throttle_, 0);
71  ROS_INFO("info_throttle : %d", info_throttle_);
72  info_counter_ = 0;
73  pnh_->param("max_queue_size", max_queue_size_, 100);
74  ROS_INFO("max_queue_size : %d", max_queue_size_);
75  // maybe below queue_size can always be 1,
76  // but we set max_queue_size_ for backward compatibility.
77  pnh_->param("max_pub_queue_size", max_pub_queue_size_, max_queue_size_);
78  pnh_->param("max_sub_queue_size", max_sub_queue_size_, max_queue_size_);
79  // set transformation
80  std::vector<double> trans_pos(3, 0);
81  std::vector<double> trans_quat(4, 0); trans_quat[3] = 1.0;
82  if (pnh_->hasParam("translation")) {
83  jsk_topic_tools::readVectorParameter(*pnh_, "translation", trans_pos);
84  }
85  ROS_INFO("translation : %f %f %f", trans_pos[0], trans_pos[1], trans_pos[2]);
86  if (pnh_->hasParam("rotation")) {
87  jsk_topic_tools::readVectorParameter(*pnh_, "rotation", trans_quat);
88  }
89  ROS_INFO("rotation : %f %f %f %f", trans_quat[0], trans_quat[1], trans_quat[2], trans_quat[3]);
90  tf::Quaternion btq(trans_quat[0], trans_quat[1], trans_quat[2], trans_quat[3]);
91  tf::Vector3 btp(trans_pos[0], trans_pos[1], trans_pos[2]);
94  pnh_->param("tf_duration", tf_duration_, 0.001);
95  ROS_INFO("tf_duration : %f", tf_duration_);
96 
97  pub_depth_ = advertise<sensor_msgs::Image> (*pnh_, "output", max_pub_queue_size_);
98  pub_image_ = advertise<sensor_msgs::Image> (*pnh_, "output_image", max_pub_queue_size_);
99  pub_cloud_ = advertise<PointCloud>(*pnh_, "output_cloud", max_pub_queue_size_);
100  pub_disp_image_ = advertise<stereo_msgs::DisparityImage> (*pnh_, "output_disp", max_pub_queue_size_);
101 
102  if (use_service) {
103  service_ = pnh_->advertiseService("set_point_cloud",
105  }
106  onInitPostProcess();
107 }
108 
110  // message_filters::Synchronizer needs to be called reset
111  // before message_filters::Subscriber is freed.
112  // Calling reset fixes the following error on shutdown of the nodelet:
113  // terminate called after throwing an instance of
114  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
115  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
116  // Also see https://github.com/ros/ros_comm/issues/720 .
117  sync_inputs_e_.reset();
118  sync_inputs_a_.reset();
119 }
120 
122  if (!use_service) {
123  if (use_asynchronous) {
124  sub_as_info_ = pnh_->subscribe<sensor_msgs::CameraInfo> ("info", max_sub_queue_size_,
126  sub_as_cloud_ = pnh_->subscribe<sensor_msgs::PointCloud2> ("input", max_sub_queue_size_,
128  } else {
129  sub_info_.subscribe(*pnh_, "info", max_sub_queue_size_);
130  sub_cloud_.subscribe(*pnh_, "input", max_sub_queue_size_);
131 
132  if (use_approximate) {
133  sync_inputs_a_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> > > (max_queue_size_);
134  sync_inputs_a_->connectInput (sub_info_, sub_cloud_);
135  sync_inputs_a_->registerCallback (bind (&DepthImageCreator::callback_sync, this, _1, _2));
136  } else {
137  sync_inputs_e_ = boost::make_shared <message_filters::Synchronizer<message_filters::sync_policies::ExactTime<sensor_msgs::CameraInfo, sensor_msgs::PointCloud2> > > (max_queue_size_);
138  sync_inputs_e_->connectInput (sub_info_, sub_cloud_);
139  sync_inputs_e_->registerCallback (bind (&DepthImageCreator::callback_sync, this, _1, _2));
140  }
141  }
142  } else {
143  // not continuous
144  sub_as_info_ = pnh_->subscribe<sensor_msgs::CameraInfo> ("info", max_sub_queue_size_,
146 
147  }
148 }
149 
151  if (!use_service) {
152  if (use_asynchronous) {
153  sub_as_info_.shutdown();
154  sub_as_cloud_.shutdown();
155  }
156  else {
157  sub_info_.unsubscribe();
158  sub_cloud_.unsubscribe();
159  }
160  } else {
161  // not continuous
162  sub_as_info_.shutdown();
163  }
164 }
165 
166 bool jsk_pcl_ros::DepthImageCreator::service_cb (std_srvs::Empty::Request &req,
167  std_srvs::Empty::Response &res) {
168  return true;
169 }
170 
171 void jsk_pcl_ros::DepthImageCreator::callback_sync(const sensor_msgs::CameraInfoConstPtr& info,
172  const sensor_msgs::PointCloud2ConstPtr& pcloud2) {
173  ROS_DEBUG("DepthImageCreator::callback_sync");
174  publish_points(info, pcloud2);
175 }
176 
177 void jsk_pcl_ros::DepthImageCreator::callback_cloud(const sensor_msgs::PointCloud2ConstPtr& pcloud2) {
178  ROS_DEBUG("DepthImageCreator::callback_cloud");
179  boost::mutex::scoped_lock lock(this->mutex_points);
180  points_ptr_ = pcloud2;
181 }
182 
183 void jsk_pcl_ros::DepthImageCreator::callback_info(const sensor_msgs::CameraInfoConstPtr& info) {
184  ROS_DEBUG("DepthImageCreator::callback_info");
185  boost::mutex::scoped_lock lock(this->mutex_points);
186  if( info_counter_++ >= info_throttle_ ) {
187  info_counter_ = 0;
188  } else {
189  return;
190  }
191  if (points_ptr_) {
192  publish_points(info, points_ptr_);
193  }
194 }
195 
196 void jsk_pcl_ros::DepthImageCreator::publish_points(const sensor_msgs::CameraInfoConstPtr& info,
197  const sensor_msgs::PointCloud2ConstPtr& pcloud2) {
198  sensor_msgs::PointCloud2Ptr pcloud2_ptr(new sensor_msgs::PointCloud2(*pcloud2));
199  if (!jsk_recognition_utils::hasField("rgb", *pcloud2_ptr)) {
200  sensor_msgs::PointCloud2Modifier pc_mod(*pcloud2_ptr);
201  pc_mod.setPointCloud2Fields(4, "x", 1, sensor_msgs::PointField::FLOAT32,
202  "y", 1, sensor_msgs::PointField::FLOAT32,
203  "z", 1, sensor_msgs::PointField::FLOAT32,
204  "rgb", 1, sensor_msgs::PointField::FLOAT32);
205  }
206 
207  ROS_DEBUG("DepthImageCreator::publish_points");
208  if (!pcloud2_ptr) return;
209  bool proc_cloud = true, proc_depth = true, proc_image = true, proc_disp = true;
210  if ( pub_cloud_.getNumSubscribers()==0 ) {
211  proc_cloud = false;
212  }
213  if ( pub_depth_.getNumSubscribers()==0 ) {
214  proc_depth = false;
215  }
216  if ( pub_image_.getNumSubscribers()==0 ) {
217  proc_image = false;
218  }
219  if ( pub_disp_image_.getNumSubscribers()==0 ) {
220  proc_disp = false;
221  }
222  if( !proc_cloud && !proc_depth && !proc_image && !proc_disp) return;
223 
224  int width = info->width;
225  int height = info->height;
226  float fx = info->P[0];
227  float cx = info->P[2];
228  float tx = info->P[3];
229  float fy = info->P[5];
230  float cy = info->P[6];
231 
232  Eigen::Affine3f sensorPose;
233  {
235  if(use_fixed_transform) {
236  transform = fixed_transform;
237  } else {
238  try {
239  tf_listener_->waitForTransform(pcloud2_ptr->header.frame_id,
240  info->header.frame_id,
241  info->header.stamp,
242  ros::Duration(tf_duration_));
243  tf_listener_->lookupTransform(pcloud2_ptr->header.frame_id,
244  info->header.frame_id,
245  info->header.stamp, transform);
246  }
247  catch ( std::runtime_error e ) {
248  ROS_ERROR("%s",e.what());
249  return;
250  }
251  }
252  tf::Vector3 p = transform.getOrigin();
253  tf::Quaternion q = transform.getRotation();
254  sensorPose = (Eigen::Affine3f)Eigen::Translation3f(p.getX(), p.getY(), p.getZ());
255  Eigen::Quaternion<float> rot(q.getW(), q.getX(), q.getY(), q.getZ());
256  sensorPose = sensorPose * rot;
257 
258  if (tx != 0.0) {
259  Eigen::Affine3f trans = (Eigen::Affine3f)Eigen::Translation3f(-tx/fx , 0, 0);
260  sensorPose = sensorPose * trans;
261  }
262 #if 0 // debug print
263  ROS_INFO("%f %f %f %f %f %f %f %f %f, %f %f %f",
264  sensorPose(0,0), sensorPose(0,1), sensorPose(0,2),
265  sensorPose(1,0), sensorPose(1,1), sensorPose(1,2),
266  sensorPose(2,0), sensorPose(2,1), sensorPose(2,2),
267  sensorPose(0,3), sensorPose(1,3), sensorPose(2,3));
268 #endif
269  }
270 
271  PointCloud pointCloud;
272  pcl::RangeImagePlanar rangeImageP;
273  {
274  // code here is dirty, some bag is in RangeImagePlanar
275  PointCloud tpc;
276  pcl::fromROSMsg(*pcloud2_ptr, tpc);
277 
278  Eigen::Affine3f inv;
279 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 5 )
280  inv = sensorPose.inverse();
281  pcl::transformPointCloud< Point > (tpc, pointCloud, inv);
282 #else
283  pcl::getInverse(sensorPose, inv);
284  pcl::getTransformedPointCloud<PointCloud> (tpc, inv, pointCloud);
285 #endif
286 
287  Eigen::Affine3f dummytrans;
288  dummytrans.setIdentity();
289  rangeImageP.createFromPointCloudWithFixedSize (pointCloud,
290  width/scale_depth, height/scale_depth,
291  cx/scale_depth, cy/scale_depth,
292  fx/scale_depth, fy/scale_depth,
293  dummytrans); //sensorPose);
294  }
295 
296  // Create color and depth image from point cloud
297  cv::Mat color_mat = cv::Mat::zeros(rangeImageP.height, rangeImageP.width, CV_8UC3);
298  cv::Mat depth_mat(rangeImageP.height, rangeImageP.width, CV_32FC1);
299  depth_mat.setTo(fill_value);
300  for (size_t i=0; i<pointCloud.size(); i++) {
301  Point pt = pointCloud[i];
302 
303  int image_x;
304  int image_y;
305  rangeImageP.getImagePoint(pt.x, pt.y, pt.z, image_x, image_y);
306 
307  if (!rangeImageP.isInImage(image_x, image_y)) {
308  continue;
309  }
310 
311  pcl::PointWithRange pt_with_range = rangeImageP.getPoint(image_x, image_y);
312  depth_mat.at<float>(image_y, image_x) = pt_with_range.z;
313 
314  if (!std::isnan(pt.x) && !std::isnan(pt.y) && !std::isnan(pt.z)) {
315  color_mat.at<cv::Vec3b>(image_y, image_x) = cv::Vec3b(pt.r, pt.g, pt.b);
316  }
317  }
318 
319  if (scale_depth != 1.0) {
320  // LINEAR
321  cv::resize(color_mat, color_mat, cv::Size(info->width, info->height));
322  cv::resize(depth_mat, depth_mat, cv::Size(info->width, info->height));
323  }
324 
325  if (proc_image) {
326  pub_image_.publish(cv_bridge::CvImage(info->header,
328  color_mat).toImageMsg());
329  }
330  if (proc_depth) {
331  pub_depth_.publish(cv_bridge::CvImage(info->header,
333  depth_mat).toImageMsg());
334  }
335 
336  if(proc_cloud || proc_disp) {
337  // publish point cloud
338  pcl::RangeImagePlanar rangeImagePP;
339  rangeImagePP.setDepthImage ((float *)depth_mat.ptr(),
340  width, height,
341  cx, cy, fx, fy);
342 #if PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION >= 7
343  rangeImagePP.header = pcl_conversions::toPCL(info->header);
344 #else
345  rangeImagePP.header = info->header;
346 #endif
347  if (proc_cloud) {
348  PointCloud cloud_out;
349  cloud_out.header = rangeImagePP.header;
350  if (organize_cloud_) {
351  cloud_out.width = rangeImagePP.width;
352  cloud_out.height = rangeImagePP.height;
353  } else {
354  cloud_out.width = rangeImagePP.width * rangeImagePP.height;
355  cloud_out.height = 1;
356  }
357  cloud_out.resize(cloud_out.width * cloud_out.height);
358  cloud_out.is_dense = true;
359  for (int y = 0; y < (int)rangeImagePP.height; y++ ) {
360  for (int x = 0; x < (int)rangeImagePP.width; x++ ) {
361  pcl::PointWithRange pt_from = rangeImagePP.points[rangeImagePP.width * y + x];
362  cv::Vec3b rgb = color_mat.at<cv::Vec3b>(y, x);
363  Point pt_to;
364  pt_to.x = pt_from.x;
365  pt_to.y = pt_from.y;
366  pt_to.z = pt_from.z;
367  pt_to.r = rgb[0];
368  pt_to.g = rgb[1];
369  pt_to.b = rgb[2];
370  cloud_out.points[rangeImagePP.width * y + x] = pt_to;
371  if (std::isnan(pt_to.x) || std::isnan(pt_to.y) || std::isnan(pt_to.z)) {
372  cloud_out.is_dense = false;
373  }
374  }
375  }
376  pub_cloud_.publish(boost::make_shared<PointCloud>(cloud_out));
377  }
378 
379  if(proc_disp) {
380  stereo_msgs::DisparityImage disp;
381 #if PCL_MAJOR_VERSION == 1 && PCL_MINOR_VERSION >= 7
382  disp.header = pcl_conversions::fromPCL(rangeImagePP.header);
383 #else
384  disp.header = rangeImagePP.header;
385 #endif
386  disp.image.encoding = sensor_msgs::image_encodings::TYPE_32FC1;
387  disp.image.height = rangeImagePP.height;
388  disp.image.width = rangeImagePP.width;
389  disp.image.step = disp.image.width * sizeof(float);
390  disp.f = fx; disp.T = 0.075;
391  disp.min_disparity = 0;
392  disp.max_disparity = disp.T * disp.f / 0.3;
393  disp.delta_d = 0.125;
394 
395  disp.image.data.resize (disp.image.height * disp.image.step);
396  float *data = reinterpret_cast<float*> (&disp.image.data[0]);
397 
398  float normalization_factor = disp.f * disp.T;
399  for (int y = 0; y < (int)rangeImagePP.height; y++ ) {
400  for (int x = 0; x < (int)rangeImagePP.width; x++ ) {
401  pcl::PointWithRange p = rangeImagePP.getPoint(x,y);
402  data[y*disp.image.width+x] = normalization_factor / p.z;
403  }
404  }
405  pub_disp_image_.publish(boost::make_shared<stereo_msgs::DisparityImage> (disp));
406  }
407  }
408 } // namespace jsk_pcl_ros
409 
rot
rot
jsk_pcl_ros::DepthImageCreator::subscribe
void subscribe()
Definition: depth_image_creator_nodelet.cpp:121
if
if(n==1)
jsk_pcl_ros::DepthImageCreator::callback_cloud
void callback_cloud(const sensor_msgs::PointCloud2ConstPtr &pcloud2)
Definition: depth_image_creator_nodelet.cpp:177
jsk_pcl_ros::DepthImageCreator::pub_cloud_
ros::Publisher pub_cloud_
Definition: depth_image_creator.h:141
point_cloud2_iterator.h
jsk_pcl_ros::DepthImageCreator::callback_sync
void callback_sync(const sensor_msgs::CameraInfoConstPtr &info, const sensor_msgs::PointCloud2ConstPtr &pcloud2)
Definition: depth_image_creator_nodelet.cpp:171
depth_error_calibration.lock
lock
Definition: depth_error_calibration.py:32
_2
boost::arg< 2 > _2
image_encodings.h
jsk_pcl_ros::DepthImageCreator::fixed_transform
tf::StampedTransform fixed_transform
Definition: depth_image_creator.h:160
i
int i
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
p
p
pcl_ros_util.h
jsk_pcl_ros::DepthImageCreator::organize_cloud_
bool organize_cloud_
Definition: depth_image_creator.h:154
getName
ROSCONSOLE_CONSOLE_IMPL_DECL std::string getName(void *handle)
pcl_conversions::toPCL
void toPCL(const pcl_msgs::ModelCoefficients &mc, pcl::ModelCoefficients &pcl_mc)
rgb
rgb
depth_image_creator.h
ROS_DEBUG
#define ROS_DEBUG(...)
jsk_pcl_ros::DepthImageCreator::use_fixed_transform
bool use_fixed_transform
Definition: depth_image_creator.h:150
jsk_pcl_ros::DepthImageCreator::publish_points
void publish_points(const sensor_msgs::CameraInfoConstPtr &info, const sensor_msgs::PointCloud2ConstPtr &pcloud2)
Definition: depth_image_creator_nodelet.cpp:196
attention_pose_set.x
x
Definition: attention_pose_set.py:18
transform
template Halfspace< double > transform(const Halfspace< double > &a, const Transform3< double > &tf)
sensor_msgs::image_encodings::RGB8
const std::string RGB8
tf::StampedTransform
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
jsk_pcl_ros::DepthImageCreator::pub_disp_image_
ros::Publisher pub_disp_image_
Definition: depth_image_creator.h:142
sensor_msgs::PointCloud2Modifier::setPointCloud2Fields
void setPointCloud2Fields(int n_fields,...)
jsk_pcl_ros::DepthImageCreator::onInit
void onInit()
Definition: depth_image_creator_nodelet.cpp:44
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::DepthImageCreator, nodelet::Nodelet)
jsk_pcl_ros::DepthImageCreator::use_approximate
bool use_approximate
Definition: depth_image_creator.h:153
class_list_macros.h
jsk_pcl_ros::DepthImageCreator::service_
ros::ServiceServer service_
Definition: depth_image_creator.h:143
jsk_recognition_utils::hasField
bool hasField(const std::string &field_name, const sensor_msgs::PointCloud2 &msg)
pcl_conversions::fromPCL
void fromPCL(const pcl::ModelCoefficients &pcl_mc, pcl_msgs::ModelCoefficients &mc)
tf::Transform::setRotation
TFSIMD_FORCE_INLINE void setRotation(const Quaternion &q)
jsk_pcl_ros::DepthImageCreator::pub_image_
ros::Publisher pub_image_
Definition: depth_image_creator.h:140
q
q
jsk_pcl_ros::DepthImageCreator
Definition: depth_image_creator.h:100
dump_depth_error.data
data
Definition: dump_depth_error.py:11
ROS_ERROR
#define ROS_ERROR(...)
_1
boost::arg< 1 > _1
jsk_pcl_ros::DepthImageCreator::Point
pcl::PointXYZRGB Point
Definition: depth_image_creator.h:165
jsk_pcl_ros::DepthImageCreator::max_queue_size_
int max_queue_size_
Definition: depth_image_creator.h:157
info
info
jsk_pcl_ros::DepthImageCreator::service_cb
bool service_cb(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: depth_image_creator_nodelet.cpp:166
tf::Transform::setOrigin
TFSIMD_FORCE_INLINE void setOrigin(const Vector3 &origin)
jsk_pcl_ros::DepthImageCreator::tf_duration_
double tf_duration_
Definition: depth_image_creator.h:163
jsk_pcl_ros::DepthImageCreator::info_counter_
int info_counter_
Definition: depth_image_creator.h:156
jsk_pcl_ros::DepthImageCreator::info_throttle_
int info_throttle_
Definition: depth_image_creator.h:155
NODELET_INFO
#define NODELET_INFO(...)
jsk_pcl_ros::DepthImageCreator::~DepthImageCreator
virtual ~DepthImageCreator()
Definition: depth_image_creator_nodelet.cpp:109
nodelet::Nodelet
width
width
sensor_msgs::image_encodings::TYPE_32FC1
const std::string TYPE_32FC1
sensor_msgs::PointCloud2Modifier
jsk_pcl_ros::DepthImageCreator::callback_info
void callback_info(const sensor_msgs::CameraInfoConstPtr &info)
Definition: depth_image_creator_nodelet.cpp:183
jsk_pcl_ros::DepthImageCreator::PointCloud
pcl::PointCloud< Point > PointCloud
Definition: depth_image_creator.h:166
cv_bridge.h
cv_bridge::CvImage
jsk_pcl_ros::DepthImageCreator::fill_value
float fill_value
Definition: depth_image_creator.h:164
jsk_pcl_ros::DepthImageCreator::use_asynchronous
bool use_asynchronous
Definition: depth_image_creator.h:152
jsk_pcl_ros::DepthImageCreator::pub_depth_
ros::Publisher pub_depth_
Definition: depth_image_creator.h:139
jsk_recognition_utils::TfListenerSingleton::getInstance
static tf::TransformListener * getInstance()
jsk_pcl_ros::DepthImageCreator::max_pub_queue_size_
int max_pub_queue_size_
Definition: depth_image_creator.h:158
attention_pose_set.y
y
Definition: attention_pose_set.py:19
height
height
ROS_INFO
#define ROS_INFO(...)
jsk_pcl_ros::DepthImageCreator::unsubscribe
void unsubscribe()
Definition: depth_image_creator_nodelet.cpp:150
jsk_pcl_ros::DepthImageCreator::scale_depth
double scale_depth
Definition: depth_image_creator.h:162
ros::Duration
tf::Quaternion
jsk_pcl_ros::DepthImageCreator::use_service
bool use_service
Definition: depth_image_creator.h:151
sample_pointcloud_localization_client.req
req
Definition: sample_pointcloud_localization_client.py:15
jsk_pcl_ros::DepthImageCreator::max_sub_queue_size_
int max_sub_queue_size_
Definition: depth_image_creator.h:159
sample_empty_service_caller.res
res
Definition: sample_empty_service_caller.py:14
jsk_pcl_ros::DepthImageCreator::tf_listener_
tf::TransformListener * tf_listener_
Definition: depth_image_creator.h:161


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44