points2_publisher.cc
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Roboception GmbH
3  * All rights reserved
4  *
5  * Author: Heiko Hirschmueller
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * 1. Redistributions of source code must retain the above copyright notice,
11  * this list of conditions and the following disclaimer.
12  *
13  * 2. Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * 3. Neither the name of the copyright holder nor the names of its contributors
18  * may be used to endorse or promote products derived from this software without
19  * specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
25  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
26  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
27  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
28  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
29  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
30  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  */
33 
34 #include "points2_publisher.h"
35 
37 
38 #include <sensor_msgs/PointCloud2.h>
39 
40 namespace rc
41 {
42 Points2Publisher::Points2Publisher(ros::NodeHandle& nh, const std::string& frame_id_prefix, double _f, double _t,
43  double _scale)
44  : GenICam2RosPublisher(frame_id_prefix), left_list(75)
45 {
46  f = _f;
47  t = _t;
48  scale = _scale;
49 
50  tolerance_ns = 0;
51 
52  pub = nh.advertise<sensor_msgs::PointCloud2>("points2", 1);
53 }
54 
56 {
57  if (alternate)
58  {
59  tolerance_ns = static_cast<uint64_t>(0.050 * 1000000000ull);
60  }
61  else
62  {
63  tolerance_ns = 0;
64  }
65 }
66 
68 {
69  return pub.getNumSubscribers() > 0;
70 }
71 
72 void Points2Publisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
73 {
74  publish(buffer, part, pixelformat, false);
75 }
76 
77 void Points2Publisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat, bool out1)
78 {
79  if (pub.getNumSubscribers() > 0)
80  {
81  // buffer left and disparity images
82 
83  if (pixelformat == Mono8 || pixelformat == YCbCr411_8)
84  {
85  // in alternate exposure mode, skip images for texture with out1 == true,
86  // i.e. with projected pattern
87 
88  if (tolerance_ns > 0 && out1)
89  {
90  return;
91  }
92 
93  left_list.add(buffer, part);
94  }
95  else if (pixelformat == Coord3D_C16)
96  {
97  disp_list.add(buffer, part);
98  }
99 
100  // get corresponding left and disparity image
101 
102  uint64_t timestamp = buffer->getTimestampNS();
103 
104  std::shared_ptr<const rcg::Image> left = left_list.find(timestamp, tolerance_ns);
105  std::shared_ptr<const rcg::Image> disp = disp_list.find(timestamp, tolerance_ns);
106 
107  // print warning with reason if no left image can be found for disparity image
108 
109  if (pixelformat == Coord3D_C16 && !left)
110  {
111  if (timestamp < left_list.getOldestTime())
112  {
113  ROS_WARN_STREAM("Cannot find left image for disparity image. Internal queue size to small.");
114  }
115  else
116  {
117  ROS_WARN_STREAM("Cannot find left image for disparity image. Left image possibly dropped.");
118  }
119  }
120 
121  if (left && disp)
122  {
123  // determine integer factor between size of left and disparity image
124 
125  uint32_t lw = left->getWidth();
126  uint32_t lh = left->getHeight();
127 
128  if (lh > lw) // there may be a stacked right image
129  {
130  lh >>= 1;
131  }
132 
133  int ds = (lw + disp->getWidth() - 1) / disp->getWidth();
134 
135  if ((lw + ds - 1) / ds == disp->getWidth() && (lh + ds - 1) / ds == disp->getHeight())
136  {
137  // allocate new image message and set meta information
138 
139  sensor_msgs::PointCloud2Ptr p = boost::make_shared<sensor_msgs::PointCloud2>();
140 
141  const uint64_t freq = 1000000000ul;
142 
143  p->header.seq = seq++;
144  p->header.stamp.sec = timestamp / freq;
145  p->header.stamp.nsec = timestamp - freq * p->header.stamp.sec;
146  p->header.frame_id = frame_id;
147 
148  // set meta data of point cloud
149 
150  p->width = lw / ds; // consider only full pixels if downscaled
151  p->height = lh / ds; // consider only full pixels if downscaled
152 
153  p->is_bigendian = rcg::isHostBigEndian();
154  p->is_dense = false;
155 
156  p->fields.resize(4);
157  p->fields[0].name = "x";
158  p->fields[0].offset = 0;
159  p->fields[0].count = 1;
160  p->fields[0].datatype = sensor_msgs::PointField::FLOAT32;
161  p->fields[1].name = "y";
162  p->fields[1].offset = 4;
163  p->fields[1].count = 1;
164  p->fields[1].datatype = sensor_msgs::PointField::FLOAT32;
165  p->fields[2].name = "z";
166  p->fields[2].offset = 8;
167  p->fields[2].count = 1;
168  p->fields[2].datatype = sensor_msgs::PointField::FLOAT32;
169  p->fields[3].name = "rgb";
170  p->fields[3].offset = 12;
171  p->fields[3].count = 1;
172  p->fields[3].datatype = sensor_msgs::PointField::FLOAT32;
173 
174  p->point_step = 16;
175  p->row_step = p->point_step * p->width;
176 
177  // allocate memory
178 
179  p->data.resize(p->row_step * p->height);
180  float* pd = reinterpret_cast<float*>(&p->data[0]);
181 
182  // pointer to disparity data
183 
184  const uint8_t* dps = disp->getPixels();
185  size_t dstep = disp->getWidth() * sizeof(uint16_t) + disp->getXPadding();
186 
187  // convert disparity to point cloud using left image for texture
188 
189  float ff = f * disp->getWidth();
190 
191  bool bigendian = disp->isBigEndian();
192 
193  for (uint32_t k = 0; k < p->height; k++)
194  {
195  for (uint32_t i = 0; i < p->width; i++)
196  {
197  // get disparity
198 
199  uint32_t j = i << 1;
200 
201  float d;
202 
203  if (bigendian)
204  {
205  d = scale * ((dps[j] << 8) | dps[j + 1]);
206  }
207  else
208  {
209  d = scale * ((dps[j + 1] << 8) | dps[j]);
210  }
211 
212  // if disparity is valid and color can be obtained
213 
214  if (d > 0)
215  {
216  // reconstruct 3D point
217 
218  pd[0] = (i + 0.5 - disp->getWidth() / 2.0) * t / d;
219  pd[1] = (k + 0.5 - disp->getHeight() / 2.0) * t / d;
220  pd[2] = ff * t / d;
221 
222  // store color of point
223 
224  uint8_t rgb[3];
225  rcg::getColor(rgb, left, ds, i, k);
226 
227  uint8_t* bgra = reinterpret_cast<uint8_t*>(pd + 3);
228 
229  bgra[0] = rgb[2];
230  bgra[1] = rgb[1];
231  bgra[2] = rgb[0];
232  bgra[3] = 0;
233  }
234  else
235  {
236  for (int i = 0; i < 4; i++)
237  {
238  pd[i] = std::numeric_limits<float>::quiet_NaN();
239  }
240  }
241 
242  pd += 4;
243  }
244 
245  dps += dstep;
246  }
247 
248  // publish message
249 
250  pub.publish(p);
251  }
252  else
253  {
254  ROS_ERROR_STREAM("Size of left and disparity image must differ only by an integer factor: "
255  << left->getWidth() << "x" << left->getHeight() << " != " << disp->getWidth() << "x"
256  << disp->getHeight());
257  }
258 
259  // remove all old images, including the current ones
260 
261  left_list.removeOld(timestamp);
262  disp_list.removeOld(timestamp);
263  }
264  }
265 }
266 }
Interface for all publishers relating to images, point clouds or other stereo-camera data...
d
void publish(const boost::shared_ptr< M > &message) const
Mono8
std::shared_ptr< const Image > find(uint64_t timestamp) const
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
Coord3D_C16
bool used() override
Returns true if there are subscribers to the topic.
rcg::ImageList left_list
YCbCr411_8
void removeOld(uint64_t timestamp)
LOG4CPP_EXPORT CategoryStream & left(CategoryStream &os)
rcg::ImageList disp_list
void add(const std::shared_ptr< const Image > &image)
void setOut1Alternate(bool alternate)
uint64_t getOldestTime() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
void getColor(uint8_t rgb[3], const std::shared_ptr< const rcg::Image > &img, uint32_t ds, uint32_t i, uint32_t k)
Points2Publisher(ros::NodeHandle &nh, const std::string &frame_id_prefix, double f, double t, double scale)
Initialization of publisher for depth errors.
uint64_t getTimestampNS() const
uint32_t getNumSubscribers() const
bool isHostBigEndian()
#define ROS_ERROR_STREAM(args)


rc_visard_driver
Author(s): Heiko Hirschmueller , Christian Emmerich , Felix Ruess
autogenerated on Sat Feb 13 2021 03:42:55