dev_camera1394.h
Go to the documentation of this file.
1 /* -*- mode: C++ -*- */
3 //
4 // Copyright (C) 2009, 2010 Patrick Beeson, Jack O'Quin
5 // ROS port of the Player 1394 camera driver.
6 //
7 // Copyright (C) 2004 Nate Koenig, Andrew Howard
8 // Player driver for IEEE 1394 digital camera capture
9 //
10 // Copyright (C) 2000-2003 Damien Douxchamps, Dan Dennedy
11 // Bayer filtering from libdc1394
12 //
13 // NOTE: On 4 Jan. 2011, this file was re-licensed under the GNU LGPL
14 // with permission of the original GPL authors: Nate Koenig, Andrew
15 // Howard, Damien Douxchamps and Dan Dennedy.
16 //
17 // This program is free software; you can redistribute it and/or
18 // modify it under the terms of the GNU Lesser General Public License
19 // as published by the Free Software Foundation; either version 2 of
20 // the License, or (at your option) any later version.
21 //
22 // This program is distributed in the hope that it will be useful, but
23 // WITHOUT ANY WARRANTY; without even the implied warranty of
24 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
25 // Lesser General Public License for more details.
26 //
27 // You should have received a copy of the GNU Lesser General Public
28 // License along with this program; if not, write to the Free Software
29 // Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA
30 // 02111-1307, USA.
31 //
33 
34 // $Id$
35 
42 #ifndef DEV_CAMERA1394_HH
43 #define DEV_CAMERA1394_HH
44 
45 #include <dc1394/dc1394.h>
46 
47 // ROS includes
48 #include <sensor_msgs/Image.h>
49 #include <sensor_msgs/CameraInfo.h>
50 #include "camera1394/Camera1394Config.h"
51 #include "registers.h"
52 #include "format7.h"
53 
54 class Features; // actually defined in features.h
55 
56 namespace camera1394
57 {
59  // (std::runtime_error should be top parent)
60  // code borrowed from drivers/laser/hokuyo_driver/hokuyo.h
61 #define DEF_EXCEPTION(name, parent) \
62  class name : public parent { \
63  public: \
64  name (const char* msg) : parent (msg) {} \
65  }
66 
68  DEF_EXCEPTION(Exception, std::runtime_error);
69 
70  class Camera1394
71  {
72  public:
73  Camera1394();
74  ~Camera1394 ();
75 
76  int open(camera1394::Camera1394Config &newconfig);
77  int close();
78  bool readData (sensor_msgs::Image &image);
79 
86  bool checkCameraInfo(const sensor_msgs::Image &image,
87  const sensor_msgs::CameraInfo &ci)
88 
89  {
90  if (format7_.active())
91  return format7_.checkCameraInfo(ci);
92  else
93  return (ci.width == image.width && ci.height == image.height);
94  }
95 
104  void setOperationalParameters(sensor_msgs::CameraInfo &ci)
105  {
106  if (format7_.active())
108  }
109 
110  std::string device_id_;
113 
114  private:
115 
116  // private data
117  dc1394camera_t *camera_;
118  dc1394video_mode_t videoMode_;
119  dc1394color_filter_t BayerPattern_;
120  dc1394bayer_method_t BayerMethod_;
125 
126  void SafeCleanup();
127  void findBayerPattern(const char*);
128  bool findBayerMethod(const char*);
129  };
130 };
131 
132 #endif // DEV_CAMERA1394_HH
dc1394video_mode_t videoMode_
void setOperationalParameters(sensor_msgs::CameraInfo &ci)
DEF_EXCEPTION(Exception, std::runtime_error)
A standard Camera1394 exception.
IEEE 1394 camera registers interface.
bool readData(sensor_msgs::Image &image)
dc1394color_filter_t BayerPattern_
bool findBayerMethod(const char *)
bool active(void)
Definition: format7.h:79
dc1394bayer_method_t BayerMethod_
void findBayerPattern(const char *)
void setOperationalParameters(sensor_msgs::CameraInfo &cinfo)
Definition: format7.cpp:464
Camera1394 Features class.
Definition: features.h:61
bool checkCameraInfo(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &ci)
boost::shared_ptr< Registers > registers_
Camera1394 Format7 interface.
int open(camera1394::Camera1394Config &newconfig)
boost::shared_ptr< Features > features_
dc1394camera_t * camera_
bool checkCameraInfo(const sensor_msgs::CameraInfo &cinfo)
Definition: format7.cpp:430


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