texture_point_cloud.cpp
Go to the documentation of this file.
1 #include <cv_bridge/cv_bridge.h>
3 #include <pcl_ros/point_cloud.h>
4 #include <ros/ros.h>
5 
6 #include <sensor_msgs/Image.h>
7 
8 #include <mutex>
9 #include <string>
10 
11 using PointCloud = pcl::PointCloud<pcl::PointXYZ>;
12 using TexturedPointCloud = pcl::PointCloud<pcl::PointXYZRGB>;
13 
19 TexturedPointCloud::Ptr texturePointCloudFromRectifiedImage(cv::Mat const& image,
20  PointCloud::ConstPtr const& pointCloud)
21 {
22  auto texturedPointCloud = boost::make_shared<TexturedPointCloud>();
23 
24  if (static_cast<int>(pointCloud->width) != image.cols || static_cast<int>(pointCloud->height) != image.rows)
25  {
26  ROS_ERROR("The point cloud does not have the same format as the rectified "
27  "image!");
28  return texturedPointCloud;
29  }
30 
31  texturedPointCloud->header.frame_id = pointCloud->header.frame_id;
32  texturedPointCloud->header.stamp = pointCloud->header.stamp;
33 
34  texturedPointCloud->is_dense = pointCloud->is_dense;
35  texturedPointCloud->width = pointCloud->width;
36  texturedPointCloud->height = pointCloud->height;
37  texturedPointCloud->points.resize(texturedPointCloud->width * texturedPointCloud->height);
38 
39  for (size_t x = 0; x < pointCloud->width; x++)
40  {
41  for (size_t y = 0; y < pointCloud->height; y++)
42  {
43  auto& point = texturedPointCloud->at(x, y);
44 
45  point.x = pointCloud->at(x, y).x;
46  point.y = pointCloud->at(x, y).y;
47  point.z = pointCloud->at(x, y).z;
48 
49  if (image.channels() == 3)
50  {
51  cv::Vec3b color = image.at<cv::Vec3b>(y, x);
52  point.b = color.val[0];
53  point.g = color.val[1];
54  point.r = color.val[2];
55  }
56  else
57  {
58  uchar color = image.at<uchar>(y, x);
59  point.r = color;
60  point.g = color;
61  point.b = color;
62  }
63  }
64  }
65 
66  return texturedPointCloud;
67 }
68 
70 {
71 private:
73 
74  std::mutex mutex;
75 
79 
80  sensor_msgs::ImageConstPtr latestImage;
81  PointCloud::ConstPtr latestPointCloud;
82 
83 public:
85  {
86  image_transport::ImageTransport imageTransport(nodeHandle);
87 
88  imageSubscriber = imageTransport.subscribe("image", 10, &TexturingNode::onImageReceived, this);
89  pointCloudSubscriber = nodeHandle.subscribe("point_cloud", 10, &TexturingNode::onPointCloudReceived, this);
90 
91  texturedPointCloudPublisher = nodeHandle.advertise<TexturedPointCloud>("textured_point_cloud", 1);
92  }
93 
94 private:
95  void onImageReceived(sensor_msgs::ImageConstPtr const& image)
96  {
97  std::lock_guard<std::mutex> lock(mutex);
98 
99  latestImage = image;
100  }
101 
102  void onPointCloudReceived(PointCloud::ConstPtr const& pointCloud)
103  {
104  std::lock_guard<std::mutex> lock(mutex);
105 
106  latestPointCloud = pointCloud;
107  texture();
108  }
109 
110  void texture() const
111  {
112  if (!latestImage.get() || !latestPointCloud.get())
113  return;
114 
116  try
117  {
118  image = cv_bridge::toCvShare(latestImage);
119  }
120  catch (cv_bridge::Exception& e)
121  {
122  ROS_ERROR("cv_bridge exception: %s", e.what());
123  }
124 
125  TexturedPointCloud::Ptr texturedPointCloud;
126  texturedPointCloud = texturePointCloudFromRectifiedImage(image->image, latestPointCloud);
127 
128  texturedPointCloudPublisher.publish(texturedPointCloud);
129  }
130 };
131 
132 int main(int argc, char** argv)
133 {
134  ros::init(argc, argv, "texture_point_cloud");
135 
136  TexturingNode t;
137  ros::spin();
138 
139  return EXIT_SUCCESS;
140 }
sensor_msgs::ImageConstPtr latestImage
PointCloud::ConstPtr latestPointCloud
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
image_transport::Subscriber imageSubscriber
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char **argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
sensor_msgs::PointCloud2 PointCloud
TFSIMD_FORCE_INLINE const tfScalar & y() const
ros::Subscriber pointCloudSubscriber
ROSCPP_DECL void spin(Spinner &spinner)
void onImageReceived(sensor_msgs::ImageConstPtr const &image)
pcl::PointCloud< pcl::PointXYZRGB > TexturedPointCloud
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void onPointCloudReceived(PointCloud::ConstPtr const &pointCloud)
TexturedPointCloud::Ptr texturePointCloudFromRectifiedImage(cv::Mat const &image, PointCloud::ConstPtr const &pointCloud)
ros::NodeHandle nodeHandle
ros::Publisher texturedPointCloudPublisher
void texture() const
#define ROS_ERROR(...)


ensenso_camera
Author(s): Ensenso
autogenerated on Thu May 16 2019 02:44:23