gc_pointcloud.cc
Go to the documentation of this file.
1 /*
2  * This file is part of the rc_genicam_api package.
3  *
4  * Copyright (c) 2017 Roboception GmbH
5  * All rights reserved
6  *
7  * Author: Heiko Hirschmueller
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions are met:
11  *
12  * 1. Redistributions of source code must retain the above copyright notice,
13  * this list of conditions and the following disclaimer.
14  *
15  * 2. Redistributions in binary form must reproduce the above copyright notice,
16  * this list of conditions and the following disclaimer in the documentation
17  * and/or other materials provided with the distribution.
18  *
19  * 3. Neither the name of the copyright holder nor the names of its contributors
20  * may be used to endorse or promote products derived from this software without
21  * specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
24  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
25  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
26  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
27  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
28  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
29  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
30  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
31  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
32  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  */
35 
36 #include <rc_genicam_api/system.h>
38 #include <rc_genicam_api/device.h>
39 #include <rc_genicam_api/stream.h>
40 #include <rc_genicam_api/buffer.h>
41 #include <rc_genicam_api/image.h>
44 #include <rc_genicam_api/config.h>
45 
47 
48 #include <Base/GCException.h>
49 
50 namespace
51 {
52 
53 /*
54  Print help text on standard output.
55 */
56 
57 void printHelp(const char *prgname)
58 {
59  // show help
60 
61  std::cout << prgname << " -h | [-o <output-filename>] [<interface-id>:]<device-id>" << std::endl;
62  std::cout << std::endl;
63  std::cout << "Gets the first synchronized image set of the Roboception rc_visard, consisting of left, disparity, confidence and error image, creates a point cloud and stores it in ply ascii format." << std::endl;
64  std::cout << std::endl;
65  std::cout << "Options:" << std::endl;
66  std::cout << "-h Prints help information and exits" << std::endl;
67  std::cout << "-o <file> Set name of output file (default is 'rc_visard_<timestamp>.ply')" << std::endl;
68  std::cout << std::endl;
69  std::cout << "Parameters:" << std::endl;
70  std::cout << "<interface-id> Optional GenICam ID of interface for connecting to the device" << std::endl;
71  std::cout << "<device-id> GenICam device ID, serial number or user defined name of device" << std::endl;
72 }
73 
74 }
75 
76 int main(int argc, char *argv[])
77 {
78  int ret=0;
79 
80  try
81  {
82  // optional parameters
83 
84  std::string name="";
85 
86  int i=1;
87 
88  while (i+1 < argc)
89  {
90  if (std::string(argv[i]) == "-o")
91  {
92  i++;
93  name=argv[i++];
94  }
95  else
96  {
97  std::cout << "Unknown parameter: " << argv[i] << std::endl;
98  std::cout << std::endl;
99 
100  printHelp(argv[0]);
101 
102  return 1;
103  }
104  }
105 
106  if (i >= argc || std::string(argv[i]) == "-h")
107  {
108  printHelp(argv[0]);
109  return 1;
110  }
111 
112  // find specific device accross all systems and interfaces and open it
113 
114  std::shared_ptr<rcg::Device> dev=rcg::getDevice(argv[i]);
115 
116  if (dev)
117  {
118  dev->open(rcg::Device::CONTROL);
119  std::shared_ptr<GenApi::CNodeMapRef> nodemap=dev->getRemoteNodeMap();
120 
121  // get focal length, baseline and disparity scale factor
122 
123  double f=rcg::getFloat(nodemap, "FocalLengthFactor", 0, 0, false);
124  double t=rcg::getFloat(nodemap, "Baseline", 0, 0, true);
125  double scale=rcg::getFloat(nodemap, "Scan3dCoordinateScale", 0, 0, true);
126 
127  // check for special exposure alternate mode of rc_visard and
128  // corresponding filter and set tolerance accordingly
129 
130  // (The exposure alternate mode is typically used with a random dot
131  // projector connected to Out1. Alternate means that Out1 is high for
132  // every second image. The rc_visard calculates disparities from images
133  // with Out1=High. However, if the alternate filter is set to OnlyLow,
134  // then it is gueranteed that Out1=Low (i.e. projector off) for all
135  // rectified images. Thus, rectified images and disparity images are
136  // always around 40 ms appart, which must be taken into account for
137  // synchronization.)
138 
139  uint64_t tol=0;
140 
141  try
142  {
143  rcg::setEnum(nodemap, "LineSelector", "Out1", true);
144  std::string linesource=rcg::getEnum(nodemap, "LineSource", true);
145  std::string filter=rcg::getEnum(nodemap, "AcquisitionAlternateFilter", true);
146 
147  if (linesource == "ExposureAlternateActive" && filter == "OnlyLow")
148  {
149  tol=50*1000*1000; // set tolerance to 50 ms
150  }
151  }
152  catch (const std::exception &)
153  {
154  // ignore possible errors
155  }
156 
157  // sanity check of some parameters
158 
159  rcg::checkFeature(nodemap, "Scan3dOutputMode", "DisparityC");
160  rcg::checkFeature(nodemap, "Scan3dCoordinateOffset", "0");
161  rcg::checkFeature(nodemap, "Scan3dInvalidDataFlag", "1");
162  rcg::checkFeature(nodemap, "Scan3dInvalidDataValue", "0");
163 
164  // set to color format if available
165 
166  rcg::setEnum(nodemap, "PixelFormat", "YCbCr411_8", false);
167 
168  // enable left image, disparity, confidence and error image and disable
169  // all others
170 
171  {
172  std::vector<std::string> component;
173 
174  rcg::getEnum(nodemap, "ComponentSelector", component, true);
175 
176  for (size_t k=0; k<component.size(); k++)
177  {
178  rcg::setEnum(nodemap, "ComponentSelector", component[k].c_str(), true);
179 
180  bool enable=(component[k] == "Intensity" || component[k] == "Disparity" ||
181  component[k] == "Confidence" || component[k] == "Error");
182  rcg::setBoolean(nodemap, "ComponentEnable", enable, true);
183  }
184  }
185 
186  // try getting synchronized data (which only has an effect if the device
187  // and GenTL producer support multipart)
188 
189  rcg::setString(nodemap, "AcquisitionMultiPartMode", "SynchronizedComponents");
190 
191  // open image stream
192 
193  std::vector<std::shared_ptr<rcg::Stream> > stream=dev->getStreams();
194 
195  if (stream.size() > 0)
196  {
197  // opening first stream
198 
199  stream[0]->open();
200  stream[0]->startStreaming();
201 
202  // prepare buffers for time synchronization of images (buffer at most
203  // 25 images in each list)
204 
205  rcg::ImageList left_list(50);
206  rcg::ImageList disp_list(25);
207  rcg::ImageList conf_list(25);
208  rcg::ImageList error_list(25);
209 
210  bool run=true;
211  int async=0, maxasync=50; // maximum number of asynchroneous images before giving up
212 
213  while (run && async < maxasync)
214  {
215  async++;
216 
217  // grab next image with timeout
218 
219  const rcg::Buffer *buffer=stream[0]->grab(5000);
220  if (buffer != 0)
221  {
222  // check for a complete image in the buffer
223 
224  if (!buffer->getIsIncomplete())
225  {
226  // go through all parts in case of multi-part buffer
227 
228  size_t partn=buffer->getNumberOfParts();
229  for (uint32_t part=0; part<partn; part++)
230  {
231  if (buffer->getImagePresent(part))
232  {
233  // store image in the corresponding list
234 
235  uint64_t left_tol=0;
236  uint64_t disp_tol=0;
237 
238  std::string component=rcg::getComponetOfPart(nodemap, buffer, part);
239 
240  if (component == "Intensity")
241  {
242  left_list.add(buffer, part);
243  disp_tol=tol;
244  }
245  else if (component == "Disparity")
246  {
247  disp_list.add(buffer, part);
248  left_tol=tol;
249  }
250  else if (component == "Confidence")
251  {
252  conf_list.add(buffer, part);
253  left_tol=tol;
254  }
255  else if (component == "Error")
256  {
257  error_list.add(buffer, part);
258  left_tol=tol;
259  }
260 
261  // get corresponding left and disparity images
262 
263  uint64_t timestamp=buffer->getTimestampNS();
264  std::shared_ptr<const rcg::Image> left=left_list.find(timestamp, left_tol);
265  std::shared_ptr<const rcg::Image> disp=disp_list.find(timestamp, disp_tol);
266 
267  // get confidence and error images that correspond to the
268  // disparity image
269 
270  std::shared_ptr<const rcg::Image> conf;
271  std::shared_ptr<const rcg::Image> error;
272 
273  if (disp)
274  {
275  conf=conf_list.find(disp->getTimestampNS());
276  error=error_list.find(disp->getTimestampNS());
277  }
278 
279  if (left && disp && conf && error)
280  {
281  // compute and store point cloud from synchronized image pair
282 
283  rcg::storePointCloud(name, f, t, scale, left, disp, conf, error);
284 
285  // remove all images from the buffer with the current or an
286  // older time stamp
287 
288  async=0;
289  left_list.removeOld(timestamp);
290  disp_list.removeOld(timestamp);
291  conf_list.removeOld(timestamp);
292  error_list.removeOld(timestamp);
293 
294  // in this example, we exit the grabbing loop after receiving
295  // the first synchronized image pair
296 
297  run=false;
298  }
299  }
300  }
301  }
302  }
303  else
304  {
305  std::cerr << "Cannot grab images" << std::endl;
306  break;
307  }
308  }
309 
310  // report if synchronization failed
311 
312  if (async >= maxasync && run)
313  {
314  std::cerr << "Cannot grab synchronized left and disparity image" << std::endl;
315  ret=1;
316  }
317 
318  // stopping and closing image stream
319 
320  stream[0]->stopStreaming();
321  stream[0]->close();
322  }
323  else
324  {
325  std::cerr << "No streams available" << std::endl;
326  ret=1;
327  }
328 
329  // closing the communication to the device
330 
331  dev->close();
332  }
333  else
334  {
335  std::cerr << "Device '" << argv[1] << "' not found!" << std::endl;
336  ret=1;
337  }
338  }
339  catch (const std::exception &ex)
340  {
341  std::cerr << ex.what() << std::endl;
342  ret=2;
343  }
344  catch (const GENICAM_NAMESPACE::GenericException &ex)
345  {
346  std::cerr << "Exception: " << ex.what() << std::endl;
347  ret=2;
348  }
349  catch (...)
350  {
351  std::cerr << "Unknown exception!" << std::endl;
352  ret=2;
353  }
354 
356 
357  return ret;
358 }
std::shared_ptr< Device > getDevice(const char *id)
Searches across all transport layers and interfaces for a device.
Definition: device.cc:469
std::shared_ptr< const Image > find(uint64_t timestamp) const
Returns the image that has the given timestamp.
Definition: imagelist.cc:102
void storePointCloud(std::string name, double f, double t, double scale, std::shared_ptr< const Image > left, std::shared_ptr< const Image > disp, std::shared_ptr< const Image > conf, std::shared_ptr< const Image > error)
Definition: pointcloud.cc:86
An object of this class manages a limited number of images.
Definition: imagelist.h:53
bool setEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, const char *value, bool exception)
Set the value of an enumeration of the given nodemap.
Definition: config.cc:294
static void clearSystems()
Clears the internal list of systems.
Definition: system.cc:213
void removeOld(uint64_t timestamp)
Removes all images that have a timestamp that is older or equal than the given timestamp.
Definition: imagelist.cc:73
The buffer class encapsulates a Genicam buffer that is provided by a stream.
Definition: buffer.h:118
void checkFeature(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, const char *value, bool igncache)
Checks the value of given feature and throws an exception in case of a mismatch.
Definition: config.cc:878
LOG4CPP_EXPORT CategoryStream & left(CategoryStream &os)
left manipulator
std::string getEnum(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception)
Get the value of an enumeration of the given nodemap.
Definition: config.cc:655
void add(const std::shared_ptr< const Image > &image)
Adds the given image to the internal list.
Definition: imagelist.cc:53
std::string getComponetOfPart(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const Buffer *buffer, uint32_t ipart)
Definition: config.cc:915
bool setString(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, const char *value, bool exception)
Set the value of a feature of the given nodemap.
Definition: config.cc:351
bool setBoolean(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool value, bool exception)
Set the value of a boolean feature of the given nodemap.
Definition: config.cc:99
double getFloat(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, double *vmin, double *vmax, bool exception, bool igncache)
Get the value of a double feature of the given nodemap.
Definition: config.cc:604
uint64_t getTimestampNS() const
Returns the acquisition timestamp of the data in this buffer in ns.
Definition: buffer.cc:591
bool getImagePresent(std::uint32_t part) const
Returns if a 2D, 3D or confidence image is present in the specified part.
Definition: buffer.cc:433
bool getIsIncomplete() const
Signals if the buffer is incomplete due to an error.
Definition: buffer.cc:304
GenICam&#39;s exception class.
Definition: GCException.h:63
int main(int argc, char *argv[])
virtual const char * what() const
Get error description (overwrite from std:exception)
std::uint32_t getNumberOfParts() const
Returns the number of parts, excluding chunk data.
Definition: buffer.cc:199


rc_genicam_api
Author(s): Heiko Hirschmueller
autogenerated on Wed Mar 17 2021 02:48:40