60 #define CAM_EXCEPT(except, msg) \ 63 snprintf(buf, 100, "[Camera1394::%s]: " msg, __FUNCTION__); \ 68 #define CAM_EXCEPT_ARGS(except, msg, ...) \ 71 snprintf(buf, 100, "[Camera1394::%s]: " msg, __FUNCTION__, __VA_ARGS__); \ 93 BayerPattern_ = (dc1394color_filter_t) DC1394_COLOR_FILTER_NUM;
94 if (0 == strcmp(bayer,
"bggr"))
98 else if (0 == strcmp(bayer,
"grbg"))
102 else if (0 == strcmp(bayer,
"rggb"))
106 else if (0 == strcmp(bayer,
"gbrg"))
110 else if (0 != strcmp(bayer,
""))
112 ROS_ERROR(
"unknown bayer pattern [%s]", bayer);
119 bool DoBayer =
false;
120 if (0 != strcmp(method,
"")
125 ROS_WARN(
"[%s] Bayer decoding in the driver is DEPRECATED;" 126 " image_proc decoding preferred.", method);
129 if (!strcmp(method,
"DownSample"))
131 else if (!strcmp(method,
"Simple"))
133 else if (!strcmp(method,
"Bilinear"))
135 else if (!strcmp(method,
"HQ"))
137 else if (!strcmp(method,
"VNG"))
139 else if (!strcmp(method,
"AHD"))
143 ROS_ERROR(
"Unknown Bayer method [%s]. Using ROS image_proc instead.",
167 const static size_t exact_guid_length = 16;
168 size_t guid_length = newconfig.guid.length();
169 if (guid_length != 0 && guid_length != exact_guid_length)
171 if (guid_length < exact_guid_length)
174 newconfig.guid.insert(0, exact_guid_length - guid_length,
'0');
179 <<
"] specified: " << guid_length
180 <<
" characters long.");
188 const char *guid = newconfig.guid.c_str();
191 dc1394camera_list_t *list;
198 "Could not initialize dc1394_context.\n" 199 "Make sure /dev/raw1394 exists, you have access permission,\n" 200 "and libraw1394 development package is installed.");
203 err = dc1394_camera_enumerate(d, &list);
204 if (err != DC1394_SUCCESS)
206 CAM_EXCEPT(camera1394::Exception,
"Could not get camera list");
212 CAM_EXCEPT(camera1394::Exception,
"No cameras found");
216 char* temp=(
char*)malloc(1024*
sizeof(
char));
217 for (
unsigned i=0; i < list->num; i++)
221 value[0]= list->ids[i].guid & 0xffffffff;
222 value[1]= (list->ids[i].guid >>32) & 0x000000ff;
223 value[2]= (list->ids[i].guid >>40) & 0xfffff;
225 sprintf(temp,
"%06x%02x%08x", value[2], value[1], value[0]);
231 << std::setw(16) << std::setfill(
'0') << std::hex
232 << list->ids[i].guid);
236 ROS_WARN(
"Comparing %s to %s", guid, temp);
237 if (strcmp(temp, guid))
245 camera_ = dc1394_camera_new (d, list->ids[i].guid);
249 << std::setw(16) << std::setfill(
'0') << std::hex
250 << list->ids[i].guid);
258 << std::setw(16) << std::setfill(
'0') << std::hex
259 << list->ids[i].guid);
266 dc1394_camera_free_list (list);
270 if (strcmp(guid,
"")==0)
272 CAM_EXCEPT(camera1394::Exception,
"Could not find camera");
277 "Could not find camera with guid %s", guid);
290 if (newconfig.reset_on_open
291 && DC1394_SUCCESS != dc1394_camera_reset(
camera_))
294 ROS_WARN(
"Unable to reset camera (continuing).");
302 "Unable to set ISO speed; is the camera plugged in?");
311 CAM_EXCEPT(camera1394::Exception,
"Failed to set video mode");
321 if (dc1394_is_video_mode_scalable(
videoMode_) == DC1394_TRUE)
327 CAM_EXCEPT(camera1394::Exception,
"Format7 start failed");
338 CAM_EXCEPT(camera1394::Exception,
"Failed to set frame rate");
353 if (DC1394_SUCCESS != dc1394_capture_setup(
camera_, newconfig.num_dma_buffers,
354 DC1394_CAPTURE_FLAGS_DEFAULT))
357 CAM_EXCEPT(camera1394::Exception,
"Failed to open device!");
362 if (DC1394_SUCCESS != dc1394_video_set_transmission(
camera_, DC1394_ON))
365 CAM_EXCEPT(camera1394::Exception,
"Failed to start device!");
390 dc1394_camera_set_power(
camera_, DC1394_OFF);
402 if (DC1394_SUCCESS != dc1394_video_set_transmission(
camera_, DC1394_OFF)
403 || DC1394_SUCCESS != dc1394_capture_stop(
camera_))
413 std::string
bayer_string(dc1394color_filter_t pattern,
unsigned int bits)
419 case DC1394_COLOR_FILTER_RGGB:
421 case DC1394_COLOR_FILTER_GBRG:
423 case DC1394_COLOR_FILTER_GRBG:
425 case DC1394_COLOR_FILTER_BGGR:
435 case DC1394_COLOR_FILTER_RGGB:
437 case DC1394_COLOR_FILTER_GBRG:
439 case DC1394_COLOR_FILTER_GRBG:
441 case DC1394_COLOR_FILTER_BGGR:
457 dc1394video_frame_t * frame = NULL;
461 dc1394_capture_dequeue (
camera_, DC1394_CAPTURE_POLICY_POLL, &frame);
462 if (!frame)
return false;
467 dc1394_capture_dequeue (
camera_, DC1394_CAPTURE_POLICY_WAIT, &frame);
470 CAM_EXCEPT(camera1394::Exception,
"Unable to capture frame");
475 uint8_t* capture_buffer;
480 image.header.stamp =
ros::Time((
double) frame->timestamp / 1000000.0);
482 dc1394video_frame_t frame2;
487 size_t frame2_size = (frame->size[0] * frame->size[1]
488 * 3 *
sizeof(
unsigned char));
489 frame2.image = (
unsigned char *) malloc(frame2_size);
490 frame2.allocated_image_bytes = frame2_size;
491 frame2.color_coding = DC1394_COLOR_CODING_RGB8;
494 int err = dc1394_debayer_frames(frame, &frame2,
BayerMethod_);
495 if (err != DC1394_SUCCESS)
498 dc1394_capture_enqueue(
camera_, frame);
499 CAM_EXCEPT(camera1394::Exception,
"Could not convert/debayer frames");
503 capture_buffer =
reinterpret_cast<uint8_t *
>(frame2.image);
505 image.width = frame2.size[0];
506 image.height = frame2.size[1];
510 image.width = frame->size[0];
511 image.height = frame->size[1];
512 capture_buffer =
reinterpret_cast<uint8_t *
>(frame->image);
520 case DC1394_VIDEO_MODE_160x120_YUV444:
521 image.step=image.width*3;
522 image_size = image.height*image.step;
524 image.data.resize(image_size);
525 yuv::uyv2rgb(reinterpret_cast<unsigned char *> (capture_buffer),
526 reinterpret_cast<unsigned char *> (&image.data[0]),
527 image.width * image.height);
529 case DC1394_VIDEO_MODE_640x480_YUV411:
530 image.step=image.width*3;
531 image_size = image.height*image.step;
533 image.data.resize(image_size);
535 reinterpret_cast<unsigned char *> (&image.data[0]),
536 image.width * image.height);
538 case DC1394_VIDEO_MODE_320x240_YUV422:
539 case DC1394_VIDEO_MODE_640x480_YUV422:
540 case DC1394_VIDEO_MODE_800x600_YUV422:
541 case DC1394_VIDEO_MODE_1024x768_YUV422:
542 case DC1394_VIDEO_MODE_1280x960_YUV422:
543 case DC1394_VIDEO_MODE_1600x1200_YUV422:
544 image.step=image.width*3;
545 image_size = image.height*image.step;
547 image.data.resize(image_size);
548 yuv::uyvy2rgb(reinterpret_cast<unsigned char *> (capture_buffer),
549 reinterpret_cast<unsigned char *> (&image.data[0]),
550 image.width * image.height);
552 case DC1394_VIDEO_MODE_640x480_RGB8:
553 case DC1394_VIDEO_MODE_800x600_RGB8:
554 case DC1394_VIDEO_MODE_1024x768_RGB8:
555 case DC1394_VIDEO_MODE_1280x960_RGB8:
556 case DC1394_VIDEO_MODE_1600x1200_RGB8:
557 image.step=image.width*3;
558 image_size = image.height*image.step;
560 image.data.resize(image_size);
561 memcpy(&image.data[0], capture_buffer, image_size);
563 case DC1394_VIDEO_MODE_640x480_MONO8:
564 case DC1394_VIDEO_MODE_800x600_MONO8:
565 case DC1394_VIDEO_MODE_1024x768_MONO8:
566 case DC1394_VIDEO_MODE_1280x960_MONO8:
567 case DC1394_VIDEO_MODE_1600x1200_MONO8:
570 image.step=image.width;
571 image_size = image.height*image.step;
574 image.data.resize(image_size);
575 memcpy(&image.data[0], capture_buffer, image_size);
579 image.step=image.width*3;
580 image_size = image.height*image.step;
582 image.data.resize(image_size);
583 memcpy(&image.data[0], capture_buffer, image_size);
586 case DC1394_VIDEO_MODE_640x480_MONO16:
587 case DC1394_VIDEO_MODE_800x600_MONO16:
588 case DC1394_VIDEO_MODE_1024x768_MONO16:
589 case DC1394_VIDEO_MODE_1280x960_MONO16:
590 case DC1394_VIDEO_MODE_1600x1200_MONO16:
593 image.step=image.width*2;
594 image_size = image.height*image.step;
596 image.is_bigendian =
true;
597 image.data.resize(image_size);
598 memcpy(&image.data[0], capture_buffer, image_size);
603 image.step=image.width*3;
604 image_size = image.height*image.step;
606 image.data.resize(image_size);
607 memcpy(&image.data[0], capture_buffer, image_size);
611 if (dc1394_is_video_mode_scalable(
videoMode_))
617 CAM_EXCEPT(camera1394::Exception,
"Unknown image mode");
621 dc1394_capture_enqueue(
camera_, frame);
624 free(capture_buffer);
const std::string BAYER_GRBG8
dc1394video_mode_t videoMode_
const std::string BAYER_GRBG16
libdc1394 enumerated modes interface
#define CAM_EXCEPT_ARGS(except, msg,...)
Macro for throwing an exception with a message, passing args.
const std::string BAYER_RGGB16
#define CAM_EXCEPT(except, msg)
Macro for throwing an exception with a message.
void uyvy2rgb(unsigned char *src, unsigned char *dest, unsigned long long int NumPixels)
bool readData(sensor_msgs::Image &image)
bool setIsoSpeed(dc1394camera_t *camera, int &iso_speed)
dc1394color_filter_t BayerPattern_
const std::string BAYER_GBRG8
const std::string BAYER_GBRG16
std::string bayer_string(dc1394color_filter_t pattern, unsigned int bits)
const std::string BAYER_BGGR16
bool findBayerMethod(const char *)
#define ROS_ASSERT_MSG(cond,...)
YUV to RGB conversion functions.
dc1394bayer_method_t BayerMethod_
void findBayerPattern(const char *)
Camera1394 Features class.
#define ROS_WARN_STREAM(args)
boost::shared_ptr< Registers > registers_
const std::string BAYER_BGGR8
int open(camera1394::Camera1394Config &newconfig)
boost::shared_ptr< Features > features_
#define ROS_INFO_STREAM(args)
bool setFrameRate(dc1394camera_t *camera, dc1394video_mode_t video_mode, double &frame_rate)
void uyyvyy2rgb(const unsigned char *src, unsigned char *dest, unsigned long long int NumPixels)
IEEE 1394 digital camera library interface.
const std::string BAYER_RGGB8
#define ROS_ERROR_STREAM_THROTTLE(rate, args)
Camera1394 features interface.
dc1394video_mode_t getVideoMode(dc1394camera_t *camera, std::string &video_mode)
void uyv2rgb(const unsigned char *src, unsigned char *dest, unsigned long long int NumPixels)