36 #include <flycapture/FlyCapture2Defs.h> 53 if(!
cam_.IsConnected())
59 boost::mutex::scoped_lock scopedLock(
mutex_);
74 if(vMode == VIDEOMODE_FORMAT7)
76 PixelFormat fmt7PixFmt;
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;
84 config.format7_roi_width = uwidth;
85 config.format7_roi_height = uheight;
86 config.format7_x_offset = uoffsetx;
87 config.format7_y_offset = uoffsety;
114 double shutter = 1000.0 * config.shutter_speed;
116 config.shutter_speed = shutter / 1000.0;
122 unsigned int pan = config.pan;
123 unsigned int not_used = 0;
128 unsigned int tilt = config.tilt;
139 uint16_t blue = config.white_balance_blue;
140 uint16_t red = config.white_balance_red;
142 config.white_balance_blue = blue;
143 config.white_balance_red = red;
146 switch (config.trigger_polarity)
148 case pointgrey_camera_driver::PointGrey_Low:
149 case pointgrey_camera_driver::PointGrey_High:
151 bool temp = config.trigger_polarity;
153 config.strobe1_polarity = temp;
161 switch (config.strobe1_polarity)
163 case pointgrey_camera_driver::PointGrey_Low:
164 case pointgrey_camera_driver::PointGrey_High:
166 bool temp = config.strobe1_polarity;
168 config.strobe1_polarity = temp;
176 switch (config.strobe2_polarity)
178 case pointgrey_camera_driver::PointGrey_Low:
179 case pointgrey_camera_driver::PointGrey_High:
181 bool temp = config.strobe2_polarity;
183 config.strobe2_polarity = temp;
207 FrameRate frameRate = FRAMERATE_7_5;
208 if(videoMode == VIDEOMODE_640x480Y8)
210 frameRate = FRAMERATE_30;
212 else if(videoMode == VIDEOMODE_1280x960Y8)
214 frameRate = FRAMERATE_15;
216 else if(videoMode == VIDEOMODE_1280x960Y16)
218 frameRate = FRAMERATE_7_5;
220 else if(videoMode == VIDEOMODE_FORMAT7)
222 frameRate = FRAMERATE_FORMAT7;
224 Error error =
cam_.SetVideoModeAndFrameRate(videoMode, frameRate);
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)
236 Format7Info fmt7Info;
238 fmt7Info.mode = fmt7Mode;
239 error =
cam_.GetFormat7Info(&fmt7Info, &supported);
243 throw std::runtime_error(
"PointGreyCamera::setFormat7 Format 7 mode not supported on this camera.");
247 Format7ImageSettings fmt7ImageSettings;
248 fmt7ImageSettings.mode = fmt7Mode;
249 fmt7ImageSettings.pixelFormat = fmt7PixFmt;
252 roi_width = roi_width / fmt7Info.imageHStepSize * fmt7Info.imageHStepSize;
255 fmt7ImageSettings.width = fmt7Info.maxWidth;
257 else if(roi_width > fmt7Info.maxWidth)
259 roi_width = fmt7Info.maxWidth;
260 fmt7ImageSettings.width = fmt7Info.maxWidth;
265 fmt7ImageSettings.width = roi_width;
269 roi_height = roi_height / fmt7Info.imageVStepSize * fmt7Info.imageVStepSize;
272 fmt7ImageSettings.height = fmt7Info.maxHeight;
274 else if(roi_height > fmt7Info.maxHeight)
276 roi_height = fmt7Info.maxHeight;
277 fmt7ImageSettings.height = fmt7Info.maxHeight;
282 fmt7ImageSettings.height = roi_height;
286 roi_offset_x = roi_offset_x / fmt7Info.offsetHStepSize * fmt7Info.offsetHStepSize;
287 if(roi_offset_x > (fmt7Info.maxWidth - fmt7ImageSettings.width))
289 roi_offset_x = fmt7Info.maxWidth - fmt7ImageSettings.width;
292 fmt7ImageSettings.offsetX = roi_offset_x;
295 roi_offset_y = roi_offset_y / fmt7Info.offsetVStepSize * fmt7Info.offsetVStepSize;
296 if(roi_offset_y > fmt7Info.maxHeight - fmt7ImageSettings.height)
298 roi_offset_y = fmt7Info.maxHeight - fmt7ImageSettings.height;
301 fmt7ImageSettings.offsetY = roi_offset_y;
304 Format7PacketInfo fmt7PacketInfo;
306 error =
cam_.ValidateFormat7Settings(&fmt7ImageSettings, &valid, &fmt7PacketInfo);
310 throw std::runtime_error(
"PointGreyCamera::setFormat7 Format 7 Settings Not Valid.");
314 error =
cam_.SetFormat7Configuration(&fmt7ImageSettings, fmt7PacketInfo.recommendedBytesPerPacket);
319 error =
cam_.GetCameraInfo(&cInfo);
333 Error error =
cam_.GetCameraInfo(&cInfo);
336 if(vmode.compare(
"640x480_mono8") == 0)
338 vmode_out = VIDEOMODE_640x480Y8;
340 else if(vmode.compare(
"640x480_mono16") == 0)
342 vmode_out = VIDEOMODE_640x480Y16;
344 else if(vmode.compare(
"1280x960_mono8") == 0)
346 vmode_out = VIDEOMODE_1280x960Y8;
347 if(cInfo.isColorCamera)
349 vmode =
"1280x960_bayer8";
353 else if(vmode.compare(
"1280x960_bayer8") == 0)
355 vmode_out = VIDEOMODE_1280x960Y8;
356 if(!cInfo.isColorCamera)
358 vmode =
"1280x960_mono8";
362 else if(vmode.compare(
"1280x960_mono16") == 0)
364 vmode_out = VIDEOMODE_1280x960Y16;
366 else if(vmode.compare(
"format7_mode0") == 0)
369 vmode_out = VIDEOMODE_FORMAT7;
371 else if(vmode.compare(
"format7_mode1") == 0)
374 vmode_out = VIDEOMODE_FORMAT7;
376 else if(vmode.compare(
"format7_mode2") == 0)
379 vmode_out = VIDEOMODE_FORMAT7;
381 else if(vmode.compare(
"format7_mode3") == 0)
384 vmode_out = VIDEOMODE_FORMAT7;
386 else if(vmode.compare(
"format7_mode4") == 0)
389 vmode_out = VIDEOMODE_FORMAT7;
391 else if(vmode.compare(
"format7_mode5") == 0)
394 vmode_out = VIDEOMODE_FORMAT7;
396 else if(vmode.compare(
"format7_mode7") == 0)
399 vmode_out = VIDEOMODE_FORMAT7;
403 vmode =
"640x480_mono8";
404 vmode_out = VIDEOMODE_640x480Y8;
418 Error error =
cam_.GetCameraInfo(&cInfo);
421 if(cInfo.isColorCamera)
423 if(sformat.compare(
"raw8") == 0)
425 fmt7PixFmt = PIXEL_FORMAT_RAW8;
427 else if(sformat.compare(
"raw16") == 0)
429 fmt7PixFmt = PIXEL_FORMAT_RAW16;
431 else if(sformat.compare(
"mono8") == 0)
433 fmt7PixFmt = PIXEL_FORMAT_MONO8;
435 else if(sformat.compare(
"mono16") == 0)
437 fmt7PixFmt = PIXEL_FORMAT_MONO16;
439 else if(sformat.compare(
"rgb8") == 0){
440 fmt7PixFmt = PIXEL_FORMAT_RGB;
445 fmt7PixFmt = PIXEL_FORMAT_RAW8;
451 if(sformat.compare(
"mono8") == 0)
453 fmt7PixFmt = PIXEL_FORMAT_MONO8;
455 else if(sformat.compare(
"mono16") == 0)
457 fmt7PixFmt = PIXEL_FORMAT_MONO16;
462 fmt7PixFmt = PIXEL_FORMAT_MONO8;
477 Error error =
cam_.GetPropertyInfo(&pInfo);
484 prop.autoManualMode = (autoSet && pInfo.autoSupported);
485 prop.absControl =
false;
486 prop.onOff = pInfo.onOffSupported;
488 if(valueA < pInfo.min)
493 else if(valueA > pInfo.max)
498 if(valueB < pInfo.min)
503 else if(valueB > pInfo.max)
508 prop.valueA = valueA;
509 prop.valueB = valueB;
510 error =
cam_.SetProperty(&prop);
514 error =
cam_.GetProperty(&prop);
516 if(!prop.autoManualMode)
518 valueA = prop.valueA;
519 valueB = prop.valueB;
538 Error error =
cam_.GetPropertyInfo(&pInfo);
545 prop.autoManualMode = (autoSet && pInfo.autoSupported);
546 prop.absControl = pInfo.absValSupported;
547 prop.onOff = pInfo.onOffSupported;
549 if(value < pInfo.absMin)
551 value = pInfo.absMin;
554 else if(value > pInfo.absMax)
556 value = pInfo.absMax;
559 prop.absValue = value;
560 error =
cam_.SetProperty(&prop);
564 error =
cam_.GetProperty(&prop);
566 if(!prop.autoManualMode)
568 value = prop.absValue;
582 Error error =
cam_.GetCameraInfo(&cInfo);
583 handleError(
"PointGreyCamera::setWhiteBalance Failed to get camera info.", error);
585 if(!cInfo.isColorCamera)
588 auto_white_balance =
false;
594 unsigned white_balance_addr = 0x80c;
595 unsigned enable = 1 << 31;
596 unsigned value = 1 << 25;
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) {
606 auto_white_balance =
false;
612 error =
cam_.WriteRegister(white_balance_addr, enable);
613 handleError(
"PointGreyCamera::setWhiteBalance Failed to write to register.", error);
621 value |= blue << 12 | red;
622 error =
cam_.WriteRegister(white_balance_addr, value);
623 handleError(
"PointGreyCamera::setWhiteBalance Failed to write to register.", error);
630 Error error =
cam_.GetConfiguration(&pConfig);
632 pConfig.grabTimeout = (int)(1000.0 * timeout);
633 if(pConfig.grabTimeout < 0.00001)
635 pConfig.grabTimeout = -1;
637 error =
cam_.SetConfiguration(&pConfig);
644 tProp.type = TEMPERATURE;
647 return tProp.valueA / 10.0f - 273.15f;
653 fProp.type = FRAME_RATE;
656 std::cout <<
"Frame Rate is: " << fProp.absValue << std::endl;
657 return fProp.absValue;
662 if(s.compare(
"gpio0") == 0)
666 else if(s.compare(
"gpio1") == 0)
670 else if(s.compare(
"gpio2") == 0)
674 else if(s.compare(
"gpio3") == 0)
699 StrobeInfo strobeInfo;
700 strobeInfo.source = pin;
701 Error error =
cam_.GetStrobeInfo(&strobeInfo);
703 if(strobeInfo.present !=
true)
710 StrobeControl strobeControl;
711 strobeControl.source = pin;
712 error =
cam_.GetStrobe(&strobeControl);
714 strobeControl.duration = duration;
715 strobeControl.delay = delay;
716 strobeControl.onOff = enable;
717 strobeControl.polarity = polarityHigh;
719 error =
cam_.SetStrobe(&strobeControl);
721 error =
cam_.GetStrobe(&strobeControl);
723 delay = strobeControl.delay;
724 enable = strobeControl.onOff;
725 polarityHigh = strobeControl.polarity;
735 TriggerModeInfo triggerModeInfo;
736 Error error =
cam_.GetTriggerModeInfo(&triggerModeInfo);
738 if(triggerModeInfo.present !=
true)
745 TriggerMode triggerMode;
746 error =
cam_.GetTriggerMode(&triggerMode);
748 triggerMode.onOff = enable;
751 std::string tmode = mode;
752 if(tmode.compare(
"mode0") == 0)
754 triggerMode.mode = 0;
756 else if(tmode.compare(
"mode1") == 0)
758 triggerMode.mode = 1;
760 else if(tmode.compare(
"mode3") == 0)
762 triggerMode.mode = 3;
764 else if(tmode.compare(
"mode14") == 0)
766 triggerMode.mode = 14;
771 triggerMode.mode = 0;
777 triggerMode.parameter = parameter;
780 std::string tsource = source;
785 triggerMode.source = 0;
791 triggerMode.source = pin;
794 triggerMode.polarity = polarityHigh;
796 error =
cam_.SetTriggerMode(&triggerMode);
798 error =
cam_.GetTriggerMode(&triggerMode);
800 enable = triggerMode.onOff;
801 std::stringstream buff;
802 buff <<
"mode" << triggerMode.mode;
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);
815 error =
cam_.GetTriggerDelay(&triggerDelay);
817 delay = triggerDelay.absValue;
833 error = cam.Connect(&guid);
835 unsigned int packet_size;
836 error = cam.DiscoverGigEPacketSize(&packet_size);
839 prop.propType = PACKET_SIZE;
840 error = cam.GetGigEProperty(&prop);
842 prop.value = packet_size;
843 error = cam.SetGigEProperty(&prop);
851 error = cam.Connect(&guid);
854 prop.propType = PACKET_SIZE;
855 prop.value = packet_size;
856 error = cam.SetGigEProperty(&prop);
864 error = cam.Connect(&guid);
867 prop.propType = PACKET_DELAY;
868 prop.value = packet_delay;
869 error = cam.SetGigEProperty(&prop);
875 if(!
cam_.IsConnected())
882 std::stringstream serial_string;
884 std::string
msg =
"PointGreyCamera::connect Could not find camera with serial number: " + serial_string.str() +
". Is that camera plugged in?";
889 error =
busMgr_.GetCameraFromIndex(0, &guid);
893 FlyCapture2::InterfaceType ifType;
894 error =
busMgr_.GetInterfaceTypeFromGuid(&guid, &ifType);
896 if (ifType == FlyCapture2::INTERFACE_GIGE)
910 error = cam.Connect(&guid);
912 GigEConfig gigeconfig;
913 error = cam.GetGigEConfig(&gigeconfig);
915 gigeconfig.enablePacketResend =
true;
916 error = cam.SetGigEConfig(&gigeconfig);
920 error =
cam_.Connect(&guid);
925 error =
cam_.GetCameraInfo(&cInfo);
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);
946 boost::mutex::scoped_lock scopedLock(
mutex_);
948 if(
cam_.IsConnected())
981 boost::mutex::scoped_lock scopedLock(
mutex_);
987 Error error =
cam_.RetrieveBuffer(&rawImage);
992 TimeStamp embeddedTime = rawImage.GetTimeStamp();
993 image.header.stamp.sec = embeddedTime.seconds;
994 image.header.stamp.nsec = 1000 * embeddedTime.microSeconds;
997 uint8_t bitsPerPixel = rawImage.GetBitsPerPixel();
1001 BayerTileFormat bayer_format = rawImage.GetBayerTileFormat();
1004 if(bitsPerPixel == 16)
1006 switch(bayer_format)
1024 switch(bayer_format)
1043 if(bitsPerPixel == 16)
1047 else if(bitsPerPixel==24)
1057 fillImage(image, imageEncoding, rawImage.GetRows(), rawImage.GetCols(), rawImage.GetStride(), rawImage.GetData());
1058 image.header.frame_id = frame_id;
1060 else if(
cam_.IsConnected())
1062 throw CameraNotRunningException(
"PointGreyCamera::grabImage: Camera is currently not running. Please start the capture.");
1066 throw std::runtime_error(
"PointGreyCamera::grabImage not connected!");
1072 boost::mutex::scoped_lock scopedLock(
mutex_);
1078 Error error =
cam_.RetrieveBuffer(&rawImage);
1083 TimeStamp embeddedTime = rawImage.GetTimeStamp();
1084 image.header.stamp.sec = embeddedTime.seconds;
1085 image.header.stamp.nsec = 1000 * embeddedTime.microSeconds;
1093 BayerTileFormat bayer_format = rawImage.GetBayerTileFormat();
1097 switch(bayer_format)
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;
1136 const uint8_t* raw_data = rawImage.GetData();
1139 for(
size_t i = 0; i < rawImage.GetRows(); i++)
1141 for(
size_t j = 0; j < rawImage.GetCols(); j++)
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];
1152 else if(
cam_.IsConnected())
1154 throw CameraNotRunningException(
"PointGreyCamera::grabStereoImage: Camera is currently not running. Please start the capture.");
1158 throw std::runtime_error(
"PointGreyCamera::grabStereoImage not connected!");
1174 return metadata_.embeddedTimeStamp >> 20;
1179 return metadata_.embeddedBrightness >> 20;
1189 return metadata_.embeddedROIPosition >> 24;
1199 std::vector<uint32_t> cameras;
1200 unsigned int num_cameras;
1203 for(
unsigned int i = 0; i < num_cameras; i++)
1205 unsigned int this_serial;
1206 error =
busMgr_.GetCameraSerialNumberFromIndex(i, &this_serial);
1208 cameras.push_back(this_serial);
1215 if(error == PGRERROR_TIMEOUT)
1219 else if(error == PGRERROR_IMAGE_CONSISTENCY_ERROR)
1223 else if(error != PGRERROR_OK)
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);
const std::string BAYER_GRBG8
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)
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 ¶meter, 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'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.
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.