dev_camera1394.cpp
Go to the documentation of this file.
1 //
3 // Copyright (C) 2009, 2010, 2012 Patrick Beeson, Jack O'Quin, Ken Tossell
4 // ROS port of the Player 1394 camera driver.
5 //
6 // Copyright (C) 2004 Nate Koenig, Andrew Howard
7 // Player driver for IEEE 1394 digital camera capture
8 //
9 // Copyright (C) 2000-2003 Damien Douxchamps, Dan Dennedy
10 // Bayer filtering from libdc1394
11 //
12 // NOTE: On 4 Jan. 2011, this file was re-licensed under the GNU LGPL
13 // with permission of the original GPL authors: Nate Koenig, Andrew
14 // Howard, Damien Douxchamps and Dan Dennedy.
15 //
16 // This program is free software; you can redistribute it and/or
17 // modify it under the terms of the GNU Lesser General Public License
18 // as published by the Free Software Foundation; either version 2 of
19 // the License, or (at your option) any later version.
20 //
21 // This program is distributed in the hope that it will be useful, but
22 // WITHOUT ANY WARRANTY; without even the implied warranty of
23 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
24 // Lesser General Public License for more details.
25 //
26 // You should have received a copy of the GNU Lesser General Public
27 // License along with this program; if not, write to the Free Software
28 // Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA
29 // 02111-1307, USA.
30 //
32 
33 // $Id$
34 
49 #include <stdint.h>
50 
51 #include "yuv.h"
52 #include <cstdlib>
54 #include "dev_camera1394.h"
55 #include "features.h"
56 #include "modes.h"
57 
58 // @todo eliminate these macros
60 #define CAM_EXCEPT(except, msg) \
61  { \
62  char buf[100]; \
63  snprintf(buf, 100, "[Camera1394::%s]: " msg, __FUNCTION__); \
64  throw except(buf); \
65  }
66 
68 #define CAM_EXCEPT_ARGS(except, msg, ...) \
69  { \
70  char buf[100]; \
71  snprintf(buf, 100, "[Camera1394::%s]: " msg, __FUNCTION__, __VA_ARGS__); \
72  throw except(buf); \
73  }
74 
75 
76 using namespace camera1394;
77 
79 // Constructor
81  camera_(NULL)
82 {}
83 
85 {
86  SafeCleanup();
87 }
88 
89 void Camera1394::findBayerPattern(const char* bayer)
90 {
91  // determine Bayer color encoding pattern
92  // (default is different from any color filter provided by DC1394)
93  BayerPattern_ = (dc1394color_filter_t) DC1394_COLOR_FILTER_NUM;
94  if (0 == strcmp(bayer, "bggr"))
95  {
96  BayerPattern_ = DC1394_COLOR_FILTER_BGGR;
97  }
98  else if (0 == strcmp(bayer, "grbg"))
99  {
100  BayerPattern_ = DC1394_COLOR_FILTER_GRBG;
101  }
102  else if (0 == strcmp(bayer, "rggb"))
103  {
104  BayerPattern_ = DC1394_COLOR_FILTER_RGGB;
105  }
106  else if (0 == strcmp(bayer, "gbrg"))
107  {
108  BayerPattern_ = DC1394_COLOR_FILTER_GBRG;
109  }
110  else if (0 != strcmp(bayer, ""))
111  {
112  ROS_ERROR("unknown bayer pattern [%s]", bayer);
113  }
114 }
115 
116 bool Camera1394::findBayerMethod(const char* method)
117 {
118  // Do Bayer conversion in the driver node?
119  bool DoBayer = false; // return value
120  if (0 != strcmp(method, "")
121  && BayerPattern_ != DC1394_COLOR_FILTER_NUM)
122  {
123  DoBayer = true; // decoding in driver
124  // add method name to message:
125  ROS_WARN("[%s] Bayer decoding in the driver is DEPRECATED;"
126  " image_proc decoding preferred.", method);
127 
128  // Set decoding method
129  if (!strcmp(method, "DownSample"))
130  BayerMethod_ = DC1394_BAYER_METHOD_DOWNSAMPLE;
131  else if (!strcmp(method, "Simple"))
132  BayerMethod_ = DC1394_BAYER_METHOD_SIMPLE;
133  else if (!strcmp(method, "Bilinear"))
134  BayerMethod_ = DC1394_BAYER_METHOD_BILINEAR;
135  else if (!strcmp(method, "HQ"))
136  BayerMethod_ = DC1394_BAYER_METHOD_HQLINEAR;
137  else if (!strcmp(method, "VNG"))
138  BayerMethod_ = DC1394_BAYER_METHOD_VNG;
139  else if (!strcmp(method, "AHD"))
140  BayerMethod_ = DC1394_BAYER_METHOD_AHD;
141  else
142  {
143  ROS_ERROR("Unknown Bayer method [%s]. Using ROS image_proc instead.",
144  method);
145  DoBayer = false;
146  }
147  }
148  return DoBayer;
149 }
150 
161 int Camera1394::open(camera1394::Camera1394Config &newconfig)
162 {
164  // Pad GUID (if specified) with leading zeros
166 
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)
170  {
171  if (guid_length < exact_guid_length)
172  {
173  // pad string with leading zeros
174  newconfig.guid.insert(0, exact_guid_length - guid_length, '0');
175  }
176  else
177  {
178  ROS_ERROR_STREAM_THROTTLE(3, "Invalid GUID [" << newconfig.guid
179  << "] specified: " << guid_length
180  << " characters long.");
181  }
182  }
183 
185  // First, look for the camera
187 
188  const char *guid = newconfig.guid.c_str(); // C-style GUID for libdc1394
189  int err;
190  dc1394_t *d;
191  dc1394camera_list_t *list;
192 
193  // TODO: make error exit paths clean up resources properly
194  d = dc1394_new ();
195  if (d == NULL)
196  {
197  CAM_EXCEPT(camera1394::Exception,
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.");
201  }
202 
203  err = dc1394_camera_enumerate(d, &list);
204  if (err != DC1394_SUCCESS)
205  {
206  CAM_EXCEPT(camera1394::Exception, "Could not get camera list");
207  return -1;
208  }
209 
210  if (list->num == 0)
211  {
212  CAM_EXCEPT(camera1394::Exception, "No cameras found");
213  return -1;
214  }
215 
216  char* temp=(char*)malloc(1024*sizeof(char));
217  for (unsigned i=0; i < list->num; i++)
218  {
219  uint32_t value[3];
220 
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;
224 
225  sprintf(temp,"%06x%02x%08x", value[2], value[1], value[0]);
226 
227  if (guid[0] == '\0')
228  {
229  // pad GUID with leading zeros in message
230  ROS_INFO_STREAM("No GUID specified, using first camera found, GUID: "
231  << std::setw(16) << std::setfill('0') << std::hex
232  << list->ids[i].guid);
233  }
234  else
235  {
236  ROS_WARN("Comparing %s to %s", guid, temp);
237  if (strcmp(temp, guid))
238  {
239  ROS_WARN("GUIDs do not match");
240  continue;
241  }
242  }
243 
244  // Create a camera
245  camera_ = dc1394_camera_new (d, list->ids[i].guid);
246  if (!camera_)
247  {
248  ROS_WARN_STREAM("Failed to initialize camera with GUID "
249  << std::setw(16) << std::setfill('0') << std::hex
250  << list->ids[i].guid);
251 
252  SafeCleanup();
253  break;
254  }
255  else
256  {
257  ROS_INFO_STREAM("Found camera with GUID "
258  << std::setw(16) << std::setfill('0') << std::hex
259  << list->ids[i].guid);
260 
261  device_id_ = std::string(temp);
262  break;
263  }
264  }
265  free (temp);
266  dc1394_camera_free_list (list);
267 
268  if (!camera_)
269  {
270  if (strcmp(guid,"")==0)
271  {
272  CAM_EXCEPT(camera1394::Exception, "Could not find camera");
273  }
274  else
275  {
276  CAM_EXCEPT_ARGS(camera1394::Exception,
277  "Could not find camera with guid %s", guid);
278  }
279  return -1;
280  }
281 
282  ROS_INFO_STREAM("camera model: " << camera_->vendor
283  << " " << camera_->model);
284 
286  // initialize camera
288 
289  // resetting some cameras is not a good idea
290  if (newconfig.reset_on_open
291  && DC1394_SUCCESS != dc1394_camera_reset(camera_))
292  {
293  // reset failed: log a warning, but continue
294  ROS_WARN("Unable to reset camera (continuing).");
295  }
296 
297  // first, set parameters that are common between Format7 and other modes
298  if (false == Modes::setIsoSpeed(camera_, newconfig.iso_speed))
299  {
300  SafeCleanup();
301  CAM_EXCEPT(camera1394::Exception,
302  "Unable to set ISO speed; is the camera plugged in?");
303  return -1;
304  }
305 
306  // set video mode
307  videoMode_ = Modes::getVideoMode(camera_, newconfig.video_mode);
308  if (DC1394_SUCCESS != dc1394_video_set_mode(camera_, videoMode_))
309  {
310  SafeCleanup();
311  CAM_EXCEPT(camera1394::Exception, "Failed to set video mode");
312  return -1;
313  }
314 
316  // special handling for Format7 modes
318 
319  DoBayerConversion_ = false;
320 
321  if (dc1394_is_video_mode_scalable(videoMode_) == DC1394_TRUE)
322  {
323  // set Format7 parameters
324  if (!format7_.start(camera_, videoMode_, newconfig))
325  {
326  SafeCleanup();
327  CAM_EXCEPT(camera1394::Exception, "Format7 start failed");
328  return -1;
329  }
330  }
331  else
332  {
333  // Set frame rate and Bayer method (only valid for non-Format7 modes)
334  DoBayerConversion_ = findBayerMethod(newconfig.bayer_method.c_str());
335  if (!Modes::setFrameRate(camera_, videoMode_, newconfig.frame_rate))
336  {
337  SafeCleanup();
338  CAM_EXCEPT(camera1394::Exception, "Failed to set frame rate");
339  return -1;
340  }
341  }
342 
343  findBayerPattern(newconfig.bayer_pattern.c_str());
344 
345  use_ros_time_ = newconfig.use_ros_time;
346  time_offset_ = newconfig.time_offset;
347 
349  // start the device streaming data
351 
352  // Set camera to use DMA, improves performance.
353  if (DC1394_SUCCESS != dc1394_capture_setup(camera_, newconfig.num_dma_buffers,
354  DC1394_CAPTURE_FLAGS_DEFAULT))
355  {
356  SafeCleanup();
357  CAM_EXCEPT(camera1394::Exception, "Failed to open device!");
358  return -1;
359  }
360 
361  // Start transmitting camera data
362  if (DC1394_SUCCESS != dc1394_video_set_transmission(camera_, DC1394_ON))
363  {
364  SafeCleanup();
365  CAM_EXCEPT(camera1394::Exception, "Failed to start device!");
366  return -1;
367  }
368 
370  // initialize feature settings
372 
373  // TODO: pass newconfig here and eliminate initialize() method
374  features_.reset(new Features(camera_));
375 
376  registers_.reset(new Registers(camera_));
377 
378  return 0;
379 }
380 
381 
384 {
385  if (camera_)
386  {
387  format7_.stop();
388  dc1394_capture_stop(camera_);
389  // try to power off the device (#5322):
390  dc1394_camera_set_power(camera_, DC1394_OFF);
391  dc1394_camera_free(camera_);
392  camera_ = NULL;
393  }
394 }
395 
396 
399 {
400  if (camera_)
401  {
402  if (DC1394_SUCCESS != dc1394_video_set_transmission(camera_, DC1394_OFF)
403  || DC1394_SUCCESS != dc1394_capture_stop(camera_))
404  ROS_WARN("unable to stop camera");
405  }
406 
407  // Free resources
408  SafeCleanup();
409 
410  return 0;
411 }
412 
413 std::string bayer_string(dc1394color_filter_t pattern, unsigned int bits)
414 {
415  if (bits == 8)
416  {
417  switch (pattern)
418  {
419  case DC1394_COLOR_FILTER_RGGB:
421  case DC1394_COLOR_FILTER_GBRG:
423  case DC1394_COLOR_FILTER_GRBG:
425  case DC1394_COLOR_FILTER_BGGR:
427  default:
429  }
430  }
431  else if (bits == 16)
432  {
433  switch (pattern)
434  {
435  case DC1394_COLOR_FILTER_RGGB:
437  case DC1394_COLOR_FILTER_GBRG:
439  case DC1394_COLOR_FILTER_GRBG:
441  case DC1394_COLOR_FILTER_BGGR:
443  default:
445  }
446  }
447 
448  // bits should always be 8 or 16, but if not MONO8 is a good default
450 }
451 
453 bool Camera1394::readData(sensor_msgs::Image& image)
454 {
455  ROS_ASSERT_MSG(camera_, "Attempt to read from camera that is not open.");
456 
457  dc1394video_frame_t * frame = NULL;
458  if (features_->isTriggerPowered())
459  {
460  ROS_DEBUG("[%016lx] polling camera", camera_->guid);
461  dc1394_capture_dequeue (camera_, DC1394_CAPTURE_POLICY_POLL, &frame);
462  if (!frame) return false;
463  }
464  else
465  {
466  ROS_DEBUG("[%016lx] waiting camera", camera_->guid);
467  dc1394_capture_dequeue (camera_, DC1394_CAPTURE_POLICY_WAIT, &frame);
468  if (!frame)
469  {
470  CAM_EXCEPT(camera1394::Exception, "Unable to capture frame");
471  return false;
472  }
473  }
474 
475  uint8_t* capture_buffer;
476 
477  if (use_ros_time_)
478  image.header.stamp = ros::Time::now() + ros::Duration(time_offset_);
479  else
480  image.header.stamp = ros::Time((double) frame->timestamp / 1000000.0);
481 
482  dc1394video_frame_t frame2;
483 
484  if (DoBayerConversion_)
485  {
486  // debayer frame into RGB8
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;
492 
493  frame->color_filter = BayerPattern_;
494  int err = dc1394_debayer_frames(frame, &frame2, BayerMethod_);
495  if (err != DC1394_SUCCESS)
496  {
497  free(frame2.image);
498  dc1394_capture_enqueue(camera_, frame);
499  CAM_EXCEPT(camera1394::Exception, "Could not convert/debayer frames");
500  return false;
501  }
502 
503  capture_buffer = reinterpret_cast<uint8_t *>(frame2.image);
504 
505  image.width = frame2.size[0];
506  image.height = frame2.size[1];
507  }
508  else
509  {
510  image.width = frame->size[0];
511  image.height = frame->size[1];
512  capture_buffer = reinterpret_cast<uint8_t *>(frame->image);
513  }
514 
515  ROS_ASSERT(capture_buffer);
516 
517  int image_size;
518  switch (videoMode_)
519  {
520  case DC1394_VIDEO_MODE_160x120_YUV444:
521  image.step=image.width*3;
522  image_size = image.height*image.step;
523  image.encoding = sensor_msgs::image_encodings::RGB8;
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);
528  break;
529  case DC1394_VIDEO_MODE_640x480_YUV411:
530  image.step=image.width*3;
531  image_size = image.height*image.step;
532  image.encoding = sensor_msgs::image_encodings::RGB8;
533  image.data.resize(image_size);
534  yuv::uyyvyy2rgb(reinterpret_cast<unsigned char *> (capture_buffer),
535  reinterpret_cast<unsigned char *> (&image.data[0]),
536  image.width * image.height);
537  break;
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;
546  image.encoding = sensor_msgs::image_encodings::RGB8;
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);
551  break;
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;
559  image.encoding = sensor_msgs::image_encodings::RGB8;
560  image.data.resize(image_size);
561  memcpy(&image.data[0], capture_buffer, image_size);
562  break;
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:
568  if (!DoBayerConversion_)
569  {
570  image.step=image.width;
571  image_size = image.height*image.step;
572  // set Bayer encoding in ROS Image message
573  image.encoding = bayer_string(BayerPattern_, 8);
574  image.data.resize(image_size);
575  memcpy(&image.data[0], capture_buffer, image_size);
576  }
577  else
578  {
579  image.step=image.width*3;
580  image_size = image.height*image.step;
581  image.encoding = sensor_msgs::image_encodings::RGB8;
582  image.data.resize(image_size);
583  memcpy(&image.data[0], capture_buffer, image_size);
584  }
585  break;
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:
591  if (!DoBayerConversion_)
592  {
593  image.step=image.width*2;
594  image_size = image.height*image.step;
595  image.encoding = bayer_string(BayerPattern_, 16);
596  image.is_bigendian = true;
597  image.data.resize(image_size);
598  memcpy(&image.data[0], capture_buffer, image_size);
599  }
600  else
601  {
602  // @todo test Bayer conversions for mono16
603  image.step=image.width*3;
604  image_size = image.height*image.step;
605  image.encoding = sensor_msgs::image_encodings::RGB8;
606  image.data.resize(image_size);
607  memcpy(&image.data[0], capture_buffer, image_size);
608  }
609  break;
610  default:
611  if (dc1394_is_video_mode_scalable(videoMode_))
612  {
613  format7_.unpackData(image, capture_buffer);
614  }
615  else
616  {
617  CAM_EXCEPT(camera1394::Exception, "Unknown image mode");
618  return false;
619  }
620  }
621  dc1394_capture_enqueue(camera_, frame);
622 
623  if (DoBayerConversion_)
624  free(capture_buffer);
625 
626  return true;
627 }
d
const std::string BAYER_GRBG8
dc1394video_mode_t videoMode_
void unpackData(sensor_msgs::Image &image, uint8_t *capture_buffer)
Definition: format7.cpp:319
const std::string BAYER_GRBG16
void stop(void)
Definition: format7.cpp:310
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.
Registers class.
Definition: registers.h:55
void uyvy2rgb(unsigned char *src, unsigned char *dest, unsigned long long int NumPixels)
Definition: yuv.h:70
bool readData(sensor_msgs::Image &image)
#define ROS_WARN(...)
bool start(dc1394camera_t *camera, dc1394video_mode_t mode, Config &newconfig)
Definition: format7.cpp:59
bool setIsoSpeed(dc1394camera_t *camera, int &iso_speed)
Definition: modes.cpp:360
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_
const std::string MONO16
void findBayerPattern(const char *)
Camera1394 Features class.
Definition: features.h:61
#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)
Definition: modes.cpp:332
void uyyvyy2rgb(const unsigned char *src, unsigned char *dest, unsigned long long int NumPixels)
Definition: yuv.h:96
IEEE 1394 digital camera library interface.
static Time now()
const std::string BAYER_RGGB8
dc1394camera_t * camera_
#define ROS_ASSERT(cond)
#define ROS_ERROR_STREAM_THROTTLE(rate, args)
Camera1394 features interface.
#define ROS_ERROR(...)
dc1394video_mode_t getVideoMode(dc1394camera_t *camera, std::string &video_mode)
Definition: modes.cpp:265
void uyv2rgb(const unsigned char *src, unsigned char *dest, unsigned long long int NumPixels)
Definition: yuv.h:50
#define ROS_DEBUG(...)


camera1394
Author(s): Jack O'Quin, Ken Tossell, Patrick Beeson, Nate Koenig, Andrew Howard, Damien Douxchamps, Dan Dennedy
autogenerated on Mon Jun 10 2019 12:52:31