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;
86 std::cout << std::endl;
87 std::cout <<
"Streaming can be aborted by hitting the 'Enter' key." << std::endl;
95 std::string getDigitalIO(
const std::shared_ptr<GenApi::CNodeMapRef> &nodemap)
104 std::vector<std::string> io;
107 for (
int i=static_cast<int>(io.size())-1; i>=0; i--)
109 rcg::setEnum(nodemap,
"LineSelector", io[i].c_str(),
true);
113 if (mode ==
"Input") in+=std::to_string((line_status>>i)&0x1);
114 if (mode ==
"Output") out+=std::to_string((line_status>>i)&0x1);
117 if (out.size() > 0 || in.size() > 0)
119 if (out.size() == 0) out.push_back(
'0');
120 if (in.size() == 0) in.push_back(
'0');
123 ret <<
"_" << out <<
"_" << in;
127 catch (
const std::exception &)
132 return std::string();
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)
150 name <<
"image_" << t_sec <<
"." << std::setfill(
'0') << std::setw(9) << t_nsec;
152 if (component.size() > 0)
154 name <<
'_' << component;
159 name << getDigitalIO(nodemap);
164 std::string full_name;
168 full_name=
storeImage(name.
str(), fmt, image, yoffset, height);
172 std::cerr <<
"storeBuffer(): Received incomplete buffer" << std::endl;
176 std::cerr <<
"storeBuffer(): Received buffer without image" << std::endl;
190 std::string storeBufferAsDisparity(
const std::shared_ptr<GenApi::CNodeMapRef> &nodemap,
193 std::string dispname;
206 inv=
static_cast<int>(
rcg::getFloat(nodemap,
"ChunkScan3dInvalidDataValue"));
209 double scale=
rcg::getFloat(nodemap,
"ChunkScan3dCoordinateScale");
210 double offset=
rcg::getFloat(nodemap,
"ChunkScan3dCoordinateOffset");
219 name <<
"image_" << t_sec <<
"." << std::setfill(
'0') << std::setw(9) << t_nsec;
220 name <<
"_Disparity";
224 name << getDigitalIO(nodemap);
233 std::cerr <<
"storeBuffer(): Received incomplete buffer" << std::endl;
237 std::cerr <<
"storeBuffer(): Received buffer without image" << std::endl;
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)
260 name <<
"image_" << t_sec <<
"." << std::setfill(
'0') << std::setw(9) << t_nsec;
262 if (component.size() > 0)
264 name <<
'_' << component;
269 name << getDigitalIO(nodemap);
270 name <<
"_param.txt";
274 rcg::setString(nodemap,
"ChunkComponentSelector", component.c_str());
280 double u=
rcg::getFloat(nodemap,
"ChunkScan3dPrincipalPointU");
281 double v=
rcg::getFloat(nodemap,
"ChunkScan3dPrincipalPointV");
282 double exp=
rcg::getFloat(nodemap,
"ChunkExposureTime")/1000000.0;
285 double scale=0, offset=0;
291 inv=
static_cast<int>(
rcg::getFloat(nodemap,
"ChunkScan3dInvalidDataValue"));
295 offset=
rcg::getFloat(nodemap,
"ChunkScan3dCoordinateOffset");
300 if (width > 0 && height > 0 && f > 0 && t > 0)
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;
316 float v=
static_cast<float>(
rcg::getFloat(nodemap,
"ChunkRcNoise", 0, 0,
true));
317 out <<
"camera.noise=" << v << std::endl;
319 catch (
const std::exception &)
324 float v=
static_cast<float>(
rcg::getFloat(nodemap,
"ChunkRcBrightness", 0, 0,
true));
325 out <<
"camera.brightness=" << v << std::endl;
327 catch (
const std::exception &)
332 float v=
static_cast<float>(
rcg::getFloat(nodemap,
"ChunkRcOut1Reduction", 0, 0,
true));
333 out <<
"camera.out1_reduction=" << v << std::endl;
335 catch (
const std::exception &)
340 out <<
"disp.inv=" << inv << std::endl;
341 out <<
"disp.scale=" << scale << std::endl;
342 out <<
"disp.offset=" << offset << std::endl;
353 std::atomic<bool> user_interrupt(
false);
355 void interruptHandler(
int)
357 std::cout <<
"Stopping ..." << std::endl;
364 void checkUserInterrupt()
369 std::cout <<
"Stopping ..." << std::endl;
378 int main(
int argc,
char *argv[])
382 signal(SIGINT, interruptHandler);
392 while (i < argc && argv[i][0] ==
'-')
394 std::string param=argv[i];
401 else if (param ==
"-t")
406 else if (param ==
"-f")
412 std::string imgfmt=argv[i];
417 else if (imgfmt ==
"png")
423 throw std::invalid_argument(std::string(
"Invalid argument of '-f': ")+argv[i]);
430 throw std::invalid_argument(
"Argument expected after '-f'!");
435 throw std::invalid_argument(
"Unknown parameter: "+param);
449 std::shared_ptr<GenApi::CNodeMapRef> nodemap=dev->getRemoteNodeMap();
462 std::string key=argv[i++];
465 size_t k=key.find(
'=');
466 if (k != std::string::npos)
468 value=key.substr(k+1);
469 key=key.substr(0, k);
474 n=std::max(1, std::stoi(value));
478 if (value.size() > 0)
491 if (
rcg::setEnum(nodemap,
"ComponentSelector",
"IntensityCombined",
false) &&
494 if (
rcg::setEnum(nodemap,
"ComponentSelector",
"Intensity",
false) &&
499 std::cout << std::endl;
500 std::cout <<
"NOTE: Disabling component 'Intensity' as 'IntensityCombined' is enabled." 508 std::vector<std::string> component;
510 rcg::getEnum(nodemap,
"ComponentSelector", component,
false);
512 if (component.size() > 0)
514 std::cout << std::endl;
515 std::cout <<
"Available components (1 means enabled, 0 means disabled):" << std::endl;
516 std::cout << std::endl;
518 for (
size_t k=0; k<component.size(); k++)
520 rcg::setEnum(nodemap,
"ComponentSelector", component[k].c_str(),
true);
522 std::cout << component[k] <<
": ";
524 std::cout << std::endl;
527 std::cout << std::endl;
533 std::vector<std::shared_ptr<rcg::Stream> > stream=dev->getStreams();
535 if (stream.size() > 0)
539 std::thread thread_cui(checkUserInterrupt);
546 stream[0]->attachBuffers(
true);
547 stream[0]->startStreaming();
549 std::cout <<
"Package size: " <<
rcg::getString(nodemap,
"GevSCPSPacketSize") << std::endl;
552 std::cout <<
"Press 'Enter' to abort grabbing." << std::endl;
554 std::cout << std::endl;
556 int buffers_received=0;
557 int buffers_incomplete=0;
558 auto time_start=std::chrono::steady_clock::now();
561 for (
int k=0; k<n && !user_interrupt; k++)
566 while (retry > 0 && !user_interrupt)
581 for (uint32_t part=0; part<npart; part++)
593 if (component ==
"Disparity" && fmt ==
rcg::PNM)
595 name=storeBufferAsDisparity(nodemap, buffer, part);
597 if (name.size() != 0)
599 std::cout <<
"Image '" << name <<
"' stored" << std::endl;
600 storeParameter(nodemap, component, buffer);
606 if (name.size() == 0)
608 if (component ==
"IntensityCombined")
614 name=storeBuffer(fmt, nodemap,
"Intensity", buffer, part, 0, h2);
618 std::cout <<
"Image '" << name <<
"' stored" << std::endl;
621 name=storeBuffer(fmt, nodemap,
"IntensityRight", buffer, part, h2, h2);
625 std::cout <<
"Image '" << name <<
"' stored" << std::endl;
630 name=storeBuffer(fmt, nodemap, component, buffer, part);
634 std::cout <<
"Image '" << name <<
"' stored" << std::endl;
642 if (component ==
"Intensity")
644 storeParameter(nodemap, component, buffer);
646 else if (component ==
"Disparity")
648 storeParameter(nodemap, component, buffer, 0,
true);
650 else if (component ==
"IntensityCombined")
653 storeParameter(nodemap,
"Intensity", buffer, h2,
false);
673 std::cout <<
"Received buffer with timestamp: " << t_sec <<
"." 674 << std::setfill(
'0') << std::setw(9) << t_nsec << std::endl;
679 auto current=std::chrono::system_clock::now();
681 static_cast<double>(std::chrono::duration_cast<std::chrono::nanoseconds>(current.time_since_epoch()).count())-
687 std::cerr <<
"Incomplete buffer received" << std::endl;
688 buffers_incomplete++;
693 std::cerr <<
"Cannot grab images" << std::endl;
701 stream[0]->stopStreaming();
706 std::cout << std::endl;
707 std::cout <<
"Received buffers: " << buffers_received << std::endl;
708 std::cout <<
"Incomplete buffers: " << buffers_incomplete << std::endl;
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()
717 if (buffers_received-buffers_incomplete > 0)
719 latency_ns/=buffers_received-buffers_incomplete;
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;
728 if (buffers_incomplete == buffers_received)
735 std::cerr <<
"No streams available" << std::endl;
743 std::cerr <<
"Device '" << argv[i] <<
"' not found!" << std::endl;
753 catch (
const std::exception &ex)
755 std::cerr <<
"Exception: " << ex.what() << std::endl;
760 std::cerr <<
"Exception: " << ex.
what() << std::endl;
765 std::cerr <<
"Unknown exception!" << std::endl;
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...
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.
std::shared_ptr< Device > getDevice(const char *id)
Searches across all transport layers and interfaces for a device.
The image class encapsulates image information.
std::string storeImage(const std::string &name, ImgFmt fmt, const Image &image, size_t yoffset, size_t height)
Stores the given image.
int main(int argc, char *argv[])
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.
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.
static void clearSystems()
Clears the internal list of systems.
The buffer class encapsulates a Genicam buffer that is provided by a stream.
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.
uint64_t getPixelFormat(std::uint32_t part) const
Returns the pixel format of the specified part as defined in the PFNC.
std::string getComponetOfPart(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const Buffer *buffer, uint32_t ipart)
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.
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.
bool getContainsChunkdata() const
Returns if the buffer contains chunk data.
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.
uint64_t getTimestampNS() const
Returns the acquisition timestamp of the data in this buffer in ns.
bool callCommand(const std::shared_ptr< GenApi::CNodeMapRef > &nodemap, const char *name, bool exception)
Calls the given command.
bool getImagePresent(std::uint32_t part) const
Returns if a 2D, 3D or confidence image is present in the specified part.
bool getIsIncomplete() const
Signals if the buffer is incomplete due to an error.
GenICam's exception class.
size_t getHeight(std::uint32_t part) const
Returns the height of the image in pixel.
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.
std::string storeImageAsDisparityPFM(const std::string &name, const Image &image, int inv, float scale, float offset)
Stores the given image as disparity.
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.