point_cloud_xyz.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 #include <ros/ros.h>
35 #include <nodelet/nodelet.h>
39 #include <boost/thread.hpp>
41 
43 
44 namespace depth_image_proc {
45 
47 
48 class PointCloudXyzNodelet : public nodelet::Nodelet
49 {
50  // Subscriptions
53  int queue_size_;
54 
55  // Publications
56  boost::mutex connect_mutex_;
57  typedef sensor_msgs::PointCloud2 PointCloud;
59 
61 
62  virtual void onInit();
63 
64  void connectCb();
65 
66  void depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
67  const sensor_msgs::CameraInfoConstPtr& info_msg);
68 };
69 
71 {
73  ros::NodeHandle& private_nh = getPrivateNodeHandle();
74  it_.reset(new image_transport::ImageTransport(nh));
75 
76  // Read parameters
77  private_nh.param("queue_size", queue_size_, 5);
78 
79  // Monitor whether anyone is subscribed to the output
81  // Make sure we don't enter connectCb() between advertising and assigning to pub_point_cloud_
82  boost::lock_guard<boost::mutex> lock(connect_mutex_);
83  pub_point_cloud_ = nh.advertise<PointCloud>("points", 1, connect_cb, connect_cb);
84 }
85 
86 // Handles (un)subscribing when clients (un)subscribe
88 {
89  boost::lock_guard<boost::mutex> lock(connect_mutex_);
91  {
93  }
94  else if (!sub_depth_)
95  {
97  sub_depth_ = it_->subscribeCamera("image_rect", queue_size_, &PointCloudXyzNodelet::depthCb, this, hints);
98  }
99 }
100 
101 void PointCloudXyzNodelet::depthCb(const sensor_msgs::ImageConstPtr& depth_msg,
102  const sensor_msgs::CameraInfoConstPtr& info_msg)
103 {
104  PointCloud::Ptr cloud_msg(new PointCloud);
105  cloud_msg->header = depth_msg->header;
106  cloud_msg->height = depth_msg->height;
107  cloud_msg->width = depth_msg->width;
108  cloud_msg->is_dense = false;
109  cloud_msg->is_bigendian = false;
110 
111  sensor_msgs::PointCloud2Modifier pcd_modifier(*cloud_msg);
112  pcd_modifier.setPointCloud2FieldsByString(1, "xyz");
113 
114  // Update camera model
116 
117  if (depth_msg->encoding == enc::TYPE_16UC1 || depth_msg->encoding == enc::MONO16)
118  {
119  convert<uint16_t>(depth_msg, cloud_msg, model_);
120  }
121  else if (depth_msg->encoding == enc::TYPE_32FC1)
122  {
123  convert<float>(depth_msg, cloud_msg, model_);
124  }
125  else
126  {
127  NODELET_ERROR_THROTTLE(5, "Depth image has unsupported encoding [%s]", depth_msg->encoding.c_str());
128  return;
129  }
130 
131  pub_point_cloud_.publish (cloud_msg);
132 }
133 
134 } // namespace depth_image_proc
135 
136 // Register as nodelet
sensor_msgs::image_encodings
point_cloud2_iterator.h
ros::Publisher
nodelet::Nodelet::getNodeHandle
ros::NodeHandle & getNodeHandle() const
image_encodings.h
depth_image_proc::PointCloudXyzNodelet::queue_size_
int queue_size_
Definition: point_cloud_xyz.cpp:117
image_transport::ImageTransport
boost::shared_ptr< image_transport::ImageTransport >
pinhole_camera_model.h
NODELET_ERROR_THROTTLE
#define NODELET_ERROR_THROTTLE(rate,...)
ros.h
depth_image_proc::PointCloudXyzNodelet::pub_point_cloud_
ros::Publisher pub_point_cloud_
Definition: point_cloud_xyz.cpp:122
ros::TransportHints
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(depth_image_proc::PointCloudXyzNodelet, nodelet::Nodelet)
ros::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
nodelet::Nodelet::getPrivateNodeHandle
ros::NodeHandle & getPrivateNodeHandle() const
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
depth_image_proc::PointCloudXyzNodelet::depthCb
void depthCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
Definition: point_cloud_xyz.cpp:133
image_geometry::PinholeCameraModel::fromCameraInfo
bool fromCameraInfo(const sensor_msgs::CameraInfo &msg)
depth_conversions.h
image_transport::CameraSubscriber
depth_image_proc::PointCloudXyzNodelet::onInit
virtual void onInit()
Definition: point_cloud_xyz.cpp:102
image_transport::CameraSubscriber::shutdown
void shutdown()
depth_image_proc::PointCloudXyzNodelet::PointCloud
sensor_msgs::PointCloud2 PointCloud
Definition: point_cloud_xyz.cpp:121
depth_image_proc::PointCloudXyzNodelet
Definition: point_cloud_xyz.cpp:80
depth_image_proc::PointCloudXyzNodelet::model_
image_geometry::PinholeCameraModel model_
Definition: point_cloud_xyz.cpp:124
depth_image_proc
Definition: depth_conversions.h:44
image_transport.h
depth_image_proc::PointCloudXyzNodelet::it_
boost::shared_ptr< image_transport::ImageTransport > it_
Definition: point_cloud_xyz.cpp:115
nodelet::Nodelet
image_geometry::PinholeCameraModel
nodelet.h
sensor_msgs::PointCloud2Modifier
class_list_macros.hpp
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
depth_image_proc::PointCloudXyzNodelet::connect_mutex_
boost::mutex connect_mutex_
Definition: point_cloud_xyz.cpp:120
depth_image_proc::PointCloudXyzNodelet::connectCb
void connectCb()
Definition: point_cloud_xyz.cpp:119
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
image_transport::TransportHints
sensor_msgs::PointCloud2Modifier::setPointCloud2FieldsByString
void setPointCloud2FieldsByString(int n_fields,...)
depth_image_proc::PointCloudXyzNodelet::sub_depth_
image_transport::CameraSubscriber sub_depth_
Definition: point_cloud_xyz.cpp:116
ros::NodeHandle


depth_image_proc
Author(s): Patrick Mihelich
autogenerated on Wed Jan 24 2024 03:57:15