00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00032
00033
00034
00049 #include <stdint.h>
00050
00051 #include "yuv.h"
00052 #include <sensor_msgs/image_encodings.h>
00053 #include "dev_camera1394.h"
00054 #include "features.h"
00055 #include "modes.h"
00056
00057 #define NUM_DMA_BUFFERS 4
00058
00059
00061 #define CAM_EXCEPT(except, msg) \
00062 { \
00063 char buf[100]; \
00064 snprintf(buf, 100, "[Camera1394::%s]: " msg, __FUNCTION__); \
00065 throw except(buf); \
00066 }
00067
00069 #define CAM_EXCEPT_ARGS(except, msg, ...) \
00070 { \
00071 char buf[100]; \
00072 snprintf(buf, 100, "[Camera1394::%s]: " msg, __FUNCTION__, __VA_ARGS__); \
00073 throw except(buf); \
00074 }
00075
00076
00077 using namespace camera1394;
00078
00080
00081 Camera1394::Camera1394():
00082 camera_(NULL)
00083 {}
00084
00085 Camera1394::~Camera1394()
00086 {
00087 SafeCleanup();
00088 }
00089
00090 void Camera1394::findBayerPattern(const char* bayer)
00091 {
00092
00093
00094 BayerPattern_ = (dc1394color_filter_t) DC1394_COLOR_FILTER_NUM;
00095 if (0 == strcmp(bayer, "bggr"))
00096 {
00097 BayerPattern_ = DC1394_COLOR_FILTER_BGGR;
00098 }
00099 else if (0 == strcmp(bayer, "grbg"))
00100 {
00101 BayerPattern_ = DC1394_COLOR_FILTER_GRBG;
00102 }
00103 else if (0 == strcmp(bayer, "rggb"))
00104 {
00105 BayerPattern_ = DC1394_COLOR_FILTER_RGGB;
00106 }
00107 else if (0 == strcmp(bayer, "gbrg"))
00108 {
00109 BayerPattern_ = DC1394_COLOR_FILTER_GBRG;
00110 }
00111 else if (0 != strcmp(bayer, ""))
00112 {
00113 ROS_ERROR("unknown bayer pattern [%s]", bayer);
00114 }
00115 }
00116
00117 bool Camera1394::findBayerMethod(const char* method)
00118 {
00119
00120 bool DoBayer = false;
00121 if (0 != strcmp(method, "")
00122 && BayerPattern_ != DC1394_COLOR_FILTER_NUM)
00123 {
00124 DoBayer = true;
00125
00126 ROS_WARN("[%s] Bayer decoding in the driver is DEPRECATED;"
00127 " image_proc decoding preferred.", method);
00128
00129
00130 if (!strcmp(method, "DownSample"))
00131 BayerMethod_ = DC1394_BAYER_METHOD_DOWNSAMPLE;
00132 else if (!strcmp(method, "Simple"))
00133 BayerMethod_ = DC1394_BAYER_METHOD_SIMPLE;
00134 else if (!strcmp(method, "Bilinear"))
00135 BayerMethod_ = DC1394_BAYER_METHOD_BILINEAR;
00136 else if (!strcmp(method, "HQ"))
00137 BayerMethod_ = DC1394_BAYER_METHOD_HQLINEAR;
00138 else if (!strcmp(method, "VNG"))
00139 BayerMethod_ = DC1394_BAYER_METHOD_VNG;
00140 else if (!strcmp(method, "AHD"))
00141 BayerMethod_ = DC1394_BAYER_METHOD_AHD;
00142 else
00143 {
00144 ROS_ERROR("Unknown Bayer method [%s]. Using ROS image_proc instead.",
00145 method);
00146 DoBayer = false;
00147 }
00148 }
00149 return DoBayer;
00150 }
00151
00162 int Camera1394::open(camera1394::Camera1394Config &newconfig)
00163 {
00165
00167
00168 const char *guid = newconfig.guid.c_str();
00169 int err;
00170 dc1394_t *d;
00171 dc1394camera_list_t *list;
00172
00173
00174 d = dc1394_new ();
00175 if (d == NULL)
00176 {
00177 CAM_EXCEPT(camera1394::Exception,
00178 "Could not initialize dc1394_context.\n"
00179 "Make sure /dev/raw1394 exists, you have access permission,\n"
00180 "and libraw1394 development package is installed.");
00181 }
00182
00183 err = dc1394_camera_enumerate(d, &list);
00184 if (err != DC1394_SUCCESS)
00185 {
00186 CAM_EXCEPT(camera1394::Exception, "Could not get camera list");
00187 return -1;
00188 }
00189
00190 if (list->num == 0)
00191 {
00192 CAM_EXCEPT(camera1394::Exception, "No cameras found");
00193 return -1;
00194 }
00195
00196 char* temp=(char*)malloc(1024*sizeof(char));
00197 for (unsigned i=0; i < list->num; i++)
00198 {
00199
00200 camera_ = dc1394_camera_new (d, list->ids[i].guid);
00201 if (!camera_)
00202 ROS_WARN_STREAM("Failed to initialize camera with GUID "
00203 << std::hex << list->ids[i].guid);
00204 else
00205 ROS_INFO_STREAM("Found camera with GUID "
00206 << std::hex << list->ids[i].guid);
00207
00208 uint32_t value[3];
00209
00210 value[0]= camera_->guid & 0xffffffff;
00211 value[1]= (camera_->guid >>32) & 0x000000ff;
00212 value[2]= (camera_->guid >>40) & 0xfffff;
00213
00214 sprintf(temp,"%06x%02x%08x", value[2], value[1], value[0]);
00215
00216 if (strcmp(guid,"")==0)
00217 {
00218 ROS_INFO_STREAM("No guid specified, using first camera found, GUID: "
00219 << std::hex << camera_->guid);
00220 device_id_ = std::string(temp);
00221 break;
00222 }
00223
00224 ROS_DEBUG("Comparing %s to %s",guid,temp);
00225 if (strcmp(temp,guid)==0)
00226 {
00227 device_id_=guid;
00228 break;
00229 }
00230 SafeCleanup();
00231 }
00232 free (temp);
00233 dc1394_camera_free_list (list);
00234
00235 if (!camera_)
00236 {
00237 if (strcmp(guid,"")==0)
00238 {
00239 CAM_EXCEPT(camera1394::Exception, "Could not find camera");
00240 }
00241 else
00242 {
00243 CAM_EXCEPT_ARGS(camera1394::Exception,
00244 "Could not find camera with guid %s", guid);
00245 }
00246 return -1;
00247 }
00248
00249 ROS_INFO_STREAM("camera model: " << camera_->vendor
00250 << " " << camera_->model);
00251
00253
00255
00256
00257 if (newconfig.reset_on_open
00258 && DC1394_SUCCESS != dc1394_camera_reset(camera_))
00259 {
00260
00261 ROS_WARN("Unable to reset camera (continuing).");
00262 }
00263
00264
00265 if (false == Modes::setIsoSpeed(camera_, newconfig.iso_speed))
00266 {
00267 SafeCleanup();
00268 CAM_EXCEPT(camera1394::Exception,
00269 "Unable to set ISO speed; is the camera plugged in?");
00270 return -1;
00271 }
00272
00273
00274 videoMode_ = Modes::getVideoMode(camera_, newconfig.video_mode);
00275 if (DC1394_SUCCESS != dc1394_video_set_mode(camera_, videoMode_))
00276 {
00277 SafeCleanup();
00278 CAM_EXCEPT(camera1394::Exception, "Failed to set video mode");
00279 return -1;
00280 }
00281
00283
00285
00286 DoBayerConversion_ = false;
00287
00288 if (dc1394_is_video_mode_scalable(videoMode_) == DC1394_TRUE)
00289 {
00290
00291 if (!format7_.start(camera_, videoMode_, newconfig))
00292 {
00293 SafeCleanup();
00294 CAM_EXCEPT(camera1394::Exception, "Format7 start failed");
00295 return -1;
00296 }
00297 }
00298 else
00299 {
00300
00301 DoBayerConversion_ = findBayerMethod(newconfig.bayer_method.c_str());
00302 if (!Modes::setFrameRate(camera_, videoMode_, newconfig.frame_rate))
00303 {
00304 SafeCleanup();
00305 CAM_EXCEPT(camera1394::Exception, "Failed to set frame rate");
00306 return -1;
00307 }
00308 }
00309
00310 findBayerPattern(newconfig.bayer_pattern.c_str());
00311
00312 use_ros_time_ = newconfig.use_ros_time;
00313
00315
00317
00318
00319 if (DC1394_SUCCESS != dc1394_capture_setup(camera_, NUM_DMA_BUFFERS,
00320 DC1394_CAPTURE_FLAGS_DEFAULT))
00321 {
00322 SafeCleanup();
00323 CAM_EXCEPT(camera1394::Exception, "Failed to open device!");
00324 return -1;
00325 }
00326
00327
00328 if (DC1394_SUCCESS != dc1394_video_set_transmission(camera_, DC1394_ON))
00329 {
00330 SafeCleanup();
00331 CAM_EXCEPT(camera1394::Exception, "Failed to start device!");
00332 return -1;
00333 }
00334
00336
00338
00339
00340 features_.reset(new Features(camera_));
00341
00342 return 0;
00343 }
00344
00345
00347 void Camera1394::SafeCleanup()
00348 {
00349 if (camera_)
00350 {
00351 format7_.stop();
00352 dc1394_capture_stop(camera_);
00353 dc1394_camera_free(camera_);
00354 camera_ = NULL;
00355 }
00356 }
00357
00358
00360 int Camera1394::close()
00361 {
00362 if (camera_)
00363 {
00364 if (DC1394_SUCCESS != dc1394_video_set_transmission(camera_, DC1394_OFF)
00365 || DC1394_SUCCESS != dc1394_capture_stop(camera_))
00366 ROS_WARN("unable to stop camera");
00367 }
00368
00369
00370 SafeCleanup();
00371
00372 return 0;
00373 }
00374
00375 std::string bayer_string(dc1394color_filter_t pattern, unsigned int bits)
00376 {
00377 if (bits == 8)
00378 {
00379 switch (pattern)
00380 {
00381 case DC1394_COLOR_FILTER_RGGB:
00382 return sensor_msgs::image_encodings::BAYER_RGGB8;
00383 case DC1394_COLOR_FILTER_GBRG:
00384 return sensor_msgs::image_encodings::BAYER_GBRG8;
00385 case DC1394_COLOR_FILTER_GRBG:
00386 return sensor_msgs::image_encodings::BAYER_GRBG8;
00387 case DC1394_COLOR_FILTER_BGGR:
00388 return sensor_msgs::image_encodings::BAYER_BGGR8;
00389 default:
00390 return sensor_msgs::image_encodings::MONO8;
00391 }
00392 }
00393 else if (bits == 16)
00394 {
00395
00396 return sensor_msgs::image_encodings::MONO16;
00397 }
00398
00399 return sensor_msgs::image_encodings::MONO8;
00400 }
00401
00403 void Camera1394::readData(sensor_msgs::Image& image)
00404 {
00405 ROS_ASSERT_MSG(camera_, "Attempt to read from camera that is not open.");
00406
00407 dc1394video_frame_t * frame = NULL;
00408 dc1394_capture_dequeue (camera_, DC1394_CAPTURE_POLICY_WAIT, &frame);
00409 if (!frame)
00410 {
00411 CAM_EXCEPT(camera1394::Exception, "Unable to capture frame");
00412 return;
00413 }
00414
00415 uint8_t* capture_buffer;
00416
00417 if (use_ros_time_)
00418 image.header.stamp = ros::Time::now();
00419 else
00420 image.header.stamp = ros::Time((double) frame->timestamp / 1000000.0);
00421
00422 dc1394video_frame_t frame2;
00423
00424 if (DoBayerConversion_)
00425 {
00426
00427 size_t frame2_size = (frame->size[0] * frame->size[1]
00428 * 3 * sizeof(unsigned char));
00429 frame2.image = (unsigned char *) malloc(frame2_size);
00430 frame2.allocated_image_bytes = frame2_size;
00431 frame2.color_coding = DC1394_COLOR_CODING_RGB8;
00432
00433 frame->color_filter = BayerPattern_;
00434 int err = dc1394_debayer_frames(frame, &frame2, BayerMethod_);
00435 if (err != DC1394_SUCCESS)
00436 {
00437 free(frame2.image);
00438 dc1394_capture_enqueue(camera_, frame);
00439 CAM_EXCEPT(camera1394::Exception, "Could not convert/debayer frames");
00440 return;
00441 }
00442
00443 capture_buffer = reinterpret_cast<uint8_t *>(frame2.image);
00444
00445 image.width = frame2.size[0];
00446 image.height = frame2.size[1];
00447 }
00448 else
00449 {
00450 image.width = frame->size[0];
00451 image.height = frame->size[1];
00452 capture_buffer = reinterpret_cast<uint8_t *>(frame->image);
00453 }
00454
00455 ROS_ASSERT(capture_buffer);
00456
00457 int image_size;
00458 switch (videoMode_)
00459 {
00460 case DC1394_VIDEO_MODE_160x120_YUV444:
00461 image.step=image.width*3;
00462 image_size = image.height*image.step;
00463 image.encoding = sensor_msgs::image_encodings::RGB8;
00464 image.data.resize(image_size);
00465 yuv::uyv2rgb(reinterpret_cast<unsigned char *> (capture_buffer),
00466 reinterpret_cast<unsigned char *> (&image.data[0]),
00467 image.width * image.height);
00468 break;
00469 case DC1394_VIDEO_MODE_640x480_YUV411:
00470 image.step=image.width*3;
00471 image_size = image.height*image.step;
00472 image.encoding = sensor_msgs::image_encodings::RGB8;
00473 image.data.resize(image_size);
00474 yuv::uyyvyy2rgb(reinterpret_cast<unsigned char *> (capture_buffer),
00475 reinterpret_cast<unsigned char *> (&image.data[0]),
00476 image.width * image.height);
00477 break;
00478 case DC1394_VIDEO_MODE_320x240_YUV422:
00479 case DC1394_VIDEO_MODE_640x480_YUV422:
00480 case DC1394_VIDEO_MODE_800x600_YUV422:
00481 case DC1394_VIDEO_MODE_1024x768_YUV422:
00482 case DC1394_VIDEO_MODE_1280x960_YUV422:
00483 case DC1394_VIDEO_MODE_1600x1200_YUV422:
00484 image.step=image.width*3;
00485 image_size = image.height*image.step;
00486 image.encoding = sensor_msgs::image_encodings::RGB8;
00487 image.data.resize(image_size);
00488 yuv::uyvy2rgb(reinterpret_cast<unsigned char *> (capture_buffer),
00489 reinterpret_cast<unsigned char *> (&image.data[0]),
00490 image.width * image.height);
00491 break;
00492 case DC1394_VIDEO_MODE_640x480_RGB8:
00493 case DC1394_VIDEO_MODE_800x600_RGB8:
00494 case DC1394_VIDEO_MODE_1024x768_RGB8:
00495 case DC1394_VIDEO_MODE_1280x960_RGB8:
00496 case DC1394_VIDEO_MODE_1600x1200_RGB8:
00497 image.step=image.width*3;
00498 image_size = image.height*image.step;
00499 image.encoding = sensor_msgs::image_encodings::RGB8;
00500 image.data.resize(image_size);
00501 memcpy(&image.data[0], capture_buffer, image_size);
00502 break;
00503 case DC1394_VIDEO_MODE_640x480_MONO8:
00504 case DC1394_VIDEO_MODE_800x600_MONO8:
00505 case DC1394_VIDEO_MODE_1024x768_MONO8:
00506 case DC1394_VIDEO_MODE_1280x960_MONO8:
00507 case DC1394_VIDEO_MODE_1600x1200_MONO8:
00508 if (!DoBayerConversion_)
00509 {
00510 image.step=image.width;
00511 image_size = image.height*image.step;
00512
00513 image.encoding = bayer_string(BayerPattern_, 8);
00514 image.data.resize(image_size);
00515 memcpy(&image.data[0], capture_buffer, image_size);
00516 }
00517 else
00518 {
00519 image.step=image.width*3;
00520 image_size = image.height*image.step;
00521 image.encoding = sensor_msgs::image_encodings::RGB8;
00522 image.data.resize(image_size);
00523 memcpy(&image.data[0], capture_buffer, image_size);
00524 }
00525 break;
00526 case DC1394_VIDEO_MODE_640x480_MONO16:
00527 case DC1394_VIDEO_MODE_800x600_MONO16:
00528 case DC1394_VIDEO_MODE_1024x768_MONO16:
00529 case DC1394_VIDEO_MODE_1280x960_MONO16:
00530 case DC1394_VIDEO_MODE_1600x1200_MONO16:
00531 if (!DoBayerConversion_)
00532 {
00533 image.step=image.width*2;
00534 image_size = image.height*image.step;
00535 image.encoding = sensor_msgs::image_encodings::MONO16;
00536 image.is_bigendian = true;
00537 image.data.resize(image_size);
00538 memcpy(&image.data[0], capture_buffer, image_size);
00539 }
00540 else
00541 {
00542
00543 image.step=image.width*3;
00544 image_size = image.height*image.step;
00545 image.encoding = sensor_msgs::image_encodings::RGB8;
00546 image.data.resize(image_size);
00547 memcpy(&image.data[0], capture_buffer, image_size);
00548 }
00549 break;
00550 default:
00551 if (dc1394_is_video_mode_scalable(videoMode_))
00552 {
00553 format7_.unpackData(image, capture_buffer);
00554 }
00555 else
00556 {
00557 CAM_EXCEPT(camera1394::Exception, "Unknown image mode");
00558 return;
00559 }
00560 }
00561 dc1394_capture_enqueue(camera_, frame);
00562
00563 if (DoBayerConversion_)
00564 free(capture_buffer);
00565 }