PointGreyCamera.cpp
Go to the documentation of this file.
1 /*
2 This code was developed by the National Robotics Engineering Center (NREC), part of the Robotics Institute at Carnegie Mellon University.
3 Its development was funded by DARPA under the LS3 program and submitted for public release on June 7th, 2012.
4 Release was granted on August, 21st 2012 with Distribution Statement "A" (Approved for Public Release, Distribution Unlimited).
5 
6 This software is released under a BSD license:
7 
8 Copyright (c) 2012, Carnegie Mellon University. All rights reserved.
9 
10 Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
11 
12 Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
13 Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
14 Neither the name of the Carnegie Mellon University nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.
15 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
16 */
17 
18 
19 
20 /*-*-C++-*-*/
33 
34 #include <iostream>
35 #include <sstream>
36 #include <flycapture/FlyCapture2Defs.h>
37 
38 using namespace FlyCapture2;
39 
41  busMgr_(), cam_()
42 {
43  serial_ = 0;
44  captureRunning_ = false;
45 }
46 
48 {
49 }
50 
51 bool PointGreyCamera::setNewConfiguration(pointgrey_camera_driver::PointGreyConfig &config, const uint32_t &level)
52 {
53  if(!cam_.IsConnected())
54  {
56  }
57 
58  // Activate mutex to prevent us from grabbing images during this time
59  boost::mutex::scoped_lock scopedLock(mutex_);
60 
61  // return true if we can set values as desired.
62  bool retVal = true;
63 
64  // Check video mode
65  VideoMode vMode; // video mode desired
66  Mode fmt7Mode; // fmt7Mode to set
67  retVal &= PointGreyCamera::getVideoModeFromString(config.video_mode, vMode, fmt7Mode);
68 
69  // Only change video mode if we have to.
70  // dynamic_reconfigure will report anything other than LEVEL_RECONFIGURE_RUNNING if we need to change videomode.
72  {
73  bool wasRunning = PointGreyCamera::stop(); // Check if camera is running, and if it is, stop it.
74  if(vMode == VIDEOMODE_FORMAT7)
75  {
76  PixelFormat fmt7PixFmt;
77  PointGreyCamera::getFormat7PixelFormatFromString(config.format7_color_coding, fmt7PixFmt);
78  // Oh no, these all need to be converted into uints, so my pass by reference trick doesn't work
79  uint16_t uwidth = (uint16_t)config.format7_roi_width;
80  uint16_t uheight = (uint16_t)config.format7_roi_height;
81  uint16_t uoffsetx = (uint16_t)config.format7_x_offset;
82  uint16_t uoffsety = (uint16_t)config.format7_y_offset;
83  retVal &= PointGreyCamera::setFormat7(fmt7Mode, fmt7PixFmt, uwidth, uheight, uoffsetx, uoffsety);
84  config.format7_roi_width = uwidth;
85  config.format7_roi_height = uheight;
86  config.format7_x_offset = uoffsetx;
87  config.format7_y_offset = uoffsety;
88  }
89  else
90  {
91  // Need to set just videoMode
93  }
94  // Restart the camera if it was running
95  if(wasRunning)
96  {
98  }
99  }
100 
101  // Set frame rate
102  retVal &= PointGreyCamera::setProperty(FRAME_RATE, false, config.frame_rate);
103 
104  // Set exposure
105  retVal &= PointGreyCamera::setProperty(AUTO_EXPOSURE, config.auto_exposure, config.exposure);
106 
107  // Set sharpness
108  retVal &= PointGreyCamera::setProperty(SHARPNESS, config.auto_sharpness, config.sharpness);
109 
110  // Set saturation
111  retVal &= PointGreyCamera::setProperty(SATURATION, config.auto_saturation, config.saturation);
112 
113  // Set shutter time
114  double shutter = 1000.0 * config.shutter_speed; // Needs to be in milliseconds
115  retVal &= PointGreyCamera::setProperty(SHUTTER, config.auto_shutter, shutter);
116  config.shutter_speed = shutter / 1000.0; // Needs to be in seconds
117 
118  // Set gain
119  retVal &= PointGreyCamera::setProperty(GAIN, config.auto_gain, config.gain);
120 
121  // Set pan
122  unsigned int pan = config.pan;
123  unsigned int not_used = 0;
124  retVal &= PointGreyCamera::setProperty(PAN, false, pan, not_used);
125  config.pan = pan;
126 
127  // Set tilt
128  unsigned int tilt = config.tilt;
129  retVal &= PointGreyCamera::setProperty(TILT, false, tilt, not_used);
130  config.tilt = tilt;
131 
132  // Set brightness
133  retVal &= PointGreyCamera::setProperty(BRIGHTNESS, false, config.brightness);
134 
135  // Set gamma
136  retVal &= PointGreyCamera::setProperty(GAMMA, false, config.gamma);
137 
138  // Set white balance
139  uint16_t blue = config.white_balance_blue;
140  uint16_t red = config.white_balance_red;
141  retVal &= PointGreyCamera::setWhiteBalance(config.auto_white_balance, blue, red);
142  config.white_balance_blue = blue;
143  config.white_balance_red = red;
144 
145  // Set trigger
146  switch (config.trigger_polarity)
147  {
148  case pointgrey_camera_driver::PointGrey_Low:
149  case pointgrey_camera_driver::PointGrey_High:
150  {
151  bool temp = config.trigger_polarity;
152  retVal &= PointGreyCamera::setExternalTrigger(config.enable_trigger, config.trigger_mode, config.trigger_source, config.trigger_parameter, config.trigger_delay, temp);
153  config.strobe1_polarity = temp;
154  }
155  break;
156  default:
157  retVal &= false;
158  }
159 
160  // Set strobe
161  switch (config.strobe1_polarity)
162  {
163  case pointgrey_camera_driver::PointGrey_Low:
164  case pointgrey_camera_driver::PointGrey_High:
165  {
166  bool temp = config.strobe1_polarity;
167  retVal &= PointGreyCamera::setExternalStrobe(config.enable_strobe1, pointgrey_camera_driver::PointGrey_GPIO1, config.strobe1_duration, config.strobe1_delay, temp);
168  config.strobe1_polarity = temp;
169  }
170  break;
171  default:
172  retVal &= false;
173  }
174 
175 
176  switch (config.strobe2_polarity)
177  {
178  case pointgrey_camera_driver::PointGrey_Low:
179  case pointgrey_camera_driver::PointGrey_High:
180  {
181  bool temp = config.strobe2_polarity;
182  retVal &= PointGreyCamera::setExternalStrobe(config.enable_strobe2, pointgrey_camera_driver::PointGrey_GPIO2, config.strobe2_duration, config.strobe2_delay, temp);
183  config.strobe2_polarity = temp;
184  }
185  break;
186  default:
187  retVal &= false;
188  }
189 
190 
191  return retVal;
192 }
193 
194 void PointGreyCamera::setGain(double &gain)
195 {
196  PointGreyCamera::setProperty(GAIN, false, gain);
197 }
198 
199 void PointGreyCamera::setBRWhiteBalance(bool auto_white_balance, uint16_t &blue, uint16_t &red)
200 {
201  PointGreyCamera::setWhiteBalance(auto_white_balance, blue, red);
202 }
203 
204 void PointGreyCamera::setVideoMode(FlyCapture2::VideoMode &videoMode)
205 {
206  // Just set max frame rate, the actual double parameter will do the fine adjustments
207  FrameRate frameRate = FRAMERATE_7_5; // Most reliable, so set as default.
208  if(videoMode == VIDEOMODE_640x480Y8)
209  {
210  frameRate = FRAMERATE_30;
211  }
212  else if(videoMode == VIDEOMODE_1280x960Y8)
213  {
214  frameRate = FRAMERATE_15;
215  }
216  else if(videoMode == VIDEOMODE_1280x960Y16)
217  {
218  frameRate = FRAMERATE_7_5;
219  }
220  else if(videoMode == VIDEOMODE_FORMAT7)
221  {
222  frameRate = FRAMERATE_FORMAT7;
223  }
224  Error error = cam_.SetVideoModeAndFrameRate(videoMode, frameRate);
225  PointGreyCamera::handleError("PointGreyCamera::setVideoMode Could not set video mode", error);
226 }
227 
228 bool PointGreyCamera::setFormat7(FlyCapture2::Mode &fmt7Mode, FlyCapture2::PixelFormat &fmt7PixFmt, uint16_t &roi_width, uint16_t &roi_height, uint16_t &roi_offset_x, uint16_t &roi_offset_y)
229 {
230  // return true if we can set values as desired.
231  bool retVal = true;
232  // Error for checking if functions went okay
233  Error error;
234 
235  // Get Format7 information
236  Format7Info fmt7Info;
237  bool supported;
238  fmt7Info.mode = fmt7Mode;
239  error = cam_.GetFormat7Info(&fmt7Info, &supported);
240  PointGreyCamera::handleError("PointGreyCamera::setFormat7 Could not get Format 7 information", error);
241  if(!supported)
242  {
243  throw std::runtime_error("PointGreyCamera::setFormat7 Format 7 mode not supported on this camera.");
244  }
245 
246  // Make Format7 Configuration
247  Format7ImageSettings fmt7ImageSettings;
248  fmt7ImageSettings.mode = fmt7Mode;
249  fmt7ImageSettings.pixelFormat = fmt7PixFmt;
250 
251  // Check Width
252  roi_width = roi_width / fmt7Info.imageHStepSize * fmt7Info.imageHStepSize; // Locks the width into an appropriate multiple using an integer divide
253  if(roi_width == 0)
254  {
255  fmt7ImageSettings.width = fmt7Info.maxWidth;
256  }
257  else if(roi_width > fmt7Info.maxWidth)
258  {
259  roi_width = fmt7Info.maxWidth;
260  fmt7ImageSettings.width = fmt7Info.maxWidth;
261  retVal &= false;
262  }
263  else
264  {
265  fmt7ImageSettings.width = roi_width;
266  }
267 
268  // Check Height
269  roi_height = roi_height / fmt7Info.imageVStepSize * fmt7Info.imageVStepSize; // Locks the height into an appropriate multiple using an integer divide
270  if(roi_height == 0)
271  {
272  fmt7ImageSettings.height = fmt7Info.maxHeight;
273  }
274  else if(roi_height > fmt7Info.maxHeight)
275  {
276  roi_height = fmt7Info.maxHeight;
277  fmt7ImageSettings.height = fmt7Info.maxHeight;
278  retVal &= false;
279  }
280  else
281  {
282  fmt7ImageSettings.height = roi_height;
283  }
284 
285  // Check OffsetX
286  roi_offset_x = roi_offset_x / fmt7Info.offsetHStepSize * fmt7Info.offsetHStepSize; // Locks the X offset into an appropriate multiple using an integer divide
287  if(roi_offset_x > (fmt7Info.maxWidth - fmt7ImageSettings.width))
288  {
289  roi_offset_x = fmt7Info.maxWidth - fmt7ImageSettings.width;
290  retVal &= false;
291  }
292  fmt7ImageSettings.offsetX = roi_offset_x;
293 
294  // Check OffsetY
295  roi_offset_y = roi_offset_y / fmt7Info.offsetVStepSize * fmt7Info.offsetVStepSize; // Locks the X offset into an appropriate multiple using an integer divide
296  if(roi_offset_y > fmt7Info.maxHeight - fmt7ImageSettings.height)
297  {
298  roi_offset_y = fmt7Info.maxHeight - fmt7ImageSettings.height;
299  retVal &= false;
300  }
301  fmt7ImageSettings.offsetY = roi_offset_y;
302 
303  // Validate the settings to make sure that they are valid
304  Format7PacketInfo fmt7PacketInfo;
305  bool valid;
306  error = cam_.ValidateFormat7Settings(&fmt7ImageSettings, &valid, &fmt7PacketInfo);
307  PointGreyCamera::handleError("PointGreyCamera::setFormat7 Error validating Format 7 settings", error);
308  if(!valid)
309  {
310  throw std::runtime_error("PointGreyCamera::setFormat7 Format 7 Settings Not Valid.");
311  }
312 
313  // Stop the camera to allow settings to change.
314  error = cam_.SetFormat7Configuration(&fmt7ImageSettings, fmt7PacketInfo.recommendedBytesPerPacket);
315  PointGreyCamera::handleError("PointGreyCamera::setFormat7 Could not send Format7 configuration to the camera", error);
316 
317  // Get camera info to check if camera is running in color or mono mode
318  CameraInfo cInfo;
319  error = cam_.GetCameraInfo(&cInfo);
320  PointGreyCamera::handleError("PointGreyCamera::setFormat7 Failed to get camera info.", error);
321  isColor_ = cInfo.isColorCamera;
322 
323  return retVal;
324 }
325 
326 bool PointGreyCamera::getVideoModeFromString(std::string &vmode, FlyCapture2::VideoMode &vmode_out, FlyCapture2::Mode &fmt7Mode)
327 {
328  // return true if we can set values as desired.
329  bool retVal = true;
330 
331  // Get camera info to check if color or black and white chameleon
332  CameraInfo cInfo;
333  Error error = cam_.GetCameraInfo(&cInfo);
334  PointGreyCamera::handleError("PointGreyCamera::getVideoModeFromString Failed to get camera info.", error);
335 
336  if(vmode.compare("640x480_mono8") == 0)
337  {
338  vmode_out = VIDEOMODE_640x480Y8;
339  }
340  else if(vmode.compare("640x480_mono16") == 0)
341  {
342  vmode_out = VIDEOMODE_640x480Y16;
343  }
344  else if(vmode.compare("1280x960_mono8") == 0)
345  {
346  vmode_out = VIDEOMODE_1280x960Y8;
347  if(cInfo.isColorCamera) // Is color camera, set the output differently
348  {
349  vmode = "1280x960_bayer8";
350  retVal &= false;
351  }
352  }
353  else if(vmode.compare("1280x960_bayer8") == 0)
354  {
355  vmode_out = VIDEOMODE_1280x960Y8;
356  if(!cInfo.isColorCamera) // Is black and white camera, set the output differently
357  {
358  vmode = "1280x960_mono8";
359  retVal &= false;
360  }
361  }
362  else if(vmode.compare("1280x960_mono16") == 0)
363  {
364  vmode_out = VIDEOMODE_1280x960Y16;
365  }
366  else if(vmode.compare("format7_mode0") == 0)
367  {
368  fmt7Mode = MODE_0;
369  vmode_out = VIDEOMODE_FORMAT7;
370  }
371  else if(vmode.compare("format7_mode1") == 0)
372  {
373  fmt7Mode = MODE_1;
374  vmode_out = VIDEOMODE_FORMAT7;
375  }
376  else if(vmode.compare("format7_mode2") == 0)
377  {
378  fmt7Mode = MODE_2;
379  vmode_out = VIDEOMODE_FORMAT7;
380  }
381  else if(vmode.compare("format7_mode3") == 0)
382  {
383  fmt7Mode = MODE_3;
384  vmode_out = VIDEOMODE_FORMAT7;
385  }
386  else if(vmode.compare("format7_mode4") == 0)
387  {
388  fmt7Mode = MODE_4;
389  vmode_out = VIDEOMODE_FORMAT7;
390  }
391  else if(vmode.compare("format7_mode5") == 0)
392  {
393  fmt7Mode = MODE_5;
394  vmode_out = VIDEOMODE_FORMAT7;
395  }
396  else if(vmode.compare("format7_mode7") == 0)
397  {
398  fmt7Mode = MODE_7;
399  vmode_out = VIDEOMODE_FORMAT7;
400  }
401  else // Something not supported was asked of us, drop down into the most compatible mode
402  {
403  vmode = "640x480_mono8";
404  vmode_out = VIDEOMODE_640x480Y8;
405  retVal &= false;
406  }
407 
408  return retVal;
409 }
410 
411 bool PointGreyCamera::getFormat7PixelFormatFromString(std::string &sformat, FlyCapture2::PixelFormat &fmt7PixFmt)
412 {
413  // return true if we can set values as desired.
414  bool retVal = true;
415 
416  // Get camera info to check if color or black and white camera
417  CameraInfo cInfo;
418  Error error = cam_.GetCameraInfo(&cInfo);
419  PointGreyCamera::handleError("PointGreyCamera::getFormat7PixelFormatFromString Failed to get camera info.", error);
420 
421  if(cInfo.isColorCamera)
422  {
423  if(sformat.compare("raw8") == 0)
424  {
425  fmt7PixFmt = PIXEL_FORMAT_RAW8;
426  }
427  else if(sformat.compare("raw16") == 0)
428  {
429  fmt7PixFmt = PIXEL_FORMAT_RAW16;
430  }
431  else if(sformat.compare("mono8") == 0)
432  {
433  fmt7PixFmt = PIXEL_FORMAT_MONO8;
434  }
435  else if(sformat.compare("mono16") == 0)
436  {
437  fmt7PixFmt = PIXEL_FORMAT_MONO16;
438  }
439  else if(sformat.compare("rgb8") == 0){
440  fmt7PixFmt = PIXEL_FORMAT_RGB;
441  }
442  else
443  {
444  sformat = "raw8";
445  fmt7PixFmt = PIXEL_FORMAT_RAW8;
446  retVal &= false;
447  }
448  }
449  else // Is black and white
450  {
451  if(sformat.compare("mono8") == 0)
452  {
453  fmt7PixFmt = PIXEL_FORMAT_MONO8;
454  }
455  else if(sformat.compare("mono16") == 0)
456  {
457  fmt7PixFmt = PIXEL_FORMAT_MONO16;
458  }
459  else
460  {
461  sformat = "mono8";
462  fmt7PixFmt = PIXEL_FORMAT_MONO8;
463  retVal &= false;
464  }
465  }
466 
467  return retVal;
468 }
469 
470 bool PointGreyCamera::setProperty(const FlyCapture2::PropertyType &type, const bool &autoSet, unsigned int &valueA, unsigned int &valueB)
471 {
472  // return true if we can set values as desired.
473  bool retVal = true;
474 
475  PropertyInfo pInfo;
476  pInfo.type = type;
477  Error error = cam_.GetPropertyInfo(&pInfo);
478  PointGreyCamera::handleError("PointGreyCamera::setProperty Could not get property info.", error);
479 
480  if(pInfo.present)
481  {
482  Property prop;
483  prop.type = type;
484  prop.autoManualMode = (autoSet && pInfo.autoSupported);
485  prop.absControl = false;
486  prop.onOff = pInfo.onOffSupported;
487 
488  if(valueA < pInfo.min)
489  {
490  valueA = pInfo.min;
491  retVal &= false;
492  }
493  else if(valueA > pInfo.max)
494  {
495  valueA = pInfo.max;
496  retVal &= false;
497  }
498  if(valueB < pInfo.min)
499  {
500  valueB = pInfo.min;
501  retVal &= false;
502  }
503  else if(valueB > pInfo.max)
504  {
505  valueB = pInfo.max;
506  retVal &= false;
507  }
508  prop.valueA = valueA;
509  prop.valueB = valueB;
510  error = cam_.SetProperty(&prop);
511  PointGreyCamera::handleError("PointGreyCamera::setProperty Failed to set property ", error);
513  // Read back setting to confirm
514  error = cam_.GetProperty(&prop);
515  PointGreyCamera::handleError("PointGreyCamera::setProperty Failed to confirm property ", error);
516  if(!prop.autoManualMode)
517  {
518  valueA = prop.valueA;
519  valueB = prop.valueB;
520  }
521  }
522  else // Not supported
523  {
524  valueA = 0;
525  valueB = 0;
526  }
527 
528  return retVal;
529 }
530 
531 bool PointGreyCamera::setProperty(const FlyCapture2::PropertyType &type, const bool &autoSet, double &value)
532 {
533  // return true if we can set values as desired.
534  bool retVal = true;
535 
536  PropertyInfo pInfo;
537  pInfo.type = type;
538  Error error = cam_.GetPropertyInfo(&pInfo);
539  PointGreyCamera::handleError("PointGreyCamera::setProperty Could not get property info.", error);
540 
541  if(pInfo.present)
542  {
543  Property prop;
544  prop.type = type;
545  prop.autoManualMode = (autoSet && pInfo.autoSupported);
546  prop.absControl = pInfo.absValSupported;
547  prop.onOff = pInfo.onOffSupported;
548 
549  if(value < pInfo.absMin)
550  {
551  value = pInfo.absMin;
552  retVal &= false;
553  }
554  else if(value > pInfo.absMax)
555  {
556  value = pInfo.absMax;
557  retVal &= false;
558  }
559  prop.absValue = value;
560  error = cam_.SetProperty(&prop);
561  PointGreyCamera::handleError("PointGreyCamera::setProperty Failed to set property ", error);
563  // Read back setting to confirm
564  error = cam_.GetProperty(&prop);
565  PointGreyCamera::handleError("PointGreyCamera::setProperty Failed to confirm property ", error);
566  if(!prop.autoManualMode)
567  {
568  value = prop.absValue;
569  }
570  }
571  else // Not supported
572  {
573  value = 0.0;
574  }
575  return retVal;
576 }
577 
578 bool PointGreyCamera::setWhiteBalance(bool &auto_white_balance, uint16_t &blue, uint16_t &red)
579 {
580  // Get camera info to check if color or black and white chameleon
581  CameraInfo cInfo;
582  Error error = cam_.GetCameraInfo(&cInfo);
583  handleError("PointGreyCamera::setWhiteBalance Failed to get camera info.", error);
584 
585  if(!cInfo.isColorCamera)
586  {
587  // Not a color camera, does not support auto white balance
588  auto_white_balance = false;
589  red = 0;
590  blue = 0;
591  return false;
592  }
593 
594  unsigned white_balance_addr = 0x80c;
595  unsigned enable = 1 << 31;
596  unsigned value = 1 << 25;
597 
598  if (auto_white_balance) {
599  PropertyInfo prop_info;
600  prop_info.type = WHITE_BALANCE;
601  error = cam_.GetPropertyInfo(&prop_info);
602  handleError("PointGreyCamera::setWhiteBalance Failed to get property info.", error);
603  if (!prop_info.autoSupported) {
604  // This is typically because a color camera is in mono mode, so we set
605  // the red and blue to some reasonable value for later use
606  auto_white_balance = false;
607  blue = 800;
608  red = 550;
609  return false;
610  }
611  // Auto white balance is supported
612  error = cam_.WriteRegister(white_balance_addr, enable);
613  handleError("PointGreyCamera::setWhiteBalance Failed to write to register.", error);
614  // Auto mode
615  value |= 1 << 24;
616  } else {
617  // Manual mode
618  value |= 0 << 24;
619  }
620  // Blue is bits 8-19 (0 is MSB), red is 20-31.
621  value |= blue << 12 | red;
622  error = cam_.WriteRegister(white_balance_addr, value);
623  handleError("PointGreyCamera::setWhiteBalance Failed to write to register.", error);
624  return true;
625 }
626 
627 void PointGreyCamera::setTimeout(const double &timeout)
628 {
629  FC2Config pConfig;
630  Error error = cam_.GetConfiguration(&pConfig);
631  PointGreyCamera::handleError("PointGreyCamera::setTimeout Could not get camera configuration", error);
632  pConfig.grabTimeout = (int)(1000.0 * timeout); // Needs to be in ms
633  if(pConfig.grabTimeout < 0.00001)
634  {
635  pConfig.grabTimeout = -1; // Default - no timeout
636  }
637  error = cam_.SetConfiguration(&pConfig);
638  PointGreyCamera::handleError("PointGreyCamera::setTimeout Could not set camera configuration", error);
639 }
640 
642 {
643  Property tProp;
644  tProp.type = TEMPERATURE;
645  Error error = cam_.GetProperty(&tProp);
646  PointGreyCamera::handleError("PointGreyCamera::getCameraTemperature Could not get property.", error);
647  return tProp.valueA / 10.0f - 273.15f; // It returns values of 10 * K
648 }
649 
651 {
652  Property fProp;
653  fProp.type = FRAME_RATE;
654  Error error = cam_.GetProperty(&fProp);
655  PointGreyCamera::handleError("PointGreyCamera::getCameraFrameRate Could not get property.", error);
656  std::cout << "Frame Rate is: " << fProp.absValue << std::endl;
657  return fProp.absValue;
658 }
659 
660 static int sourceNumberFromGpioName(const std::string s)
661 {
662  if(s.compare("gpio0") == 0)
663  {
664  return 0;
665  }
666  else if(s.compare("gpio1") == 0)
667  {
668  return 1;
669  }
670  else if(s.compare("gpio2") == 0)
671  {
672  return 2;
673  }
674  else if(s.compare("gpio3") == 0)
675  {
676  return 3;
677  }
678  else
679  {
680  // Unrecognized pin
681  return -1;
682  }
683 }
684 
685 bool PointGreyCamera::setExternalStrobe(bool &enable, const std::string &dest, double &duration, double &delay, bool &polarityHigh)
686 {
687  // return true if we can set values as desired.
688  bool retVal = true;
689 
690  // Check strobe source
691  int pin;
692  pin = sourceNumberFromGpioName(dest);
693  if (pin < 0)
694  {
695  // Unrecognized source
696  return false;
697  }
698  // Check for external trigger support
699  StrobeInfo strobeInfo;
700  strobeInfo.source = pin;
701  Error error = cam_.GetStrobeInfo(&strobeInfo);
702  PointGreyCamera::handleError("PointGreyCamera::setExternalStrobe Could not check external strobe support.", error);
703  if(strobeInfo.present != true)
704  {
705  // Camera doesn't support external strobes on this pin, so set enable_strobe to false
706  enable = false;
707  return false;
708  }
709 
710  StrobeControl strobeControl;
711  strobeControl.source = pin;
712  error = cam_.GetStrobe(&strobeControl);
713  PointGreyCamera::handleError("PointGreyCamera::setExternalStrobe Could not get strobe control.", error);
714  strobeControl.duration = duration;
715  strobeControl.delay = delay;
716  strobeControl.onOff = enable;
717  strobeControl.polarity = polarityHigh;
718 
719  error = cam_.SetStrobe(&strobeControl);
720  PointGreyCamera::handleError("PointGreyCamera::setExternalStrobe Could not set strobe control.", error);
721  error = cam_.GetStrobe(&strobeControl);
722  PointGreyCamera::handleError("PointGreyCamera::setExternalStrobe Could not get strobe control.", error);
723  delay = strobeControl.delay;
724  enable = strobeControl.onOff;
725  polarityHigh = strobeControl.polarity;
726 
727  return retVal;
728 }
729 
730 bool PointGreyCamera::setExternalTrigger(bool &enable, std::string &mode, std::string &source, int32_t &parameter, double &delay, bool &polarityHigh)
731 {
732  // return true if we can set values as desired.
733  bool retVal = true;
734  // Check for external trigger support
735  TriggerModeInfo triggerModeInfo;
736  Error error = cam_.GetTriggerModeInfo(&triggerModeInfo);
737  PointGreyCamera::handleError("PointGreyCamera::setExternalTrigger Could not check external trigger support.", error);
738  if(triggerModeInfo.present != true)
739  {
740  // Camera doesn't support external triggering, so set enable_trigger to false
741  enable = false;
742  return false;
743  }
744 
745  TriggerMode triggerMode;
746  error = cam_.GetTriggerMode(&triggerMode);
747  PointGreyCamera::handleError("PointGreyCamera::setExternalTrigger Could not get trigger mode.", error);
748  triggerMode.onOff = enable;
749 
750  // Set trigger mode
751  std::string tmode = mode;
752  if(tmode.compare("mode0") == 0)
753  {
754  triggerMode.mode = 0;
755  }
756  else if(tmode.compare("mode1") == 0)
757  {
758  triggerMode.mode = 1;
759  }
760  else if(tmode.compare("mode3") == 0)
761  {
762  triggerMode.mode = 3;
763  }
764  else if(tmode.compare("mode14") == 0)
765  {
766  triggerMode.mode = 14;
767  }
768  else
769  {
770  // Unrecognized mode
771  triggerMode.mode = 0;
772  mode = "mode0";
773  retVal &= false;
774  }
775 
776  // Parameter is used for mode3 (return one out of every N frames). So if N is two, it returns every other frame.
777  triggerMode.parameter = parameter;
778 
779  // Set trigger source
780  std::string tsource = source;
781  int pin = sourceNumberFromGpioName(tsource);
782  if (pin < 0)
783  {
784  // Unrecognized source
785  triggerMode.source = 0;
786  source = "gpio0";
787  retVal &= false;
788  }
789  else
790  {
791  triggerMode.source = pin;
792  }
793 
794  triggerMode.polarity = polarityHigh;
795 
796  error = cam_.SetTriggerMode(&triggerMode);
797  PointGreyCamera::handleError("PointGreyCamera::setExternalTrigger Could not set trigger mode.", error);
798  error = cam_.GetTriggerMode(&triggerMode);
799  PointGreyCamera::handleError("PointGreyCamera::setExternalTrigger Could not get trigger mode.", error);
800  enable = triggerMode.onOff;
801  std::stringstream buff;
802  buff << "mode" << triggerMode.mode;
803  mode = buff.str();
804 
807  // Set trigger delay
808  TriggerDelay triggerDelay;
809  triggerDelay.type = TRIGGER_DELAY;
810  triggerDelay.absControl = true;
811  triggerDelay.absValue = delay;
812  triggerDelay.onOff = true;
813  error = cam_.SetTriggerDelay(&triggerDelay);
814  PointGreyCamera::handleError("PointGreyCamera::setExternalTrigger Could not set trigger delay.", error);
815  error = cam_.GetTriggerDelay(&triggerDelay);
816  PointGreyCamera::handleError("PointGreyCamera::setExternalTrigger Could not get trigger delay.", error);
817  delay = triggerDelay.absValue;
818 
819  return retVal;
820 }
821 
822 void PointGreyCamera::setGigEParameters(bool auto_packet_size, unsigned int packet_size, unsigned int packet_delay)
823 {
824  auto_packet_size_ = auto_packet_size;
825  packet_size_ = packet_size;
826  packet_delay_ = packet_delay;
827 }
828 
829 void PointGreyCamera::setupGigEPacketSize(PGRGuid & guid)
830 {
831  GigECamera cam;
832  Error error;
833  error = cam.Connect(&guid);
834  PointGreyCamera::handleError("PointGreyCamera::connect could not connect as GigE camera", error);
835  unsigned int packet_size;
836  error = cam.DiscoverGigEPacketSize(&packet_size);
837  PointGreyCamera::handleError("PointGreyCamera::connect could not discover GigE packet_size", error);
838  GigEProperty prop;
839  prop.propType = PACKET_SIZE;
840  error = cam.GetGigEProperty(&prop);
841  PointGreyCamera::handleError("PointGreyCamera::connect could not get GigE packet_size", error);
842  prop.value = packet_size;
843  error = cam.SetGigEProperty(&prop);
844  PointGreyCamera::handleError("PointGreyCamera::connect could not set GigE packet_size", error);
845 }
846 
847 void PointGreyCamera::setupGigEPacketSize(PGRGuid & guid, unsigned int packet_size)
848 {
849  GigECamera cam;
850  Error error;
851  error = cam.Connect(&guid);
852  PointGreyCamera::handleError("PointGreyCamera::connect could not connect as GigE camera", error);
853  GigEProperty prop;
854  prop.propType = PACKET_SIZE;
855  prop.value = packet_size;
856  error = cam.SetGigEProperty(&prop);
857  PointGreyCamera::handleError("PointGreyCamera::connect could not set GigE packet_size", error);
858 }
859 
860 void PointGreyCamera::setupGigEPacketDelay(PGRGuid & guid, unsigned int packet_delay)
861 {
862  GigECamera cam;
863  Error error;
864  error = cam.Connect(&guid);
865  PointGreyCamera::handleError("PointGreyCamera::connect could not connect as GigE camera", error);
866  GigEProperty prop;
867  prop.propType = PACKET_DELAY;
868  prop.value = packet_delay;
869  error = cam.SetGigEProperty(&prop);
870  PointGreyCamera::handleError("PointGreyCamera::connect could not set GigE packet_delay", error);
871 }
872 
874 {
875  if(!cam_.IsConnected())
876  {
877  Error error;
878  PGRGuid guid; // GUIDS are NOT persistent accross executions, do not store them.
879  if(serial_ != 0) // If we have a specific camera to connect to.
880  {
881  error = busMgr_.GetCameraFromSerialNumber(serial_, &guid);
882  std::stringstream serial_string;
883  serial_string << serial_;
884  std::string msg = "PointGreyCamera::connect Could not find camera with serial number: " + serial_string.str() + ". Is that camera plugged in?";
885  PointGreyCamera::handleError(msg, error);
886  }
887  else // Connect to any camera (the first)
888  {
889  error = busMgr_.GetCameraFromIndex(0, &guid);
890  PointGreyCamera::handleError("PointGreyCamera::connect Failed to get first connected camera", error);
891  }
892 
893  FlyCapture2::InterfaceType ifType;
894  error = busMgr_.GetInterfaceTypeFromGuid(&guid, &ifType);
895  PointGreyCamera::handleError("PointGreyCamera::connect Failed to get interface style of camera", error);
896  if (ifType == FlyCapture2::INTERFACE_GIGE)
897  {
898  // Set packet size:
899  if (auto_packet_size_)
900  setupGigEPacketSize(guid);
901  else
903 
904  // Set packet delay:
906 
907  // Enable packet resend
908  GigECamera cam;
909  Error error;
910  error = cam.Connect(&guid);
911  PointGreyCamera::handleError("PointGreyCamera::connect could not connect as GigE camera", error);
912  GigEConfig gigeconfig;
913  error = cam.GetGigEConfig(&gigeconfig);
914  PointGreyCamera::handleError("PointGreyCamera::GetGigEConfig could not get GigE setting", error);
915  gigeconfig.enablePacketResend = true;
916  error = cam.SetGigEConfig(&gigeconfig);
917  PointGreyCamera::handleError("PointGreyCamera::SetGigEConfig could not set GigE settings (packet resend)", error);
918  }
919 
920  error = cam_.Connect(&guid);
921  PointGreyCamera::handleError("PointGreyCamera::connect Failed to connect to camera", error);
922 
923  // Get camera info to check if camera is running in color or mono mode
924  CameraInfo cInfo;
925  error = cam_.GetCameraInfo(&cInfo);
926  PointGreyCamera::handleError("PointGreyCamera::connect Failed to get camera info.", error);
927  isColor_ = cInfo.isColorCamera;
928 
929  // Enable metadata
930  EmbeddedImageInfo info;
931  info.timestamp.onOff = true;
932  info.gain.onOff = true;
933  info.shutter.onOff = true;
934  info.brightness.onOff = true;
935  info.exposure.onOff = true;
936  info.whiteBalance.onOff = true;
937  info.frameCounter.onOff = true;
938  info.ROIPosition.onOff = true;
939  error = cam_.SetEmbeddedImageInfo(&info);
940  PointGreyCamera::handleError("PointGreyCamera::connect Could not enable metadata", error);
941  }
942 }
943 
945 {
946  boost::mutex::scoped_lock scopedLock(mutex_);
947  captureRunning_ = false;
948  if(cam_.IsConnected())
949  {
950  Error error = cam_.Disconnect();
951  PointGreyCamera::handleError("PointGreyCamera::disconnect Failed to disconnect camera", error);
952  }
953 }
954 
956 {
957  if(cam_.IsConnected() && !captureRunning_)
958  {
959  // Start capturing images
960  Error error = cam_.StartCapture();
961  PointGreyCamera::handleError("PointGreyCamera::start Failed to start capture", error);
962  captureRunning_ = true;
963  }
964 }
965 
967 {
968  if(cam_.IsConnected() && captureRunning_)
969  {
970  // Stop capturing images
971  captureRunning_ = false;
972  Error error = cam_.StopCapture();
973  PointGreyCamera::handleError("PointGreyCamera::stop Failed to stop capture", error);
974  return true;
975  }
976  return false;
977 }
978 
979 void PointGreyCamera::grabImage(sensor_msgs::Image &image, const std::string &frame_id)
980 {
981  boost::mutex::scoped_lock scopedLock(mutex_);
982  if(cam_.IsConnected() && captureRunning_)
983  {
984  // Make a FlyCapture2::Image to hold the buffer returned by the camera.
985  Image rawImage;
986  // Retrieve an image
987  Error error = cam_.RetrieveBuffer(&rawImage);
988  PointGreyCamera::handleError("PointGreyCamera::grabImage Failed to retrieve buffer", error);
989  metadata_ = rawImage.GetMetadata();
990 
991  // Set header timestamp as embedded for now
992  TimeStamp embeddedTime = rawImage.GetTimeStamp();
993  image.header.stamp.sec = embeddedTime.seconds;
994  image.header.stamp.nsec = 1000 * embeddedTime.microSeconds;
995 
996  // Check the bits per pixel.
997  uint8_t bitsPerPixel = rawImage.GetBitsPerPixel();
998 
999  // Set the image encoding
1000  std::string imageEncoding = sensor_msgs::image_encodings::MONO8;
1001  BayerTileFormat bayer_format = rawImage.GetBayerTileFormat();
1002  if(isColor_ && bayer_format != NONE)
1003  {
1004  if(bitsPerPixel == 16)
1005  {
1006  switch(bayer_format)
1007  {
1008  case RGGB:
1010  break;
1011  case GRBG:
1013  break;
1014  case GBRG:
1016  break;
1017  case BGGR:
1019  break;
1020  }
1021  }
1022  else
1023  {
1024  switch(bayer_format)
1025  {
1026  case RGGB:
1028  break;
1029  case GRBG:
1031  break;
1032  case GBRG:
1034  break;
1035  case BGGR:
1037  break;
1038  }
1039  }
1040  }
1041  else // Mono camera or in pixel binned mode.
1042  {
1043  if(bitsPerPixel == 16)
1044  {
1045  imageEncoding = sensor_msgs::image_encodings::MONO16;
1046  }
1047  else if(bitsPerPixel==24)
1048  {
1049  imageEncoding = sensor_msgs::image_encodings::RGB8;
1050  }
1051  else
1052  {
1053  imageEncoding = sensor_msgs::image_encodings::MONO8;
1054  }
1055  }
1056 
1057  fillImage(image, imageEncoding, rawImage.GetRows(), rawImage.GetCols(), rawImage.GetStride(), rawImage.GetData());
1058  image.header.frame_id = frame_id;
1059  }
1060  else if(cam_.IsConnected())
1061  {
1062  throw CameraNotRunningException("PointGreyCamera::grabImage: Camera is currently not running. Please start the capture.");
1063  }
1064  else
1065  {
1066  throw std::runtime_error("PointGreyCamera::grabImage not connected!");
1067  }
1068 }
1069 
1070 void PointGreyCamera::grabStereoImage(sensor_msgs::Image &image, const std::string &frame_id, sensor_msgs::Image &second_image, const std::string &second_frame_id)
1071 {
1072  boost::mutex::scoped_lock scopedLock(mutex_);
1073  if(cam_.IsConnected() && captureRunning_)
1074  {
1075  // Make a FlyCapture2::Image to hold the buffer returned by the camera.
1076  Image rawImage;
1077  // Retrieve an image
1078  Error error = cam_.RetrieveBuffer(&rawImage);
1079  PointGreyCamera::handleError("PointGreyCamera::grabStereoImage Failed to retrieve buffer", error);
1080  metadata_ = rawImage.GetMetadata();
1081 
1082  // Set header timestamp as embedded for now
1083  TimeStamp embeddedTime = rawImage.GetTimeStamp();
1084  image.header.stamp.sec = embeddedTime.seconds;
1085  image.header.stamp.nsec = 1000 * embeddedTime.microSeconds;
1086 
1087  // GetBitsPerPixel returns 16, but that seems to mean "2 8 bit pixels,
1088  // one for each image". Therefore, we don't use it
1089  //uint8_t bitsPerPixel = rawImage.GetBitsPerPixel();
1090 
1091  // Set the image encoding
1092  std::string imageEncoding = sensor_msgs::image_encodings::MONO8;
1093  BayerTileFormat bayer_format = rawImage.GetBayerTileFormat();
1094 
1095  if(isColor_ && bayer_format != NONE)
1096  {
1097  switch(bayer_format)
1098  {
1099  case RGGB:
1101  break;
1102  case GRBG:
1104  break;
1105  case GBRG:
1107  break;
1108  case BGGR:
1110  break;
1111  }
1112  }
1113  else // Mono camera
1114  {
1115  imageEncoding = sensor_msgs::image_encodings::MONO8;
1116  }
1117 
1118  // Set up the output images
1119  image.encoding = imageEncoding;
1120  second_image.encoding = imageEncoding;
1121  image.height = rawImage.GetRows();
1122  second_image.height = image.height;
1123  image.width = rawImage.GetCols();
1124  second_image.width = image.width;
1125  image.step = rawImage.GetStride() / 2;
1126  second_image.step = image.step;
1127  image.is_bigendian = 0;
1128  second_image.is_bigendian = 0;
1129  size_t st0 = (image.height * image.step);
1130  image.data.resize(st0);
1131  second_image.data.resize(st0);
1132  image.header.frame_id = frame_id;
1133  second_image.header.frame_id = second_frame_id;
1134 
1135  // Get the image data
1136  const uint8_t* raw_data = rawImage.GetData();
1137 
1138  // Step through the raw data and set each image in turn
1139  for(size_t i = 0; i < rawImage.GetRows(); i++) // Rows
1140  {
1141  for(size_t j = 0; j < rawImage.GetCols(); j++) // Columns that need to have the 16 bits split into 2 8 bit groups
1142  {
1143  size_t index = i * image.step + j;
1144  size_t raw_index = 2 * index;
1145  image.data[index] = raw_data[raw_index];
1146  second_image.data[index] = raw_data[raw_index + 1];
1147  }
1148  }
1149 
1150  //fillImage(image, imageEncoding, rawImage.GetRows(), rawImage.GetCols(), rawImage.GetStride(), rawImage.GetData());
1151  }
1152  else if(cam_.IsConnected())
1153  {
1154  throw CameraNotRunningException("PointGreyCamera::grabStereoImage: Camera is currently not running. Please start the capture.");
1155  }
1156  else
1157  {
1158  throw std::runtime_error("PointGreyCamera::grabStereoImage not connected!");
1159  }
1160 }
1161 
1163 {
1164  return metadata_.embeddedGain >> 20;
1165 }
1166 
1168 {
1169  return metadata_.embeddedShutter >> 20;
1170 }
1171 
1173 {
1174  return metadata_.embeddedTimeStamp >> 20;
1175 }
1176 
1178 {
1179  return metadata_.embeddedBrightness >> 20;
1180 }
1181 
1183 {
1184  return metadata_.embeddedExposure >> 8;
1185 }
1186 
1188 {
1189  return metadata_.embeddedROIPosition >> 24;
1190 }
1191 
1192 void PointGreyCamera::setDesiredCamera(const uint32_t &id)
1193 {
1194  serial_ = id;
1195 }
1196 
1198 {
1199  std::vector<uint32_t> cameras;
1200  unsigned int num_cameras;
1201  Error error = busMgr_.GetNumOfCameras(&num_cameras);
1202  PointGreyCamera::handleError("PointGreyCamera::getAttachedCameras: Could not get number of cameras", error);
1203  for(unsigned int i = 0; i < num_cameras; i++)
1204  {
1205  unsigned int this_serial;
1206  error = busMgr_.GetCameraSerialNumberFromIndex(i, &this_serial);
1207  PointGreyCamera::handleError("PointGreyCamera::getAttachedCameras: Could not get get serial number from index", error);
1208  cameras.push_back(this_serial);
1209  }
1210  return cameras;
1211 }
1212 
1213 void PointGreyCamera::handleError(const std::string &prefix, const FlyCapture2::Error &error)
1214 {
1215  if(error == PGRERROR_TIMEOUT)
1216  {
1217  throw CameraTimeoutException("PointGreyCamera: Failed to retrieve buffer within timeout.");
1218  }
1219  else if(error == PGRERROR_IMAGE_CONSISTENCY_ERROR)
1220  {
1221  throw CameraImageConsistencyError("PointGreyCamera: Image consistency error.");
1222  }
1223  else if(error != PGRERROR_OK) // If there is actually an error (PGRERROR_OK means the function worked as intended...)
1224  {
1225  std::string start(" | FlyCapture2::ErrorType ");
1226  std::stringstream out;
1227  out << error.GetType();
1228  std::string desc(error.GetDescription());
1229  throw std::runtime_error(prefix + start + out.str() + " " + desc);
1230  }
1231 }
const std::string BAYER_GRBG8
msg
Error
float getCameraTemperature()
Gets the current operating temperature.
const std::string BAYER_GRBG16
volatile bool captureRunning_
A status boolean that checks if the camera has been started and is loading images into its buffer...
void setDesiredCamera(const uint32_t &id)
Used to set the serial number for the camera you wish to connect to.
FlyCapture2::ImageMetadata metadata_
Metadata from the last image, stores useful information such as timestamp, gain, shutter, brightness, exposure.
void setBRWhiteBalance(bool auto_white_balance, uint16_t &blue, uint16_t &red)
NONE
const std::string BAYER_RGGB16
Interface to Point Grey cameras.
bool getFormat7PixelFormatFromString(std::string &sformat, FlyCapture2::PixelFormat &fmt7PixFmt)
Converts the dynamic_reconfigure string type into a FlyCapture2::PixelFormat.
bool auto_packet_size_
If true, GigE packet size is automatically determined, otherwise packet_size_ is used: ...
FlyCapture2::BusManager busMgr_
A FlyCapture2::BusManager that is responsible for finding the appropriate camera. ...
bool setExternalTrigger(bool &enable, std::string &mode, std::string &source, int32_t &parameter, double &delay, bool &polarityHigh)
Will set the external triggering of the camera.
void setGain(double &gain)
uint32_t serial_
A variable to hold the serial number of the desired camera.
bool stop()
Stops the camera loading data into its buffer.
float getCameraFrameRate()
Gets the current frame rate.
const std::string BAYER_GBRG8
bool setFormat7(FlyCapture2::Mode &fmt7Mode, FlyCapture2::PixelFormat &fmt7PixFmt, uint16_t &roi_width, uint16_t &roi_height, uint16_t &roi_offset_x, uint16_t &roi_offset_y)
Changes the camera into Format7 mode with the associated parameters.
const std::string BAYER_GBRG16
void setTimeout(const double &timeout)
Will set grabImage timeout for the camera.
boost::mutex mutex_
A mutex to make sure that we don&#39;t try to grabImages while reconfiguring or vice versa. Implemented with boost::mutex::scoped_lock.
void setVideoMode(FlyCapture2::VideoMode &videoMode)
Changes the video mode of the connected camera.
const std::string BAYER_BGGR16
FlyCapture2::Camera cam_
A FlyCapture2::Camera set by the bus manager.
void connect()
Function that connects to a specified camera.
void setGigEParameters(bool auto_packet_size, unsigned int packet_size, unsigned int packet_delay)
Set parameters relative to GigE cameras.
const std::string MONO16
bool setProperty(const FlyCapture2::PropertyType &type, const bool &autoSet, unsigned int &valueA, unsigned int &valueB)
void setupGigEPacketSize(FlyCapture2::PGRGuid &guid)
Will autoconfigure the packet size of the GigECamera with the given GUID.
void grabImage(sensor_msgs::Image &image, const std::string &frame_id)
Loads the raw data from the cameras buffer.
void setupGigEPacketDelay(FlyCapture2::PGRGuid &guid, unsigned int packet_delay)
Will configure the packet delay of the GigECamera with the given GUID to a given value.
bool setExternalStrobe(bool &enable, const std::string &dest, double &duration, double &delay, bool &polarityHigh)
Will set the external strobe of the camera.
void start()
Starts the camera loading data into its buffer.
const std::string BAYER_BGGR8
unsigned int packet_delay_
GigE packet delay:
static const uint8_t LEVEL_RECONFIGURE_RUNNING
std::vector< uint32_t > getAttachedCameras()
unsigned int packet_size_
GigE packet size:
const std::string BAYER_RGGB8
bool isColor_
If true, camera is currently running in color mode, otherwise camera is running in mono mode...
static int sourceNumberFromGpioName(const std::string s)
void disconnect()
Disconnects from the camera.
bool getVideoModeFromString(std::string &vmode, FlyCapture2::VideoMode &vmode_out, FlyCapture2::Mode &fmt7Mode)
Converts the dynamic_reconfigure string type into a FlyCapture2::VideoMode.
bool setWhiteBalance(bool &auto_white_balance, uint16_t &blue, uint16_t &red)
Sets the white balance property.
static void handleError(const std::string &prefix, const FlyCapture2::Error &error)
Handles errors returned by FlyCapture2.
void grabStereoImage(sensor_msgs::Image &image, const std::string &frame_id, sensor_msgs::Image &second_image, const std::string &second_frame_id)
bool setNewConfiguration(pointgrey_camera_driver::PointGreyConfig &config, const uint32_t &level)
Function that allows reconfiguration of the camera.


pointgrey_camera_driver
Author(s): Chad Rockey
autogenerated on Thu Jun 6 2019 19:27:05