00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00032 #include "pointgrey_camera_driver/PointGreyCamera.h"
00033
00034 #include <iostream>
00035 #include <sstream>
00036
00037 using namespace FlyCapture2;
00038
00039 PointGreyCamera::PointGreyCamera():
00040 busMgr_(), cam_()
00041 {
00042 serial_ = 0;
00043 captureRunning_ = false;
00044 }
00045
00046 PointGreyCamera::~PointGreyCamera()
00047 {
00048 }
00049
00050 bool PointGreyCamera::setNewConfiguration(pointgrey_camera_driver::PointGreyConfig &config, const uint32_t &level)
00051 {
00052 if(!cam_.IsConnected())
00053 {
00054 PointGreyCamera::connect();
00055 }
00056
00057
00058 boost::mutex::scoped_lock scopedLock(mutex_);
00059
00060
00061 bool retVal = true;
00062
00063
00064 VideoMode vMode;
00065 Mode fmt7Mode;
00066 retVal &= PointGreyCamera::getVideoModeFromString(config.video_mode, vMode, fmt7Mode);
00067
00068
00069
00070 if(level != PointGreyCamera::LEVEL_RECONFIGURE_RUNNING)
00071 {
00072 bool wasRunning = PointGreyCamera::stop();
00073 if(vMode == VIDEOMODE_FORMAT7)
00074 {
00075 PixelFormat fmt7PixFmt;
00076 PointGreyCamera::getFormat7PixelFormatFromString(config.format7_color_coding, fmt7PixFmt);
00077
00078 uint16_t uwidth = (uint16_t)config.format7_roi_width;
00079 uint16_t uheight = (uint16_t)config.format7_roi_height;
00080 uint16_t uoffsetx = (uint16_t)config.format7_x_offset;
00081 uint16_t uoffsety = (uint16_t)config.format7_y_offset;
00082 retVal &= PointGreyCamera::setFormat7(fmt7Mode, fmt7PixFmt, uwidth, uheight, uoffsetx, uoffsety);
00083 config.format7_roi_width = uwidth;
00084 config.format7_roi_height = uheight;
00085 config.format7_x_offset = uoffsetx;
00086 config.format7_y_offset = uoffsety;
00087 }
00088 else
00089 {
00090
00091 PointGreyCamera::setVideoMode(vMode);
00092 }
00093
00094 if(wasRunning)
00095 {
00096 PointGreyCamera::start();
00097 }
00098 }
00099
00100
00101 retVal &= PointGreyCamera::setProperty(FRAME_RATE, false, config.frame_rate);
00102
00103
00104 retVal &= PointGreyCamera::setProperty(AUTO_EXPOSURE, config.auto_exposure, config.exposure);
00105
00106
00107 double shutter = 1000.0 * config.shutter_speed;
00108 retVal &= PointGreyCamera::setProperty(SHUTTER, config.auto_shutter, shutter);
00109 config.shutter_speed = shutter / 1000.0;
00110
00111
00112 retVal &= PointGreyCamera::setProperty(GAIN, config.auto_gain, config.gain);
00113
00114
00115 unsigned int pan = config.pan;
00116 unsigned int not_used = 0;
00117 retVal &= PointGreyCamera::setProperty(PAN, false, pan, not_used);
00118 config.pan = pan;
00119
00120
00121 unsigned int tilt = config.tilt;
00122 retVal &= PointGreyCamera::setProperty(TILT, false, tilt, not_used);
00123 config.tilt = tilt;
00124
00125
00126 retVal &= PointGreyCamera::setProperty(BRIGHTNESS, false, config.brightness);
00127
00128
00129 retVal &= PointGreyCamera::setProperty(GAMMA, false, config.gamma);
00130
00131
00132 uint16_t blue = config.white_balance_blue;
00133 uint16_t red = config.white_balance_red;
00134 retVal &= PointGreyCamera::setWhiteBalance(config.auto_white_balance, blue, red);
00135 config.white_balance_blue = blue;
00136 config.white_balance_red = red;
00137
00138
00139 switch (config.trigger_polarity)
00140 {
00141 case pointgrey_camera_driver::PointGrey_Low:
00142 case pointgrey_camera_driver::PointGrey_High:
00143 {
00144 bool temp = config.trigger_polarity;
00145 retVal &= PointGreyCamera::setExternalTrigger(config.enable_trigger, config.trigger_mode, config.trigger_source, config.trigger_parameter, config.trigger_delay, temp);
00146 config.strobe1_polarity = temp;
00147 }
00148 break;
00149 default:
00150 retVal &= false;
00151 }
00152
00153
00154 switch (config.strobe1_polarity)
00155 {
00156 case pointgrey_camera_driver::PointGrey_Low:
00157 case pointgrey_camera_driver::PointGrey_High:
00158 {
00159 bool temp = config.strobe1_polarity;
00160 retVal &= PointGreyCamera::setExternalStrobe(config.enable_strobe1, pointgrey_camera_driver::PointGrey_GPIO1, config.strobe1_duration, config.strobe1_delay, temp);
00161 config.strobe1_polarity = temp;
00162 }
00163 break;
00164 default:
00165 retVal &= false;
00166 }
00167
00168 return retVal;
00169 }
00170
00171 void PointGreyCamera::setGain(double &gain)
00172 {
00173 PointGreyCamera::setProperty(GAIN, false, gain);
00174 }
00175
00176 void PointGreyCamera::setBRWhiteBalance(bool auto_white_balance, uint16_t &blue, uint16_t &red)
00177 {
00178 PointGreyCamera::setWhiteBalance(auto_white_balance, blue, red);
00179 }
00180
00181 void PointGreyCamera::setVideoMode(FlyCapture2::VideoMode &videoMode)
00182 {
00183
00184 FrameRate frameRate = FRAMERATE_7_5;
00185 if(videoMode == VIDEOMODE_640x480Y8)
00186 {
00187 frameRate = FRAMERATE_30;
00188 }
00189 else if(videoMode == VIDEOMODE_1280x960Y8)
00190 {
00191 frameRate = FRAMERATE_15;
00192 }
00193 else if(videoMode == VIDEOMODE_1280x960Y16)
00194 {
00195 frameRate = FRAMERATE_7_5;
00196 }
00197 else if(videoMode == VIDEOMODE_FORMAT7)
00198 {
00199 frameRate = FRAMERATE_FORMAT7;
00200 }
00201 Error error = cam_.SetVideoModeAndFrameRate(videoMode, frameRate);
00202 PointGreyCamera::handleError("PointGreyCamera::setVideoMode Could not set video mode", error);
00203 }
00204
00205 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)
00206 {
00207
00208 bool retVal = true;
00209
00210 Error error;
00211
00212
00213 Format7Info fmt7Info;
00214 bool supported;
00215 fmt7Info.mode = fmt7Mode;
00216 error = cam_.GetFormat7Info(&fmt7Info, &supported);
00217 PointGreyCamera::handleError("PointGreyCamera::setFormat7 Could not get Format 7 information", error);
00218 if(!supported)
00219 {
00220 throw std::runtime_error("PointGreyCamera::setFormat7 Format 7 mode not supported on this camera.");
00221 }
00222
00223
00224 Format7ImageSettings fmt7ImageSettings;
00225 fmt7ImageSettings.mode = fmt7Mode;
00226 fmt7ImageSettings.pixelFormat = fmt7PixFmt;
00227
00228
00229 roi_width = roi_width / fmt7Info.imageHStepSize * fmt7Info.imageHStepSize;
00230 if(roi_width == 0)
00231 {
00232 fmt7ImageSettings.width = fmt7Info.maxWidth;
00233 }
00234 else if(roi_width > fmt7Info.maxWidth)
00235 {
00236 roi_width = fmt7Info.maxWidth;
00237 fmt7ImageSettings.width = fmt7Info.maxWidth;
00238 retVal &= false;
00239 }
00240 else
00241 {
00242 fmt7ImageSettings.width = roi_width;
00243 }
00244
00245
00246 roi_height = roi_height / fmt7Info.imageVStepSize * fmt7Info.imageVStepSize;
00247 if(roi_height == 0)
00248 {
00249 fmt7ImageSettings.height = fmt7Info.maxHeight;
00250 }
00251 else if(roi_height > fmt7Info.maxHeight)
00252 {
00253 roi_height = fmt7Info.maxHeight;
00254 fmt7ImageSettings.height = fmt7Info.maxHeight;
00255 retVal &= false;
00256 }
00257 else
00258 {
00259 fmt7ImageSettings.height = roi_height;
00260 }
00261
00262
00263 roi_offset_x = roi_offset_x / fmt7Info.offsetHStepSize * fmt7Info.offsetHStepSize;
00264 if(roi_offset_x > (fmt7Info.maxWidth - fmt7ImageSettings.width))
00265 {
00266 roi_offset_x = fmt7Info.maxWidth - fmt7ImageSettings.width;
00267 retVal &= false;
00268 }
00269 fmt7ImageSettings.offsetX = roi_offset_x;
00270
00271
00272 roi_offset_y = roi_offset_y / fmt7Info.offsetVStepSize * fmt7Info.offsetVStepSize;
00273 if(roi_offset_y > fmt7Info.maxHeight - fmt7ImageSettings.height)
00274 {
00275 roi_offset_y = fmt7Info.maxHeight - fmt7ImageSettings.height;
00276 retVal &= false;
00277 }
00278 fmt7ImageSettings.offsetY = roi_offset_y;
00279
00280
00281 Format7PacketInfo fmt7PacketInfo;
00282 bool valid;
00283 error = cam_.ValidateFormat7Settings(&fmt7ImageSettings, &valid, &fmt7PacketInfo);
00284 PointGreyCamera::handleError("PointGreyCamera::setFormat7 Error validating Format 7 settings", error);
00285 if(!valid)
00286 {
00287 throw std::runtime_error("PointGreyCamera::setFormat7 Format 7 Settings Not Valid.");
00288 }
00289
00290
00291 error = cam_.SetFormat7Configuration(&fmt7ImageSettings, fmt7PacketInfo.recommendedBytesPerPacket);
00292 PointGreyCamera::handleError("PointGreyCamera::setFormat7 Could not send Format7 configuration to the camera", error);
00293
00294
00295 CameraInfo cInfo;
00296 error = cam_.GetCameraInfo(&cInfo);
00297 PointGreyCamera::handleError("PointGreyCamera::setFormat7 Failed to get camera info.", error);
00298 isColor_ = cInfo.isColorCamera;
00299
00300 return retVal;
00301 }
00302
00303 bool PointGreyCamera::getVideoModeFromString(std::string &vmode, FlyCapture2::VideoMode &vmode_out, FlyCapture2::Mode &fmt7Mode)
00304 {
00305
00306 bool retVal = true;
00307
00308
00309 CameraInfo cInfo;
00310 Error error = cam_.GetCameraInfo(&cInfo);
00311 PointGreyCamera::handleError("PointGreyCamera::getVideoModeFromString Failed to get camera info.", error);
00312
00313 if(vmode.compare("640x480_mono8") == 0)
00314 {
00315 vmode_out = VIDEOMODE_640x480Y8;
00316 }
00317 else if(vmode.compare("640x480_mono16") == 0)
00318 {
00319 vmode_out = VIDEOMODE_640x480Y16;
00320 }
00321 else if(vmode.compare("1280x960_mono8") == 0)
00322 {
00323 vmode_out = VIDEOMODE_1280x960Y8;
00324 if(cInfo.isColorCamera)
00325 {
00326 vmode = "1280x960_bayer8";
00327 retVal &= false;
00328 }
00329 }
00330 else if(vmode.compare("1280x960_bayer8") == 0)
00331 {
00332 vmode_out = VIDEOMODE_1280x960Y8;
00333 if(!cInfo.isColorCamera)
00334 {
00335 vmode = "1280x960_mono8";
00336 retVal &= false;
00337 }
00338 }
00339 else if(vmode.compare("1280x960_mono16") == 0)
00340 {
00341 vmode_out = VIDEOMODE_1280x960Y16;
00342 }
00343 else if(vmode.compare("format7_mode0") == 0)
00344 {
00345 fmt7Mode = MODE_0;
00346 vmode_out = VIDEOMODE_FORMAT7;
00347 }
00348 else if(vmode.compare("format7_mode1") == 0)
00349 {
00350 fmt7Mode = MODE_1;
00351 vmode_out = VIDEOMODE_FORMAT7;
00352 }
00353 else if(vmode.compare("format7_mode2") == 0)
00354 {
00355 fmt7Mode = MODE_2;
00356 vmode_out = VIDEOMODE_FORMAT7;
00357 }
00358 else if(vmode.compare("format7_mode3") == 0)
00359 {
00360 fmt7Mode = MODE_3;
00361 vmode_out = VIDEOMODE_FORMAT7;
00362 }
00363 else
00364 {
00365 vmode = "640x480_mono8";
00366 vmode_out = VIDEOMODE_640x480Y8;
00367 retVal &= false;
00368 }
00369
00370 return retVal;
00371 }
00372
00373 bool PointGreyCamera::getFormat7PixelFormatFromString(std::string &sformat, FlyCapture2::PixelFormat &fmt7PixFmt)
00374 {
00375
00376 bool retVal = true;
00377
00378
00379 CameraInfo cInfo;
00380 Error error = cam_.GetCameraInfo(&cInfo);
00381 PointGreyCamera::handleError("PointGreyCamera::getFormat7PixelFormatFromString Failed to get camera info.", error);
00382
00383 if(cInfo.isColorCamera)
00384 {
00385 if(sformat.compare("raw8") == 0)
00386 {
00387 fmt7PixFmt = PIXEL_FORMAT_RAW8;
00388 }
00389 else if(sformat.compare("raw16") == 0)
00390 {
00391 fmt7PixFmt = PIXEL_FORMAT_RAW16;
00392 }
00393 else if(sformat.compare("mono8") == 0)
00394 {
00395 fmt7PixFmt = PIXEL_FORMAT_MONO8;
00396 }
00397 else if(sformat.compare("mono16") == 0)
00398 {
00399 fmt7PixFmt = PIXEL_FORMAT_MONO16;
00400 }
00401 else
00402 {
00403 sformat = "raw8";
00404 fmt7PixFmt = PIXEL_FORMAT_RAW8;
00405 retVal &= false;
00406 }
00407 }
00408 else
00409 {
00410 if(sformat.compare("mono8") == 0)
00411 {
00412 fmt7PixFmt = PIXEL_FORMAT_MONO8;
00413 }
00414 else if(sformat.compare("mono16") == 0)
00415 {
00416 fmt7PixFmt = PIXEL_FORMAT_MONO16;
00417 }
00418 else
00419 {
00420 sformat = "mono8";
00421 fmt7PixFmt = PIXEL_FORMAT_MONO8;
00422 retVal &= false;
00423 }
00424 }
00425
00426 return retVal;
00427 }
00428
00429 bool PointGreyCamera::setProperty(const FlyCapture2::PropertyType &type, const bool &autoSet, unsigned int &valueA, unsigned int &valueB)
00430 {
00431
00432 bool retVal = true;
00433
00434 PropertyInfo pInfo;
00435 pInfo.type = type;
00436 Error error = cam_.GetPropertyInfo(&pInfo);
00437 PointGreyCamera::handleError("PointGreyCamera::setProperty Could not get property info.", error);
00438
00439 if(pInfo.present)
00440 {
00441 Property prop;
00442 prop.type = type;
00443 prop.autoManualMode = (autoSet && pInfo.autoSupported);
00444 prop.absControl = false;
00445 prop.onOff = pInfo.onOffSupported;
00446
00447 if(valueA < pInfo.min)
00448 {
00449 valueA = pInfo.min;
00450 retVal &= false;
00451 }
00452 else if(valueA > pInfo.max)
00453 {
00454 valueA = pInfo.max;
00455 retVal &= false;
00456 }
00457 if(valueB < pInfo.min)
00458 {
00459 valueB = pInfo.min;
00460 retVal &= false;
00461 }
00462 else if(valueB > pInfo.max)
00463 {
00464 valueB = pInfo.max;
00465 retVal &= false;
00466 }
00467 prop.valueA = valueA;
00468 prop.valueB = valueB;
00469 error = cam_.SetProperty(&prop);
00470 PointGreyCamera::handleError("PointGreyCamera::setProperty Failed to set property ", error);
00472
00473 error = cam_.GetProperty(&prop);
00474 PointGreyCamera::handleError("PointGreyCamera::setProperty Failed to confirm property ", error);
00475 if(!prop.autoManualMode)
00476 {
00477 valueA = prop.valueA;
00478 valueB = prop.valueB;
00479 }
00480 }
00481 else
00482 {
00483 valueA = 0;
00484 valueB = 0;
00485 }
00486
00487 return retVal;
00488 }
00489
00490 bool PointGreyCamera::setProperty(const FlyCapture2::PropertyType &type, const bool &autoSet, double &value)
00491 {
00492
00493 bool retVal = true;
00494
00495 PropertyInfo pInfo;
00496 pInfo.type = type;
00497 Error error = cam_.GetPropertyInfo(&pInfo);
00498 PointGreyCamera::handleError("PointGreyCamera::setProperty Could not get property info.", error);
00499
00500 if(pInfo.present)
00501 {
00502 Property prop;
00503 prop.type = type;
00504 prop.autoManualMode = (autoSet && pInfo.autoSupported);
00505 prop.absControl = pInfo.absValSupported;
00506 prop.onOff = pInfo.onOffSupported;
00507
00508 if(value < pInfo.absMin)
00509 {
00510 value = pInfo.absMin;
00511 retVal &= false;
00512 }
00513 else if(value > pInfo.absMax)
00514 {
00515 value = pInfo.absMax;
00516 retVal &= false;
00517 }
00518 prop.absValue = value;
00519 error = cam_.SetProperty(&prop);
00520 PointGreyCamera::handleError("PointGreyCamera::setProperty Failed to set property ", error);
00522
00523 error = cam_.GetProperty(&prop);
00524 PointGreyCamera::handleError("PointGreyCamera::setProperty Failed to confirm property ", error);
00525 if(!prop.autoManualMode)
00526 {
00527 value = prop.absValue;
00528 }
00529 }
00530 else
00531 {
00532 value = 0.0;
00533 }
00534 return retVal;
00535 }
00536
00537 bool PointGreyCamera::setWhiteBalance(bool &auto_white_balance, uint16_t &blue, uint16_t &red)
00538 {
00539
00540 CameraInfo cInfo;
00541 Error error = cam_.GetCameraInfo(&cInfo);
00542 handleError("PointGreyCamera::setWhiteBalance Failed to get camera info.", error);
00543
00544 if(!cInfo.isColorCamera)
00545 {
00546
00547 auto_white_balance = false;
00548 red = 0;
00549 blue = 0;
00550 return false;
00551 }
00552
00553 unsigned white_balance_addr = 0x80c;
00554 unsigned enable = 1 << 31;
00555 unsigned value = 1 << 25;
00556
00557 if (auto_white_balance) {
00558 PropertyInfo prop_info;
00559 prop_info.type = WHITE_BALANCE;
00560 error = cam_.GetPropertyInfo(&prop_info);
00561 handleError("PointGreyCamera::setWhiteBalance Failed to get property info.", error);
00562 if (!prop_info.autoSupported) {
00563
00564
00565 auto_white_balance = false;
00566 blue = 800;
00567 red = 550;
00568 return false;
00569 }
00570
00571 error = cam_.WriteRegister(white_balance_addr, enable);
00572 handleError("PointGreyCamera::setWhiteBalance Failed to write to register.", error);
00573 value |= 1 << 24;
00574 } else {
00575
00576 value |= blue << 12 | red;
00577 }
00578 error = cam_.WriteRegister(white_balance_addr, value);
00579 handleError("PointGreyCamera::setWhiteBalance Failed to write to register.", error);
00580 return true;
00581 }
00582
00583 void PointGreyCamera::setTimeout(const double &timeout)
00584 {
00585 FC2Config pConfig;
00586 Error error = cam_.GetConfiguration(&pConfig);
00587 PointGreyCamera::handleError("PointGreyCamera::setTimeout Could not get camera configuration", error);
00588 pConfig.grabTimeout = (int)(1000.0 * timeout);
00589 if(pConfig.grabTimeout < 0.00001)
00590 {
00591 pConfig.grabTimeout = -1;
00592 }
00593 error = cam_.SetConfiguration(&pConfig);
00594 PointGreyCamera::handleError("PointGreyCamera::setTimeout Could not set camera configuration", error);
00595 }
00596
00597 float PointGreyCamera::getCameraTemperature()
00598 {
00599 Property tProp;
00600 tProp.type = TEMPERATURE;
00601 Error error = cam_.GetProperty(&tProp);
00602 PointGreyCamera::handleError("PointGreyCamera::getCameraTemperature Could not get property.", error);
00603 return tProp.valueA / 10.0f - 273.15f;
00604 }
00605
00606 float PointGreyCamera::getCameraFrameRate()
00607 {
00608 Property fProp;
00609 fProp.type = FRAME_RATE;
00610 Error error = cam_.GetProperty(&fProp);
00611 PointGreyCamera::handleError("PointGreyCamera::getCameraFrameRate Could not get property.", error);
00612 std::cout << "Frame Rate is: " << fProp.absValue << std::endl;
00613 return fProp.absValue;
00614 }
00615
00616 static int sourceNumberFromGpioName(const std::string s)
00617 {
00618 if(s.compare("gpio0") == 0)
00619 {
00620 return 0;
00621 }
00622 else if(s.compare("gpio1") == 0)
00623 {
00624 return 1;
00625 }
00626 else if(s.compare("gpio2") == 0)
00627 {
00628 return 2;
00629 }
00630 else if(s.compare("gpio3") == 0)
00631 {
00632 return 3;
00633 }
00634 else
00635 {
00636
00637 return -1;
00638 }
00639 }
00640
00641 bool PointGreyCamera::setExternalStrobe(bool &enable, const std::string &dest, double &duration, double &delay, bool &polarityHigh)
00642 {
00643
00644 bool retVal = true;
00645
00646
00647 int pin;
00648 pin = sourceNumberFromGpioName(dest);
00649 if (pin < 0)
00650 {
00651
00652 return false;
00653 }
00654
00655 StrobeInfo strobeInfo;
00656 strobeInfo.source = pin;
00657 Error error = cam_.GetStrobeInfo(&strobeInfo);
00658 PointGreyCamera::handleError("PointGreyCamera::setExternalStrobe Could not check external strobe support.", error);
00659 if(strobeInfo.present != true)
00660 {
00661
00662 enable = false;
00663 return false;
00664 }
00665
00666 StrobeControl strobeControl;
00667 strobeControl.source = pin;
00668 error = cam_.GetStrobe(&strobeControl);
00669 PointGreyCamera::handleError("PointGreyCamera::setExternalStrobe Could not get strobe control.", error);
00670 strobeControl.duration = duration;
00671 strobeControl.delay = delay;
00672 strobeControl.onOff = enable;
00673 strobeControl.polarity = polarityHigh;
00674
00675 error = cam_.SetStrobe(&strobeControl);
00676 PointGreyCamera::handleError("PointGreyCamera::setExternalStrobe Could not set strobe control.", error);
00677 error = cam_.GetStrobe(&strobeControl);
00678 PointGreyCamera::handleError("PointGreyCamera::setExternalStrobe Could not get strobe control.", error);
00679 delay = strobeControl.delay;
00680 enable = strobeControl.onOff;
00681 polarityHigh = strobeControl.polarity;
00682
00683 return retVal;
00684 }
00685
00686 bool PointGreyCamera::setExternalTrigger(bool &enable, std::string &mode, std::string &source, int32_t ¶meter, double &delay, bool &polarityHigh)
00687 {
00688
00689 bool retVal = true;
00690
00691 TriggerModeInfo triggerModeInfo;
00692 Error error = cam_.GetTriggerModeInfo(&triggerModeInfo);
00693 PointGreyCamera::handleError("PointGreyCamera::setExternalTrigger Could not check external trigger support.", error);
00694 if(triggerModeInfo.present != true)
00695 {
00696
00697 enable = false;
00698 return false;
00699 }
00700
00701 TriggerMode triggerMode;
00702 error = cam_.GetTriggerMode(&triggerMode);
00703 PointGreyCamera::handleError("PointGreyCamera::setExternalTrigger Could not get trigger mode.", error);
00704 triggerMode.onOff = enable;
00705
00706
00707 std::string tmode = mode;
00708 if(tmode.compare("mode0") == 0)
00709 {
00710 triggerMode.mode = 0;
00711 }
00712 else if(tmode.compare("mode1") == 0)
00713 {
00714 triggerMode.mode = 1;
00715 }
00716 else if(tmode.compare("mode3") == 0)
00717 {
00718 triggerMode.mode = 3;
00719 }
00720 else if(tmode.compare("mode14") == 0)
00721 {
00722 triggerMode.mode = 14;
00723 }
00724 else
00725 {
00726
00727 triggerMode.mode = 0;
00728 mode = "mode0";
00729 retVal &= false;
00730 }
00731
00732
00733 triggerMode.parameter = parameter;
00734
00735
00736 std::string tsource = source;
00737 int pin = sourceNumberFromGpioName(tsource);
00738 if (pin < 0)
00739 {
00740
00741 triggerMode.source = 0;
00742 source = "gpio0";
00743 retVal &= false;
00744 }
00745 else
00746 {
00747 triggerMode.source = pin;
00748 }
00749
00750 triggerMode.polarity = polarityHigh;
00751
00752 error = cam_.SetTriggerMode(&triggerMode);
00753 PointGreyCamera::handleError("PointGreyCamera::setExternalTrigger Could not set trigger mode.", error);
00754 error = cam_.GetTriggerMode(&triggerMode);
00755 PointGreyCamera::handleError("PointGreyCamera::setExternalTrigger Could not get trigger mode.", error);
00756 enable = triggerMode.onOff;
00757 std::stringstream buff;
00758 buff << "mode" << triggerMode.mode;
00759 mode = buff.str();
00760
00763
00764 TriggerDelay triggerDelay;
00765 triggerDelay.type = TRIGGER_DELAY;
00766 triggerDelay.absControl = true;
00767 triggerDelay.absValue = delay;
00768 triggerDelay.onOff = true;
00769 error = cam_.SetTriggerDelay(&triggerDelay);
00770 PointGreyCamera::handleError("PointGreyCamera::setExternalTrigger Could not set trigger delay.", error);
00771 error = cam_.GetTriggerDelay(&triggerDelay);
00772 PointGreyCamera::handleError("PointGreyCamera::setExternalTrigger Could not get trigger delay.", error);
00773 delay = triggerDelay.absValue;
00774
00775 return retVal;
00776 }
00777
00778 void PointGreyCamera::setGigEParameters(bool auto_packet_size, unsigned int packet_size, unsigned int packet_delay)
00779 {
00780 auto_packet_size_ = auto_packet_size;
00781 packet_size_ = packet_size;
00782 packet_delay_ = packet_delay;
00783 }
00784
00785 void PointGreyCamera::setupGigEPacketSize(PGRGuid & guid)
00786 {
00787 GigECamera cam;
00788 Error error;
00789 error = cam.Connect(&guid);
00790 PointGreyCamera::handleError("PointGreyCamera::connect could not connect as GigE camera", error);
00791 unsigned int packet_size;
00792 error = cam.DiscoverGigEPacketSize(&packet_size);
00793 PointGreyCamera::handleError("PointGreyCamera::connect could not discover GigE packet_size", error);
00794 GigEProperty prop;
00795 prop.propType = PACKET_SIZE;
00796 error = cam.GetGigEProperty(&prop);
00797 PointGreyCamera::handleError("PointGreyCamera::connect could not get GigE packet_size", error);
00798 prop.value = packet_size;
00799 error = cam.SetGigEProperty(&prop);
00800 PointGreyCamera::handleError("PointGreyCamera::connect could not set GigE packet_size", error);
00801 }
00802
00803 void PointGreyCamera::setupGigEPacketSize(PGRGuid & guid, unsigned int packet_size)
00804 {
00805 GigECamera cam;
00806 Error error;
00807 error = cam.Connect(&guid);
00808 PointGreyCamera::handleError("PointGreyCamera::connect could not connect as GigE camera", error);
00809 GigEProperty prop;
00810 prop.propType = PACKET_SIZE;
00811 prop.value = packet_size;
00812 error = cam.SetGigEProperty(&prop);
00813 PointGreyCamera::handleError("PointGreyCamera::connect could not set GigE packet_size", error);
00814 }
00815
00816 void PointGreyCamera::setupGigEPacketDelay(PGRGuid & guid, unsigned int packet_delay)
00817 {
00818 GigECamera cam;
00819 Error error;
00820 error = cam.Connect(&guid);
00821 PointGreyCamera::handleError("PointGreyCamera::connect could not connect as GigE camera", error);
00822 GigEProperty prop;
00823 prop.propType = PACKET_DELAY;
00824 prop.value = packet_delay;
00825 error = cam.SetGigEProperty(&prop);
00826 PointGreyCamera::handleError("PointGreyCamera::connect could not set GigE packet_delay", error);
00827 }
00828
00829 void PointGreyCamera::connect()
00830 {
00831 if(!cam_.IsConnected())
00832 {
00833 Error error;
00834 PGRGuid guid;
00835 if(serial_ != 0)
00836 {
00837 error = busMgr_.GetCameraFromSerialNumber(serial_, &guid);
00838 std::stringstream serial_string;
00839 serial_string << serial_;
00840 std::string msg = "PointGreyCamera::connect Could not find camera with serial number: " + serial_string.str() + ". Is that camera plugged in?";
00841 PointGreyCamera::handleError(msg, error);
00842 }
00843 else
00844 {
00845 error = busMgr_.GetCameraFromIndex(0, &guid);
00846 PointGreyCamera::handleError("PointGreyCamera::connect Failed to get first connected camera", error);
00847 }
00848
00849 FlyCapture2::InterfaceType ifType;
00850 error = busMgr_.GetInterfaceTypeFromGuid(&guid, &ifType);
00851 PointGreyCamera::handleError("PointGreyCamera::connect Failed to get interface style of camera", error);
00852 if (ifType == FlyCapture2::INTERFACE_GIGE)
00853 {
00854
00855 if (auto_packet_size_)
00856 setupGigEPacketSize(guid);
00857 else
00858 setupGigEPacketSize(guid, packet_size_);
00859
00860
00861 setupGigEPacketDelay(guid, packet_delay_);
00862 }
00863
00864 error = cam_.Connect(&guid);
00865 PointGreyCamera::handleError("PointGreyCamera::connect Failed to connect to camera", error);
00866
00867
00868 CameraInfo cInfo;
00869 error = cam_.GetCameraInfo(&cInfo);
00870 PointGreyCamera::handleError("PointGreyCamera::connect Failed to get camera info.", error);
00871 isColor_ = cInfo.isColorCamera;
00872
00873
00874 EmbeddedImageInfo info;
00875 info.timestamp.onOff = true;
00876 info.gain.onOff = true;
00877 info.shutter.onOff = true;
00878 info.brightness.onOff = true;
00879 info.exposure.onOff = true;
00880 info.whiteBalance.onOff = true;
00881 info.frameCounter.onOff = true;
00882 info.ROIPosition.onOff = true;
00883 error = cam_.SetEmbeddedImageInfo(&info);
00884 PointGreyCamera::handleError("PointGreyCamera::connect Could not enable metadata", error);
00885 }
00886 }
00887
00888 void PointGreyCamera::disconnect()
00889 {
00890 boost::mutex::scoped_lock scopedLock(mutex_);
00891 captureRunning_ = false;
00892 if(cam_.IsConnected())
00893 {
00894 Error error = cam_.Disconnect();
00895 PointGreyCamera::handleError("PointGreyCamera::disconnect Failed to disconnect camera", error);
00896 }
00897 }
00898
00899 void PointGreyCamera::start()
00900 {
00901 if(cam_.IsConnected() && !captureRunning_)
00902 {
00903
00904 Error error = cam_.StartCapture();
00905 PointGreyCamera::handleError("PointGreyCamera::start Failed to start capture", error);
00906 captureRunning_ = true;
00907 }
00908 }
00909
00910 bool PointGreyCamera::stop()
00911 {
00912 if(cam_.IsConnected() && captureRunning_)
00913 {
00914
00915 captureRunning_ = false;
00916 Error error = cam_.StopCapture();
00917 PointGreyCamera::handleError("PointGreyCamera::stop Failed to stop capture", error);
00918 return true;
00919 }
00920 return false;
00921 }
00922
00923 void PointGreyCamera::grabImage(sensor_msgs::Image &image, const std::string &frame_id)
00924 {
00925 boost::mutex::scoped_lock scopedLock(mutex_);
00926 if(cam_.IsConnected() && captureRunning_)
00927 {
00928
00929 Image rawImage;
00930
00931 Error error = cam_.RetrieveBuffer(&rawImage);
00932 PointGreyCamera::handleError("PointGreyCamera::grabImage Failed to retrieve buffer", error);
00933 metadata_ = rawImage.GetMetadata();
00934
00935
00936 TimeStamp embeddedTime = rawImage.GetTimeStamp();
00937 image.header.stamp.sec = embeddedTime.seconds;
00938 image.header.stamp.nsec = 1000 * embeddedTime.microSeconds;
00939
00940
00941 uint8_t bitsPerPixel = rawImage.GetBitsPerPixel();
00942
00943
00944 std::string imageEncoding = sensor_msgs::image_encodings::MONO8;
00945 BayerTileFormat bayer_format = rawImage.GetBayerTileFormat();
00946 if(isColor_ && bayer_format != NONE)
00947 {
00948 if(bitsPerPixel == 16)
00949 {
00950 imageEncoding = sensor_msgs::image_encodings::MONO16;
00951 }
00952 else
00953 {
00954 switch(bayer_format)
00955 {
00956 case RGGB:
00957 imageEncoding = sensor_msgs::image_encodings::BAYER_RGGB8;
00958 break;
00959 case GRBG:
00960 imageEncoding = sensor_msgs::image_encodings::BAYER_GRBG8;
00961 break;
00962 case GBRG:
00963 imageEncoding = sensor_msgs::image_encodings::BAYER_GBRG8;
00964 break;
00965 case BGGR:
00966 imageEncoding = sensor_msgs::image_encodings::BAYER_BGGR8;
00967 break;
00968 }
00969 }
00970 }
00971 else
00972 {
00973 if(bitsPerPixel == 16)
00974 {
00975 imageEncoding = sensor_msgs::image_encodings::MONO16;
00976 }
00977 else
00978 {
00979 imageEncoding = sensor_msgs::image_encodings::MONO8;
00980 }
00981 }
00982
00983 fillImage(image, imageEncoding, rawImage.GetRows(), rawImage.GetCols(), rawImage.GetStride(), rawImage.GetData());
00984 image.header.frame_id = frame_id;
00985 }
00986 else if(cam_.IsConnected())
00987 {
00988 throw CameraNotRunningException("PointGreyCamera::grabImage: Camera is currently not running. Please start the capture.");
00989 }
00990 else
00991 {
00992 throw std::runtime_error("PointGreyCamera::grabImage not connected!");
00993 }
00994 }
00995
00996 void PointGreyCamera::grabStereoImage(sensor_msgs::Image &image, const std::string &frame_id, sensor_msgs::Image &second_image, const std::string &second_frame_id)
00997 {
00998 boost::mutex::scoped_lock scopedLock(mutex_);
00999 if(cam_.IsConnected() && captureRunning_)
01000 {
01001
01002 Image rawImage;
01003
01004 Error error = cam_.RetrieveBuffer(&rawImage);
01005 PointGreyCamera::handleError("PointGreyCamera::grabStereoImage Failed to retrieve buffer", error);
01006 metadata_ = rawImage.GetMetadata();
01007
01008
01009 TimeStamp embeddedTime = rawImage.GetTimeStamp();
01010 image.header.stamp.sec = embeddedTime.seconds;
01011 image.header.stamp.nsec = 1000 * embeddedTime.microSeconds;
01012
01013
01014
01015
01016
01017
01018 std::string imageEncoding = sensor_msgs::image_encodings::MONO8;
01019 BayerTileFormat bayer_format = rawImage.GetBayerTileFormat();
01020
01021 if(isColor_ && bayer_format != NONE)
01022 {
01023 switch(bayer_format)
01024 {
01025 case RGGB:
01026 imageEncoding = sensor_msgs::image_encodings::BAYER_RGGB8;
01027 break;
01028 case GRBG:
01029 imageEncoding = sensor_msgs::image_encodings::BAYER_GRBG8;
01030 break;
01031 case GBRG:
01032 imageEncoding = sensor_msgs::image_encodings::BAYER_GBRG8;
01033 break;
01034 case BGGR:
01035 imageEncoding = sensor_msgs::image_encodings::BAYER_BGGR8;
01036 break;
01037 }
01038 }
01039 else
01040 {
01041 imageEncoding = sensor_msgs::image_encodings::MONO8;
01042 }
01043
01044
01045 image.encoding = imageEncoding;
01046 second_image.encoding = imageEncoding;
01047 image.height = rawImage.GetRows();
01048 second_image.height = image.height;
01049 image.width = rawImage.GetCols();
01050 second_image.width = image.width;
01051 image.step = rawImage.GetStride() / 2;
01052 second_image.step = image.step;
01053 image.is_bigendian = 0;
01054 second_image.is_bigendian = 0;
01055 size_t st0 = (image.height * image.step);
01056 image.data.resize(st0);
01057 second_image.data.resize(st0);
01058 image.header.frame_id = frame_id;
01059 second_image.header.frame_id = second_frame_id;
01060
01061
01062 const uint8_t* raw_data = rawImage.GetData();
01063
01064
01065 for(size_t i = 0; i < rawImage.GetRows(); i++)
01066 {
01067 for(size_t j = 0; j < rawImage.GetCols(); j++)
01068 {
01069 size_t index = i * image.step + j;
01070 size_t raw_index = 2 * index;
01071 image.data[index] = raw_data[raw_index];
01072 second_image.data[index] = raw_data[raw_index + 1];
01073 }
01074 }
01075
01076
01077 }
01078 else if(cam_.IsConnected())
01079 {
01080 throw CameraNotRunningException("PointGreyCamera::grabStereoImage: Camera is currently not running. Please start the capture.");
01081 }
01082 else
01083 {
01084 throw std::runtime_error("PointGreyCamera::grabStereoImage not connected!");
01085 }
01086 }
01087
01088 uint PointGreyCamera::getGain()
01089 {
01090 return metadata_.embeddedGain >> 20;
01091 }
01092
01093 uint PointGreyCamera::getShutter()
01094 {
01095 return metadata_.embeddedShutter >> 20;
01096 }
01097
01098 uint PointGreyCamera::getBrightness()
01099 {
01100 return metadata_.embeddedTimeStamp >> 20;
01101 }
01102
01103 uint PointGreyCamera::getExposure()
01104 {
01105 return metadata_.embeddedBrightness >> 20;
01106 }
01107
01108 uint PointGreyCamera::getWhiteBalance()
01109 {
01110 return metadata_.embeddedExposure >> 8;
01111 }
01112
01113 uint PointGreyCamera::getROIPosition()
01114 {
01115 return metadata_.embeddedROIPosition >> 24;
01116 }
01117
01118 void PointGreyCamera::setDesiredCamera(const uint32_t &id)
01119 {
01120 serial_ = id;
01121 }
01122
01123 std::vector<uint32_t> PointGreyCamera::getAttachedCameras()
01124 {
01125 std::vector<uint32_t> cameras;
01126 unsigned int num_cameras;
01127 Error error = busMgr_.GetNumOfCameras(&num_cameras);
01128 PointGreyCamera::handleError("PointGreyCamera::getAttachedCameras: Could not get number of cameras", error);
01129 for(unsigned int i = 0; i < num_cameras; i++)
01130 {
01131 unsigned int this_serial;
01132 error = busMgr_.GetCameraSerialNumberFromIndex(i, &this_serial);
01133 PointGreyCamera::handleError("PointGreyCamera::getAttachedCameras: Could not get get serial number from index", error);
01134 cameras.push_back(this_serial);
01135 }
01136 return cameras;
01137 }
01138
01139 void PointGreyCamera::handleError(const std::string &prefix, const FlyCapture2::Error &error)
01140 {
01141 if(error == PGRERROR_TIMEOUT)
01142 {
01143 throw CameraTimeoutException("PointGreyCamera: Failed to retrieve buffer within timeout.");
01144 }
01145 else if(error != PGRERROR_OK)
01146 {
01147 std::string start(" | FlyCapture2::ErrorType ");
01148 std::stringstream out;
01149 out << error.GetType();
01150 std::string desc(error.GetDescription());
01151 throw std::runtime_error(prefix + start + out.str() + desc);
01152 }
01153 }