points2_publisher.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020 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 #include <rc_genicam_api/config.h>
38 
39 #include <sensor_msgs/PointCloud2.h>
40 
41 namespace rc
42 {
43 Points2Publisher::Points2Publisher(ros::NodeHandle& nh, const std::string& frame_id, std::function<void()>& sub_changed)
44  : GenICam2RosPublisher(frame_id), left_list(75)
45 {
46  f = 0;
47  t = 0;
48  invalid = -1;
49  scale = 1;
50 
51  sub_callback = sub_changed;
52  pub = nh.advertise<sensor_msgs::PointCloud2>("points2", 1, boost::bind(&GenICam2RosPublisher::subChanged, this, _1),
53  boost::bind(&GenICam2RosPublisher::subChanged, this, _1));
54 }
55 
57 {
58  return pub.getNumSubscribers() > 0;
59 }
60 
61 void Points2Publisher::requiresComponents(int& components, bool& color)
62 {
63  if (pub.getNumSubscribers() > 0)
64  {
65  components |= ComponentIntensity | ComponentDisparity;
66  }
67 }
68 
69 void Points2Publisher::publish(const rcg::Buffer* buffer, uint32_t part, uint64_t pixelformat)
70 {
71  if (nodemap)
72  {
73  if (pub.getNumSubscribers() > 0)
74  {
75  rcg::setEnum(nodemap, "ChunkLineSelector", "Out1", true);
76  std::string out1_mode = rcg::getEnum(nodemap, "ChunkLineSource", true);
77  uint64_t tolerance_ns;
78 
79  if (out1_mode == "ExposureAlternateActive")
80  {
81  tolerance_ns = static_cast<uint64_t>(1.0 * 1000000000ull);
82  }
83  else
84  {
85  tolerance_ns = 0;
86  }
87 
88  bool out1 = rcg::getInteger(nodemap, "ChunkLineStatusAll", 0, 0, true) & 0x1;
89 
90  // buffer left and disparity images
91 
92  if (pixelformat == Mono8 || pixelformat == YCbCr411_8 || pixelformat == RGB8)
93  {
94  // in alternate exposure mode, skip images for texture with out1 == true,
95  // i.e. with projected pattern
96 
97  if (tolerance_ns > 0 && out1)
98  {
99  return;
100  }
101 
102  left_list.add(buffer, part);
103  }
104  else if (pixelformat == Coord3D_C16)
105  {
106  disp_list.add(buffer, part);
107 
108  rcg::setEnum(nodemap, "ChunkComponentSelector", "Disparity", true);
109  f = rcg::getFloat(nodemap, "ChunkScan3dFocalLength", 0, 0, true);
110  t = rcg::getFloat(nodemap, "ChunkScan3dBaseline", 0, 0, true);
111 
112  invalid = -1;
113  if (rcg::getBoolean(nodemap, "ChunkScan3dInvalidDataFlag", false))
114  {
115  invalid = rcg::getFloat(nodemap, "ChunkScan3dInvalidDataValue", 0, 0, true);
116  }
117 
118  scale = rcg::getFloat(nodemap, "ChunkScan3dCoordinateScale", 0, 0, true);
119  }
120 
121  // get corresponding left and disparity image
122 
123  uint64_t timestamp = buffer->getTimestampNS();
124 
125  std::shared_ptr<const rcg::Image> left = left_list.find(timestamp, tolerance_ns);
126  std::shared_ptr<const rcg::Image> disp = disp_list.find(timestamp, tolerance_ns);
127 
128  // print warning with reason if no left image can be found for disparity image
129 
130  if (pixelformat == Coord3D_C16 && !left)
131  {
132  ROS_WARN_STREAM("Cannot find left image for disparity image.");
133  }
134 
135  if (left && disp)
136  {
137  // determine integer factor between size of left and disparity image
138 
139  uint32_t lw = left->getWidth();
140  uint32_t lh = left->getHeight();
141 
142  if (lh > lw) // there may be a stacked right image
143  {
144  lh >>= 1;
145  }
146 
147  int ds = (lw + disp->getWidth() - 1) / disp->getWidth();
148 
149  if ((lw + ds - 1) / ds == disp->getWidth() && (lh + ds - 1) / ds == disp->getHeight())
150  {
151  // allocate new image message and set meta information
152 
153  sensor_msgs::PointCloud2Ptr p = boost::make_shared<sensor_msgs::PointCloud2>();
154 
155  p->header.seq = 0;
156  p->header.stamp.sec = timestamp / 1000000000ul;
157  p->header.stamp.nsec = timestamp % 1000000000ul;
158  p->header.frame_id = frame_id;
159 
160  // set meta data of point cloud
161 
162  p->width = lw / ds; // consider only full pixels if downscaled
163  p->height = lh / ds; // consider only full pixels if downscaled
164 
165  p->is_bigendian = rcg::isHostBigEndian();
166  p->is_dense = false;
167 
168  p->fields.resize(4);
169  p->fields[0].name = "x";
170  p->fields[0].offset = 0;
171  p->fields[0].count = 1;
172  p->fields[0].datatype = sensor_msgs::PointField::FLOAT32;
173  p->fields[1].name = "y";
174  p->fields[1].offset = 4;
175  p->fields[1].count = 1;
176  p->fields[1].datatype = sensor_msgs::PointField::FLOAT32;
177  p->fields[2].name = "z";
178  p->fields[2].offset = 8;
179  p->fields[2].count = 1;
180  p->fields[2].datatype = sensor_msgs::PointField::FLOAT32;
181  p->fields[3].name = "rgb";
182  p->fields[3].offset = 12;
183  p->fields[3].count = 1;
184  p->fields[3].datatype = sensor_msgs::PointField::FLOAT32;
185 
186  p->point_step = 16;
187  p->row_step = p->point_step * p->width;
188 
189  // allocate memory
190 
191  p->data.resize(p->row_step * p->height);
192  float* pd = reinterpret_cast<float*>(&p->data[0]);
193 
194  // pointer to disparity data
195 
196  const uint8_t* dps = disp->getPixels();
197  size_t dstep = disp->getWidth() * sizeof(uint16_t) + disp->getXPadding();
198 
199  // convert disparity to point cloud using left image for texture
200 
201  bool bigendian = disp->isBigEndian();
202 
203  for (uint32_t k = 0; k < p->height; k++)
204  {
205  for (uint32_t i = 0; i < p->width; i++)
206  {
207  // get disparity
208 
209  uint32_t j = i << 1;
210 
211  float d;
212 
213  if (bigendian)
214  {
215  d = scale * ((dps[j] << 8) | dps[j + 1]);
216  }
217  else
218  {
219  d = scale * ((dps[j + 1] << 8) | dps[j]);
220  }
221 
222  // if disparity is valid and color can be obtained
223 
224  if (d > 0 && d != invalid)
225  {
226  // reconstruct 3D point
227 
228  pd[0] = (i + 0.5 - disp->getWidth() / 2.0) * t / d;
229  pd[1] = (k + 0.5 - disp->getHeight() / 2.0) * t / d;
230  pd[2] = f * t / d;
231 
232  // store color of point
233 
234  uint8_t rgb[3];
235  rcg::getColor(rgb, left, ds, i, k);
236 
237  uint8_t* bgra = reinterpret_cast<uint8_t*>(pd + 3);
238 
239  bgra[0] = rgb[2];
240  bgra[1] = rgb[1];
241  bgra[2] = rgb[0];
242  bgra[3] = 0;
243  }
244  else
245  {
246  for (int i = 0; i < 4; i++)
247  {
248  pd[i] = std::numeric_limits<float>::quiet_NaN();
249  }
250  }
251 
252  pd += 4;
253  }
254 
255  dps += dstep;
256  }
257 
258  // publish message
259 
260  pub.publish(p);
261  }
262  else
263  {
264  ROS_ERROR_STREAM("Size of left and disparity image must differ only by an integer factor: "
265  << left->getWidth() << "x" << left->getHeight() << " != " << disp->getWidth() << "x"
266  << disp->getHeight());
267  }
268 
269  // remove all old images, including the current ones
270 
271  left_list.removeOld(timestamp);
272  disp_list.removeOld(timestamp);
273  }
274  }
275  }
276 }
277 
278 } // namespace rc
Interface for all publishers relating to images, point clouds or other stereo-camera data...
d
bool getBoolean(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false, bool igncache=false)
Points2Publisher(ros::NodeHandle &nh, const std::string &frame_id, std::function< void()> &sub_changed)
Mono8
static const int ComponentDisparity
void publish(const rcg::Buffer *buffer, uint32_t part, uint64_t pixelformat) override
Offers a buffer for publication.
std::function< void()> sub_callback
Coord3D_C16
bool used() override
Returns true if there are subscribers to the topic.
rcg::ImageList left_list
int64_t getInteger(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, int64_t *vmin=0, int64_t *vmax=0, bool exception=false, bool igncache=false)
YCbCr411_8
bool setEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, const char *value, bool exception=false)
static const int ComponentIntensity
void subChanged(const ros::SingleSubscriberPublisher &pub)
Called by publisher if subscription changed.
void removeOld(uint64_t timestamp)
void publish(const boost::shared_ptr< M > &message) const
LOG4CPP_EXPORT CategoryStream & left(CategoryStream &os)
std::string getEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception=false)
rcg::ImageList disp_list
RGB8
uint64_t getTimestampNS() const
void add(const std::shared_ptr< const Image > &image)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
double getFloat(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, double *vmin=0, double *vmax=0, bool exception=false, bool igncache=false)
std::shared_ptr< const Image > find(uint64_t timestamp) const
bool isHostBigEndian()
#define ROS_ERROR_STREAM(args)
std::shared_ptr< GenApi::CNodeMapRef > nodemap
uint32_t getNumSubscribers() const
void getColor(uint8_t rgb[3], const std::shared_ptr< const Image > &img, uint32_t ds, uint32_t i, uint32_t k)
void requiresComponents(int &components, bool &color) override
Adds components and if color images are required to the given values.


rc_genicam_driver
Author(s): Heiko Hirschmueller , Felix Ruess
autogenerated on Sun Mar 12 2023 02:20:15