$search
00001 00002 // 00003 // Copyright (C) 2009, 2010 Patrick Beeson, Jack O'Quin, Ken Tossell 00004 // ROS port of the Player 1394 camera driver. 00005 // 00006 // Copyright (C) 2004 Nate Koenig, Andrew Howard 00007 // Player driver for IEEE 1394 digital camera capture 00008 // 00009 // Copyright (C) 2000-2003 Damien Douxchamps, Dan Dennedy 00010 // Bayer filtering from libdc1394 00011 // 00012 // NOTE: On 4 Jan. 2011, this file was re-licensed under the GNU LGPL 00013 // with permission of the original GPL authors: Nate Koenig, Andrew 00014 // Howard, Damien Douxchamps and Dan Dennedy. 00015 // 00016 // This program is free software; you can redistribute it and/or 00017 // modify it under the terms of the GNU Lesser General Public License 00018 // as published by the Free Software Foundation; either version 2 of 00019 // the License, or (at your option) any later version. 00020 // 00021 // This program is distributed in the hope that it will be useful, but 00022 // WITHOUT ANY WARRANTY; without even the implied warranty of 00023 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 00024 // Lesser General Public License for more details. 00025 // 00026 // You should have received a copy of the GNU Lesser General Public 00027 // License along with this program; if not, write to the Free Software 00028 // Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 00029 // 02111-1307, USA. 00030 // 00032 00033 // $Id: dev_camera1394.cpp 37636 2011-07-21 00:45:20Z joq $ 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 // @todo eliminate these macros 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 // Constructor 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 // determine Bayer color encoding pattern 00093 // (default is different from any color filter provided by DC1394) 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 // Do Bayer conversion in the driver node? 00120 bool DoBayer = false; // return value 00121 if (0 != strcmp(method, "") 00122 && BayerPattern_ != DC1394_COLOR_FILTER_NUM) 00123 { 00124 DoBayer = true; // decoding in driver 00125 // add method name to message: 00126 ROS_WARN("[%s] Bayer decoding in the driver is DEPRECATED;" 00127 " image_proc decoding preferred.", method); 00128 00129 // Set decoding method 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 // First, look for the camera 00167 00168 const char *guid = newconfig.guid.c_str(); // C-style GUID for libdc1394 00169 int err; 00170 dc1394_t *d; 00171 dc1394camera_list_t *list; 00172 00173 // TODO: make error exit paths clean up resources properly 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 // Create a camera 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 // initialize camera 00255 00256 // resetting some cameras is not a good idea 00257 if (newconfig.reset_on_open 00258 && DC1394_SUCCESS != dc1394_camera_reset(camera_)) 00259 { 00260 // reset failed: log a warning, but continue 00261 ROS_WARN("Unable to reset camera (continuing)."); 00262 } 00263 00264 // first, set parameters that are common between Format7 and other modes 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 // set video mode 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 // special handling for Format7 modes 00285 00286 DoBayerConversion_ = false; 00287 00288 if (dc1394_is_video_mode_scalable(videoMode_) == DC1394_TRUE) 00289 { 00290 // set Format7 parameters 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 // Set frame rate and Bayer method (only valid for non-Format7 modes) 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 // start the device streaming data 00317 00318 // Set camera to use DMA, improves performance. 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 // Start transmitting camera data 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 // initialize feature settings 00338 00339 // TODO: pass newconfig here and eliminate initialize() method 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 // Free resources 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 switch (pattern) 00396 { 00397 case DC1394_COLOR_FILTER_RGGB: 00398 return sensor_msgs::image_encodings::BAYER_RGGB16; 00399 case DC1394_COLOR_FILTER_GBRG: 00400 return sensor_msgs::image_encodings::BAYER_GBRG16; 00401 case DC1394_COLOR_FILTER_GRBG: 00402 return sensor_msgs::image_encodings::BAYER_GRBG16; 00403 case DC1394_COLOR_FILTER_BGGR: 00404 return sensor_msgs::image_encodings::BAYER_BGGR16; 00405 default: 00406 return sensor_msgs::image_encodings::MONO16; 00407 } 00408 } 00409 00410 // bits should always be 8 or 16, but if not MONO8 is a good default 00411 return sensor_msgs::image_encodings::MONO8; 00412 } 00413 00415 void Camera1394::readData(sensor_msgs::Image& image) 00416 { 00417 ROS_ASSERT_MSG(camera_, "Attempt to read from camera that is not open."); 00418 00419 dc1394video_frame_t * frame = NULL; 00420 dc1394_capture_dequeue (camera_, DC1394_CAPTURE_POLICY_WAIT, &frame); 00421 if (!frame) 00422 { 00423 CAM_EXCEPT(camera1394::Exception, "Unable to capture frame"); 00424 return; 00425 } 00426 00427 uint8_t* capture_buffer; 00428 00429 if (use_ros_time_) 00430 image.header.stamp = ros::Time::now(); 00431 else 00432 image.header.stamp = ros::Time((double) frame->timestamp / 1000000.0); 00433 00434 dc1394video_frame_t frame2; 00435 00436 if (DoBayerConversion_) 00437 { 00438 // debayer frame into RGB8 00439 size_t frame2_size = (frame->size[0] * frame->size[1] 00440 * 3 * sizeof(unsigned char)); 00441 frame2.image = (unsigned char *) malloc(frame2_size); 00442 frame2.allocated_image_bytes = frame2_size; 00443 frame2.color_coding = DC1394_COLOR_CODING_RGB8; 00444 00445 frame->color_filter = BayerPattern_; 00446 int err = dc1394_debayer_frames(frame, &frame2, BayerMethod_); 00447 if (err != DC1394_SUCCESS) 00448 { 00449 free(frame2.image); 00450 dc1394_capture_enqueue(camera_, frame); 00451 CAM_EXCEPT(camera1394::Exception, "Could not convert/debayer frames"); 00452 return; 00453 } 00454 00455 capture_buffer = reinterpret_cast<uint8_t *>(frame2.image); 00456 00457 image.width = frame2.size[0]; 00458 image.height = frame2.size[1]; 00459 } 00460 else 00461 { 00462 image.width = frame->size[0]; 00463 image.height = frame->size[1]; 00464 capture_buffer = reinterpret_cast<uint8_t *>(frame->image); 00465 } 00466 00467 ROS_ASSERT(capture_buffer); 00468 00469 int image_size; 00470 switch (videoMode_) 00471 { 00472 case DC1394_VIDEO_MODE_160x120_YUV444: 00473 image.step=image.width*3; 00474 image_size = image.height*image.step; 00475 image.encoding = sensor_msgs::image_encodings::RGB8; 00476 image.data.resize(image_size); 00477 yuv::uyv2rgb(reinterpret_cast<unsigned char *> (capture_buffer), 00478 reinterpret_cast<unsigned char *> (&image.data[0]), 00479 image.width * image.height); 00480 break; 00481 case DC1394_VIDEO_MODE_640x480_YUV411: 00482 image.step=image.width*3; 00483 image_size = image.height*image.step; 00484 image.encoding = sensor_msgs::image_encodings::RGB8; 00485 image.data.resize(image_size); 00486 yuv::uyyvyy2rgb(reinterpret_cast<unsigned char *> (capture_buffer), 00487 reinterpret_cast<unsigned char *> (&image.data[0]), 00488 image.width * image.height); 00489 break; 00490 case DC1394_VIDEO_MODE_320x240_YUV422: 00491 case DC1394_VIDEO_MODE_640x480_YUV422: 00492 case DC1394_VIDEO_MODE_800x600_YUV422: 00493 case DC1394_VIDEO_MODE_1024x768_YUV422: 00494 case DC1394_VIDEO_MODE_1280x960_YUV422: 00495 case DC1394_VIDEO_MODE_1600x1200_YUV422: 00496 image.step=image.width*3; 00497 image_size = image.height*image.step; 00498 image.encoding = sensor_msgs::image_encodings::RGB8; 00499 image.data.resize(image_size); 00500 yuv::uyvy2rgb(reinterpret_cast<unsigned char *> (capture_buffer), 00501 reinterpret_cast<unsigned char *> (&image.data[0]), 00502 image.width * image.height); 00503 break; 00504 case DC1394_VIDEO_MODE_640x480_RGB8: 00505 case DC1394_VIDEO_MODE_800x600_RGB8: 00506 case DC1394_VIDEO_MODE_1024x768_RGB8: 00507 case DC1394_VIDEO_MODE_1280x960_RGB8: 00508 case DC1394_VIDEO_MODE_1600x1200_RGB8: 00509 image.step=image.width*3; 00510 image_size = image.height*image.step; 00511 image.encoding = sensor_msgs::image_encodings::RGB8; 00512 image.data.resize(image_size); 00513 memcpy(&image.data[0], capture_buffer, image_size); 00514 break; 00515 case DC1394_VIDEO_MODE_640x480_MONO8: 00516 case DC1394_VIDEO_MODE_800x600_MONO8: 00517 case DC1394_VIDEO_MODE_1024x768_MONO8: 00518 case DC1394_VIDEO_MODE_1280x960_MONO8: 00519 case DC1394_VIDEO_MODE_1600x1200_MONO8: 00520 if (!DoBayerConversion_) 00521 { 00522 image.step=image.width; 00523 image_size = image.height*image.step; 00524 // set Bayer encoding in ROS Image message 00525 image.encoding = bayer_string(BayerPattern_, 8); 00526 image.data.resize(image_size); 00527 memcpy(&image.data[0], capture_buffer, image_size); 00528 } 00529 else 00530 { 00531 image.step=image.width*3; 00532 image_size = image.height*image.step; 00533 image.encoding = sensor_msgs::image_encodings::RGB8; 00534 image.data.resize(image_size); 00535 memcpy(&image.data[0], capture_buffer, image_size); 00536 } 00537 break; 00538 case DC1394_VIDEO_MODE_640x480_MONO16: 00539 case DC1394_VIDEO_MODE_800x600_MONO16: 00540 case DC1394_VIDEO_MODE_1024x768_MONO16: 00541 case DC1394_VIDEO_MODE_1280x960_MONO16: 00542 case DC1394_VIDEO_MODE_1600x1200_MONO16: 00543 if (!DoBayerConversion_) 00544 { 00545 image.step=image.width*2; 00546 image_size = image.height*image.step; 00547 image.encoding = bayer_string(BayerPattern_, 16); 00548 image.is_bigendian = true; 00549 image.data.resize(image_size); 00550 memcpy(&image.data[0], capture_buffer, image_size); 00551 } 00552 else 00553 { 00554 // @todo test Bayer conversions for mono16 00555 image.step=image.width*3; 00556 image_size = image.height*image.step; 00557 image.encoding = sensor_msgs::image_encodings::RGB8; 00558 image.data.resize(image_size); 00559 memcpy(&image.data[0], capture_buffer, image_size); 00560 } 00561 break; 00562 default: 00563 if (dc1394_is_video_mode_scalable(videoMode_)) 00564 { 00565 format7_.unpackData(image, capture_buffer); 00566 } 00567 else 00568 { 00569 CAM_EXCEPT(camera1394::Exception, "Unknown image mode"); 00570 return; 00571 } 00572 } 00573 dc1394_capture_enqueue(camera_, frame); 00574 00575 if (DoBayerConversion_) 00576 free(capture_buffer); 00577 }