34 #include <boost/version.hpp> 35 #if ((BOOST_VERSION / 100) % 1000) >= 53 36 #include <boost/thread/lock_guard.hpp> 48 #include <sensor_msgs/PointCloud2.h> 52 #include <opencv2/imgproc/imgproc.hpp> 78 virtual void onInit();
82 void imageCb(
const sensor_msgs::ImageConstPtr& depth_msg,
83 const sensor_msgs::ImageConstPtr& intensity_msg,
84 const sensor_msgs::CameraInfoConstPtr& info_msg);
86 template<
typename T,
typename T2>
87 void convert(
const sensor_msgs::ImageConstPtr& depth_msg,
88 const sensor_msgs::ImageConstPtr& intensity_msg,
89 const PointCloud::Ptr& cloud_msg);
103 private_nh.
param(
"queue_size", queue_size, 5);
112 boost::lock_guard<boost::mutex> lock(connect_mutex_);
119 boost::lock_guard<boost::mutex> lock(connect_mutex_);
120 if (pub_point_cloud_.getNumSubscribers() == 0)
122 sub_depth_.unsubscribe();
123 sub_intensity_ .unsubscribe();
124 sub_info_ .unsubscribe();
126 else if (!sub_depth_.getSubscriber())
130 std::string depth_image_transport_param =
"depth_image_transport";
134 sub_depth_.subscribe(*depth_it_,
"image_rect", 1, depth_hints);
138 sub_intensity_.subscribe(*intensity_it_,
"image_rect", 1, hints);
139 sub_info_.subscribe(*intensity_nh_,
"camera_info", 1);
144 const sensor_msgs::ImageConstPtr& intensity_msg_in,
145 const sensor_msgs::CameraInfoConstPtr& info_msg)
148 if (depth_msg->header.frame_id != intensity_msg_in->header.frame_id)
151 depth_msg->header.frame_id.c_str(), intensity_msg_in->header.frame_id.c_str());
156 model_.fromCameraInfo(info_msg);
159 sensor_msgs::ImageConstPtr intensity_msg = intensity_msg_in;
160 if (depth_msg->width != intensity_msg->width || depth_msg->height != intensity_msg->height)
162 sensor_msgs::CameraInfo info_msg_tmp = *info_msg;
163 info_msg_tmp.width = depth_msg->width;
164 info_msg_tmp.height = depth_msg->height;
165 float ratio = float(depth_msg->width)/float(intensity_msg->width);
166 info_msg_tmp.K[0] *= ratio;
167 info_msg_tmp.K[2] *= ratio;
168 info_msg_tmp.K[4] *= ratio;
169 info_msg_tmp.K[5] *= ratio;
170 info_msg_tmp.P[0] *= ratio;
171 info_msg_tmp.P[2] *= ratio;
172 info_msg_tmp.P[5] *= ratio;
173 info_msg_tmp.P[6] *= ratio;
174 model_.fromCameraInfo(info_msg_tmp);
183 ROS_ERROR(
"cv_bridge exception: %s", e.what());
187 cv_rsz.
header = cv_ptr->header;
189 cv::resize(cv_ptr->image.rowRange(0,depth_msg->height/ratio), cv_rsz.
image, cv::Size(depth_msg->width, depth_msg->height));
190 if ((intensity_msg->encoding == enc::MONO8) || (intensity_msg->encoding == enc::MONO16))
199 intensity_msg = intensity_msg_in;
202 if (intensity_msg->encoding != enc::MONO8 || intensity_msg->encoding != enc::MONO16)
217 cloud_msg->header = depth_msg->header;
218 cloud_msg->height = depth_msg->height;
219 cloud_msg->width = depth_msg->width;
220 cloud_msg->is_dense =
false;
221 cloud_msg->is_bigendian =
false;
226 "x", 1, sensor_msgs::PointField::FLOAT32,
227 "y", 1, sensor_msgs::PointField::FLOAT32,
228 "z", 1, sensor_msgs::PointField::FLOAT32,
229 "intensity", 1, sensor_msgs::PointField::FLOAT32);
232 if (depth_msg->encoding == enc::TYPE_16UC1 &&
233 intensity_msg->encoding == enc::MONO8)
235 convert<uint16_t, uint8_t>(depth_msg, intensity_msg, cloud_msg);
237 else if (depth_msg->encoding == enc::TYPE_16UC1 &&
238 intensity_msg->encoding == enc::MONO16)
240 convert<uint16_t, uint16_t>(depth_msg, intensity_msg, cloud_msg);
242 else if (depth_msg->encoding == enc::TYPE_32FC1 &&
243 intensity_msg->encoding == enc::MONO8)
245 convert<float, uint8_t>(depth_msg, intensity_msg, cloud_msg);
247 else if (depth_msg->encoding == enc::TYPE_32FC1 &&
248 intensity_msg->encoding == enc::MONO16)
250 convert<float, uint16_t>(depth_msg, intensity_msg, cloud_msg);
258 pub_point_cloud_.publish (cloud_msg);
261 template<
typename T,
typename T2>
263 const sensor_msgs::ImageConstPtr& intensity_msg,
264 const PointCloud::Ptr& cloud_msg)
267 float center_x = model_.cx();
268 float center_y = model_.cy();
272 float constant_x = unit_scaling / model_.fx();
273 float constant_y = unit_scaling / model_.fy();
274 float bad_point = std::numeric_limits<float>::quiet_NaN ();
276 const T* depth_row =
reinterpret_cast<const T*
>(&depth_msg->data[0]);
277 int row_step = depth_msg->step /
sizeof(T);
279 const T2* inten_row =
reinterpret_cast<const T2*
>(&intensity_msg->data[0]);
280 int inten_row_step = intensity_msg->step /
sizeof(T2);
287 for (
int v = 0; v < int(cloud_msg->height); ++v, depth_row += row_step, inten_row += inten_row_step)
289 for (
int u = 0; u < int(cloud_msg->width); ++u, ++iter_x, ++iter_y, ++iter_z, ++iter_i)
291 T depth = depth_row[u];
292 T2 inten = inten_row[u];
296 *iter_x = *iter_y = *iter_z = bad_point;
301 *iter_x = (u - center_x) * depth * constant_x;
302 *iter_y = (v - center_y) * depth * constant_y;
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void convert(const sensor_msgs::ImageConstPtr &depth_msg, PointCloud::Ptr &cloud_msg, const image_geometry::PinholeCameraModel &model, double range_max=0.0)
PLUGINLIB_EXPORT_CLASS(depth_image_proc::PointCloudXyziNodelet, nodelet::Nodelet)
ros::Publisher pub_point_cloud_
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
void imageCb(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &intensity_msg, const sensor_msgs::CameraInfoConstPtr &info_msg)
boost::shared_ptr< image_transport::ImageTransport > intensity_it_
#define NODELET_ERROR_THROTTLE(rate,...)
ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo > SyncPolicy
void setPointCloud2Fields(int n_fields,...)
boost::shared_ptr< Synchronizer > sync_
boost::mutex connect_mutex_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
image_geometry::PinholeCameraModel model_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void convert(const sensor_msgs::ImageConstPtr &depth_msg, const sensor_msgs::ImageConstPtr &intensity_msg, const PointCloud::Ptr &cloud_msg)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
sensor_msgs::PointCloud2 PointCloud
message_filters::Synchronizer< SyncPolicy > Synchronizer
image_transport::SubscriberFilter sub_intensity_
sensor_msgs::ImagePtr toImageMsg() const
ros::NodeHandlePtr intensity_nh_