gc_stream.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-2019 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>
43 #include <rc_genicam_api/config.h>
44 
46 
47 #include <Base/GCException.h>
48 
49 #include <signal.h>
50 
51 #include <iostream>
52 #include <fstream>
53 #include <iomanip>
54 #include <algorithm>
55 #include <atomic>
56 #include <thread>
57 #include <chrono>
58 
59 #ifdef _WIN32
60 #undef min
61 #undef max
62 #endif
63 
64 namespace
65 {
66 
67 void printHelp()
68 {
69  // show help
70 
71  std::cout << "gc_stream -h | [-f <fmt>] [-t] [<interface-id>:]<device-id> [n=<n>] [<key>=<value>] ..." << std::endl;
72  std::cout << std::endl;
73  std::cout << "Stores images from the specified device after applying the given optional GenICam parameters." << std::endl;
74  std::cout << std::endl;
75  std::cout << "Options:" << std::endl;
76  std::cout << "-h Prints help information and exits" << std::endl;
77  std::cout << "-t Testmode, which does not store images and provides extended statistics" << std::endl;
78  std::cout << "-f pnm|png Format for storing images. Default is pnm" << std::endl;
79  std::cout << std::endl;
80  std::cout << "Parameters:" << std::endl;
81  std::cout << "<interface-id> Optional GenICam ID of interface for connecting to the device" << std::endl;
82  std::cout << "<device-id> GenICam device ID, serial number or user defined name of device" << std::endl;
83  std::cout << "n=<n> Optional number of images to be received (default is 1)" << std::endl;
84  std::cout << "<key>=<value> Optional GenICam parameters to be changed in the given order" << std::endl;
85 #ifdef _WIN32
86  std::cout << std::endl;
87  std::cout << "Streaming can be aborted by hitting the 'Enter' key." << std::endl;
88 #endif
89 }
90 
95 std::string getDigitalIO(const std::shared_ptr<GenApi::CNodeMapRef> &nodemap)
96 {
97  try
98  {
99  std::int64_t line_status=rcg::getInteger(nodemap, "ChunkLineStatusAll", 0, 0, true);
100 
101  std::string out;
102  std::string in;
103 
104  std::vector<std::string> io;
105  rcg::getEnum(nodemap, "LineSelector", io, true);
106 
107  for (int i=static_cast<int>(io.size())-1; i>=0; i--)
108  {
109  rcg::setEnum(nodemap, "LineSelector", io[i].c_str(), true);
110 
111  std::string mode=rcg::getString(nodemap, "LineMode", true);
112 
113  if (mode == "Input") in+=std::to_string((line_status>>i)&0x1);
114  if (mode == "Output") out+=std::to_string((line_status>>i)&0x1);
115  }
116 
117  if (out.size() > 0 || in.size() > 0)
118  {
119  if (out.size() == 0) out.push_back('0');
120  if (in.size() == 0) in.push_back('0');
121 
122  std::ostringstream ret;
123  ret << "_" << out << "_" << in;
124  return ret.str();
125  }
126  }
127  catch (const std::exception &)
128  {
129  // just ignore and return empty string
130  }
131 
132  return std::string();
133 }
134 
139 std::string storeBuffer(rcg::ImgFmt fmt, const std::shared_ptr<GenApi::CNodeMapRef> &nodemap,
140  const std::string &component, const rcg::Buffer *buffer, uint32_t part,
141  size_t yoffset=0, size_t height=0)
142 {
143  // prepare file name
144 
145  std::ostringstream name;
146 
147  uint64_t t_sec = buffer->getTimestampNS()/1000000000;
148  uint64_t t_nsec = buffer->getTimestampNS()%1000000000;
149 
150  name << "image_" << t_sec << "." << std::setfill('0') << std::setw(9) << t_nsec;
151 
152  if (component.size() > 0)
153  {
154  name << '_' << component;
155  }
156 
157  if (buffer->getContainsChunkdata())
158  {
159  name << getDigitalIO(nodemap);
160  }
161 
162  // store image (see e.g. the sv tool of cvkit for show images)
163 
164  std::string full_name;
165  if (!buffer->getIsIncomplete() && buffer->getImagePresent(part))
166  {
167  rcg::Image image(buffer, part);
168  full_name=storeImage(name.str(), fmt, image, yoffset, height);
169  }
170  else if (buffer->getIsIncomplete())
171  {
172  std::cerr << "storeBuffer(): Received incomplete buffer" << std::endl;
173  }
174  else if (!buffer->getImagePresent(part))
175  {
176  std::cerr << "storeBuffer(): Received buffer without image" << std::endl;
177  }
178 
179  return full_name;
180 }
181 
190 std::string storeBufferAsDisparity(const std::shared_ptr<GenApi::CNodeMapRef> &nodemap,
191  const rcg::Buffer *buffer, uint32_t part)
192 {
193  std::string dispname;
194 
195  if (!buffer->getIsIncomplete() && buffer->getImagePresent(part) &&
196  buffer->getPixelFormat(part) == Coord3D_C16 && buffer->getContainsChunkdata())
197  {
198  // get necessary information from ChunkScan3d parameters
199 
200  int inv=-1;
201 
202  rcg::setString(nodemap, "ChunkComponentSelector", "Disparity");
203 
204  if (rcg::getBoolean(nodemap, "ChunkScan3dInvalidDataFlag"))
205  {
206  inv=static_cast<int>(rcg::getFloat(nodemap, "ChunkScan3dInvalidDataValue"));
207  }
208 
209  double scale=rcg::getFloat(nodemap, "ChunkScan3dCoordinateScale");
210  double offset=rcg::getFloat(nodemap, "ChunkScan3dCoordinateOffset");
211 
212  // prepare file name
213 
214  std::ostringstream name;
215 
216  uint64_t t_sec = buffer->getTimestampNS()/1000000000;
217  uint64_t t_nsec = buffer->getTimestampNS()%1000000000;
218 
219  name << "image_" << t_sec << "." << std::setfill('0') << std::setw(9) << t_nsec;
220  name << "_Disparity";
221 
222  // Append out1 and out2 status to file name: _<out1>_<out2>
223 
224  name << getDigitalIO(nodemap);
225 
226  // store image
227 
228  rcg::Image image(buffer, part);
229  dispname=storeImageAsDisparityPFM(name.str(), image, inv, static_cast<float>(scale), static_cast<float>(offset));
230  }
231  else if (buffer->getIsIncomplete())
232  {
233  std::cerr << "storeBuffer(): Received incomplete buffer" << std::endl;
234  }
235  else if (!buffer->getImagePresent(part))
236  {
237  std::cerr << "storeBuffer(): Received buffer without image" << std::endl;
238  }
239 
240  return dispname;
241 }
242 
247 void storeParameter(const std::shared_ptr<GenApi::CNodeMapRef> &nodemap,
248  const std::string &component, const rcg::Buffer *buffer,
249  size_t height=0, bool dispinfo=false)
250 {
251  if (buffer->getContainsChunkdata())
252  {
253  // prepare file name
254 
255  std::ostringstream name;
256 
257  uint64_t t_sec = buffer->getTimestampNS()/1000000000;
258  uint64_t t_nsec = buffer->getTimestampNS()%1000000000;
259 
260  name << "image_" << t_sec << "." << std::setfill('0') << std::setw(9) << t_nsec;
261 
262  if (component.size() > 0)
263  {
264  name << '_' << component;
265  }
266 
267  // Append out1 and out2 status to file name: _<out1>_<out2>
268 
269  name << getDigitalIO(nodemap);
270  name << "_param.txt";
271 
272  // get 3D parameter
273 
274  rcg::setString(nodemap, "ChunkComponentSelector", component.c_str());
275 
276  int width=static_cast<int>(rcg::getInteger(nodemap, "ChunkWidth"));
277  if (height == 0) height=rcg::getInteger(nodemap, "ChunkHeight");
278  double f=rcg::getFloat(nodemap, "ChunkScan3dFocalLength");
279  double t=rcg::getFloat(nodemap, "ChunkScan3dBaseline");
280  double u=rcg::getFloat(nodemap, "ChunkScan3dPrincipalPointU");
281  double v=rcg::getFloat(nodemap, "ChunkScan3dPrincipalPointV");
282  double exp=rcg::getFloat(nodemap, "ChunkExposureTime")/1000000.0;
283  double gain=rcg::getFloat(nodemap, "ChunkGain");
284  int inv=-1;
285  double scale=0, offset=0;
286 
287  if (dispinfo)
288  {
289  if (rcg::getBoolean(nodemap, "ChunkScan3dInvalidDataFlag"))
290  {
291  inv=static_cast<int>(rcg::getFloat(nodemap, "ChunkScan3dInvalidDataValue"));
292  }
293 
294  scale=rcg::getFloat(nodemap, "ChunkScan3dCoordinateScale");
295  offset=rcg::getFloat(nodemap, "ChunkScan3dCoordinateOffset");
296  }
297 
298  // create parameter file
299 
300  if (width > 0 && height > 0 && f > 0 && t > 0)
301  {
302  std::ofstream out(rcg::ensureNewFileName(name.str()));
303 
304  out << "# Created by gc_stream" << std::endl;
305  out << std::fixed << std::setprecision(5);
306  out << "camera.A=[" << f << " 0 " << u << "; 0 " << f << " " << v << "; 0 0 1]" << std::endl;
307  out << "camera.height=" << height << std::endl;
308  out << "camera.width=" << width << std::endl;
309  out << "camera.exposure_time=" << exp << std::endl;
310  out << "camera.gain=" << gain << std::endl;
311  out << "rho=" << f*t << std::endl;
312  out << "t=" << t << std::endl;
313 
314  try
315  {
316  float v=static_cast<float>(rcg::getFloat(nodemap, "ChunkRcNoise", 0, 0, true));
317  out << "camera.noise=" << v << std::endl;
318  }
319  catch (const std::exception &)
320  { }
321 
322  try
323  {
324  float v=static_cast<float>(rcg::getFloat(nodemap, "ChunkRcBrightness", 0, 0, true));
325  out << "camera.brightness=" << v << std::endl;
326  }
327  catch (const std::exception &)
328  { }
329 
330  try
331  {
332  float v=static_cast<float>(rcg::getFloat(nodemap, "ChunkRcOut1Reduction", 0, 0, true));
333  out << "camera.out1_reduction=" << v << std::endl;
334  }
335  catch (const std::exception &)
336  { }
337 
338  if (scale > 0)
339  {
340  out << "disp.inv=" << inv << std::endl;
341  out << "disp.scale=" << scale << std::endl;
342  out << "disp.offset=" << offset << std::endl;
343  }
344 
345  out.close();
346  }
347  }
348 }
349 
350 // simple mechanism to set the boolean flag when the user presses enter in the
351 // terminal
352 
353 std::atomic<bool> user_interrupt(false);
354 
355 void interruptHandler(int)
356 {
357  std::cout << "Stopping ..." << std::endl;
358 
359  user_interrupt=true;
360 }
361 
362 #ifdef _WIN32
363 
364 void checkUserInterrupt()
365 {
366  char a;
367  std::cin.get(a);
368 
369  std::cout << "Stopping ..." << std::endl;
370 
371  user_interrupt=true;
372 }
373 
374 #endif
375 
376 }
377 
378 int main(int argc, char *argv[])
379 {
380  int ret=0;
381 
382  signal(SIGINT, interruptHandler);
383 
384  try
385  {
386  bool store=true;
387  rcg::ImgFmt fmt=rcg::PNM;
388  int i=1;
389 
390  // get parameters
391 
392  while (i < argc && argv[i][0] == '-')
393  {
394  std::string param=argv[i];
395 
396  if (param == "-h")
397  {
398  printHelp();
399  return 0;
400  }
401  else if (param == "-t")
402  {
403  store=false;
404  i++;
405  }
406  else if (param == "-f")
407  {
408  i++;
409 
410  if (i < argc)
411  {
412  std::string imgfmt=argv[i];
413  if (imgfmt == "pnm")
414  {
415  fmt=rcg::PNM;
416  }
417  else if (imgfmt == "png")
418  {
419  fmt=rcg::PNG;
420  }
421  else
422  {
423  throw std::invalid_argument(std::string("Invalid argument of '-f': ")+argv[i]);
424  }
425 
426  i++;
427  }
428  else
429  {
430  throw std::invalid_argument("Argument expected after '-f'!");
431  }
432  }
433  else
434  {
435  throw std::invalid_argument("Unknown parameter: "+param);
436  }
437  }
438 
439  if (i < argc)
440  {
441  // find specific device accross all systems and interfaces and open it
442 
443  std::shared_ptr<rcg::Device> dev=rcg::getDevice(argv[i]);
444 
445  if (dev)
446  {
447  i++;
448  dev->open(rcg::Device::CONTROL);
449  std::shared_ptr<GenApi::CNodeMapRef> nodemap=dev->getRemoteNodeMap();
450 
451  // try to enable chunks by default (can be disabed by the user)
452 
453  rcg::setBoolean(nodemap, "ChunkModeActive", true);
454 
455  // set values as given on the command line
456 
457  int n=1;
458  while (i < argc)
459  {
460  // split argument in key and value
461 
462  std::string key=argv[i++];
463  std::string value;
464 
465  size_t k=key.find('=');
466  if (k != std::string::npos)
467  {
468  value=key.substr(k+1);
469  key=key.substr(0, k);
470  }
471 
472  if (key == "n") // set number of images
473  {
474  n=std::max(1, std::stoi(value));
475  }
476  else // set key=value pair through GenICam
477  {
478  if (value.size() > 0)
479  {
480  rcg::setString(nodemap, key.c_str(), value.c_str(), true);
481  }
482  else
483  {
484  rcg::callCommand(nodemap, key.c_str(), true);
485  }
486  }
487  }
488 
489  // disable component Intensity if component IntensityCombined is enabled
490 
491  if (rcg::setEnum(nodemap, "ComponentSelector", "IntensityCombined", false) &&
492  rcg::getBoolean(nodemap, "ComponentEnable", true, true))
493  {
494  if (rcg::setEnum(nodemap, "ComponentSelector", "Intensity", false) &&
495  rcg::getBoolean(nodemap, "ComponentEnable", true, true))
496  {
497  rcg::setBoolean(nodemap, "ComponentEnable", false, true);
498 
499  std::cout << std::endl;
500  std::cout << "NOTE: Disabling component 'Intensity' as 'IntensityCombined' is enabled."
501  << std::endl;
502  }
503  }
504 
505  // print enabled streams
506 
507  {
508  std::vector<std::string> component;
509 
510  rcg::getEnum(nodemap, "ComponentSelector", component, false);
511 
512  if (component.size() > 0)
513  {
514  std::cout << std::endl;
515  std::cout << "Available components (1 means enabled, 0 means disabled):" << std::endl;
516  std::cout << std::endl;
517 
518  for (size_t k=0; k<component.size(); k++)
519  {
520  rcg::setEnum(nodemap, "ComponentSelector", component[k].c_str(), true);
521 
522  std::cout << component[k] << ": ";
523  std::cout << rcg::getBoolean(nodemap, "ComponentEnable", true, true);
524  std::cout << std::endl;
525  }
526 
527  std::cout << std::endl;
528  }
529  }
530 
531  // open stream and get n images
532 
533  std::vector<std::shared_ptr<rcg::Stream> > stream=dev->getStreams();
534 
535  if (stream.size() > 0)
536  {
537 #ifdef _WIN32
538  // start background thread for checking user input
539  std::thread thread_cui(checkUserInterrupt);
540  thread_cui.detach();
541 #endif
542 
543  // opening first stream
544 
545  stream[0]->open();
546  stream[0]->attachBuffers(true);
547  stream[0]->startStreaming();
548 
549  std::cout << "Package size: " << rcg::getString(nodemap, "GevSCPSPacketSize") << std::endl;
550 
551 #ifdef _WIN32
552  std::cout << "Press 'Enter' to abort grabbing." << std::endl;
553 #endif
554  std::cout << std::endl;
555 
556  int buffers_received=0;
557  int buffers_incomplete=0;
558  auto time_start=std::chrono::steady_clock::now();
559  double latency_ns=0;
560 
561  for (int k=0; k<n && !user_interrupt; k++)
562  {
563  // grab next image with timeout of 3 seconds
564 
565  int retry=5;
566  while (retry > 0 && !user_interrupt)
567  {
568  const rcg::Buffer *buffer=stream[0]->grab(3000);
569 
570  if (buffer != 0)
571  {
572  buffers_received++;
573 
574  if (!buffer->getIsIncomplete())
575  {
576  // store images in all parts
577 
578  if (store)
579  {
580  uint32_t npart=buffer->getNumberOfParts();
581  for (uint32_t part=0; part<npart; part++)
582  {
583  if (buffer->getImagePresent(part))
584  {
585  std::string name;
586 
587  // get component name
588 
589  std::string component=rcg::getComponetOfPart(nodemap, buffer, part);
590 
591  // try storing disparity as float image with meta information
592 
593  if (component == "Disparity" && fmt == rcg::PNM)
594  {
595  name=storeBufferAsDisparity(nodemap, buffer, part);
596 
597  if (name.size() != 0)
598  {
599  std::cout << "Image '" << name << "' stored" << std::endl;
600  storeParameter(nodemap, component, buffer);
601  }
602  }
603 
604  // otherwise, store as ordinary image
605 
606  if (name.size() == 0)
607  {
608  if (component == "IntensityCombined")
609  {
610  // splitting left and right image of combined format of
611  // Roboceptions rc_visard camera
612 
613  size_t h2=buffer->getHeight(part)/2;
614  name=storeBuffer(fmt, nodemap, "Intensity", buffer, part, 0, h2);
615 
616  if (name.size() > 0)
617  {
618  std::cout << "Image '" << name << "' stored" << std::endl;
619  }
620 
621  name=storeBuffer(fmt, nodemap, "IntensityRight", buffer, part, h2, h2);
622 
623  if (name.size() > 0)
624  {
625  std::cout << "Image '" << name << "' stored" << std::endl;
626  }
627  }
628  else
629  {
630  name=storeBuffer(fmt, nodemap, component, buffer, part);
631 
632  if (name.size() > 0)
633  {
634  std::cout << "Image '" << name << "' stored" << std::endl;
635  }
636  }
637 
638  // store 3D parameters for intensity and disparity
639  // components (nothing is done if chunk parameters are
640  // not available)
641 
642  if (component == "Intensity")
643  {
644  storeParameter(nodemap, component, buffer);
645  }
646  else if (component == "Disparity")
647  {
648  storeParameter(nodemap, component, buffer, 0, true);
649  }
650  else if (component == "IntensityCombined")
651  {
652  size_t h2=buffer->getHeight(part)/2;
653  storeParameter(nodemap, "Intensity", buffer, h2, false);
654  }
655  }
656 
657  // report success
658 
659  if (name.size() > 0)
660  {
661  retry=0;
662  }
663  }
664  }
665  }
666  else
667  {
668  // just print timestamp of received buffer
669 
670  uint64_t t_sec = buffer->getTimestampNS()/1000000000;
671  uint64_t t_nsec = buffer->getTimestampNS()%1000000000;
672 
673  std::cout << "Received buffer with timestamp: " << t_sec << "."
674  << std::setfill('0') << std::setw(9) << t_nsec << std::endl;
675  retry=0;
676 
677  // accumulate mean latency
678 
679  auto current=std::chrono::system_clock::now();
680  latency_ns+=
681  static_cast<double>(std::chrono::duration_cast<std::chrono::nanoseconds>(current.time_since_epoch()).count())-
682  static_cast<double>(buffer->getTimestampNS());
683  }
684  }
685  else
686  {
687  std::cerr << "Incomplete buffer received" << std::endl;
688  buffers_incomplete++;
689  }
690  }
691  else
692  {
693  std::cerr << "Cannot grab images" << std::endl;
694  break;
695  }
696 
697  retry--;
698  }
699  }
700 
701  stream[0]->stopStreaming();
702  stream[0]->close();
703 
704  // report received and incomplete buffers
705 
706  std::cout << std::endl;
707  std::cout << "Received buffers: " << buffers_received << std::endl;
708  std::cout << "Incomplete buffers: " << buffers_incomplete << std::endl;
709 
710  auto time_stop=std::chrono::steady_clock::now();
711  std::cout << "Buffers per second: " << std::setprecision(3)
712  << 1000.0*buffers_received/std::chrono::duration_cast<std::chrono::milliseconds>(time_stop-time_start).count()
713  << std::endl;
714 
715  if (!store)
716  {
717  if (buffers_received-buffers_incomplete > 0)
718  {
719  latency_ns/=buffers_received-buffers_incomplete;
720  }
721 
722  std::cout << "Mean latency: " << std::setprecision(5) << latency_ns/1.0e6
723  << " ms (only meaningful if camera is synchronized e.g. via PTP!)" << std::endl;
724  }
725 
726  // return error code if no images could be received
727 
728  if (buffers_incomplete == buffers_received)
729  {
730  ret=1;
731  }
732  }
733  else
734  {
735  std::cerr << "No streams available" << std::endl;
736  ret=1;
737  }
738 
739  dev->close();
740  }
741  else
742  {
743  std::cerr << "Device '" << argv[i] << "' not found!" << std::endl;
744  ret=1;
745  }
746  }
747  else
748  {
749  printHelp();
750  ret=1;
751  }
752  }
753  catch (const std::exception &ex)
754  {
755  std::cerr << "Exception: " << ex.what() << std::endl;
756  ret=2;
757  }
758  catch (const GENICAM_NAMESPACE::GenericException &ex)
759  {
760  std::cerr << "Exception: " << ex.what() << std::endl;
761  ret=2;
762  }
763  catch (...)
764  {
765  std::cerr << "Unknown exception!" << std::endl;
766  ret=2;
767  }
768 
770 
771  return ret;
772 }
std::string ensureNewFileName(std::string name)
This method checks if the given file name already exists and produces a new file name if this happens...
Definition: image_store.cc:60
bool getBoolean(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception, bool igncache)
Get the value of a boolean feature of the given nodemap.
Definition: config.cc:497
std::shared_ptr< Device > getDevice(const char *id)
Searches across all transport layers and interfaces for a device.
Definition: device.cc:469
The image class encapsulates image information.
Definition: image.h:55
ImgFmt
Definition: image_store.h:46
std::string storeImage(const std::string &name, ImgFmt fmt, const Image &image, size_t yoffset, size_t height)
Stores the given image.
Definition: image_store.cc:528
int main(int argc, char *argv[])
Definition: gc_stream.cc:378
__int64 int64_t
Definition: config-win32.h:21
int64_t getInteger(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, int64_t *vmin, int64_t *vmax, bool exception, bool igncache)
Get the value of an integer feature of the given nodemap.
Definition: config.cc:542
std::string str()
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
The buffer class encapsulates a Genicam buffer that is provided by a stream.
Definition: buffer.h:118
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
uint64_t getPixelFormat(std::uint32_t part) const
Returns the pixel format of the specified part as defined in the PFNC.
Definition: buffer.cc:480
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
bool getContainsChunkdata() const
Returns if the buffer contains chunk data.
Definition: buffer.cc:627
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 callCommand(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception)
Calls the given command.
Definition: config.cc:53
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
size_t getHeight(std::uint32_t part) const
Returns the height of the image in pixel.
Definition: buffer.cc:351
std::string getString(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception, bool igncache)
Get the value of a feature of the given nodemap.
Definition: config.cc:773
std::string storeImageAsDisparityPFM(const std::string &name, const Image &image, int inv, float scale, float offset)
Stores the given image as disparity.
Definition: image_store.cc:552
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