dev_camera1394stereo.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: dev_camera1394.h 35691 2011-02-02 04:28:58Z joq $
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 "camera1394stereo/Camera1394StereoConfig.h"
51 #include "format7.h"
52 
53 class Features;
54 
56 {
58  // (std::runtime_error should be top parent)
59  // code borrowed from drivers/laser/hokuyo_driver/hokuyo.h
60 #define DEF_EXCEPTION(name, parent) \
61  class name : public parent { \
62  public: \
63  name (const char* msg) : parent (msg) {} \
64  }
65 
67  DEF_EXCEPTION(Exception, std::runtime_error);
68 
70  {
71  public:
74 
75  int open(camera1394stereo::Camera1394StereoConfig &newconfig);
76  int close();
77  bool readData (sensor_msgs::Image &image, sensor_msgs::Image &image2);
78 
85  bool checkCameraInfo(const sensor_msgs::Image &image,
86  const sensor_msgs::CameraInfo &ci)
87 
88  {
89  if (format7_.active())
90  return format7_.checkCameraInfo(ci);
91  else
92  return (ci.width == image.width && ci.height == image.height);
93  }
94 
103  void setOperationalParameters(sensor_msgs::CameraInfo &ci)
104  {
105  if (format7_.active())
107  }
108 
109  std::string device_id_;
111 
112  private:
113 
114  // private data
115  dc1394camera_t *camera_;
116  dc1394video_mode_t videoMode_;
117  dc1394color_coding_t colorCoding_;
118  dc1394color_filter_t BayerPattern_;
119  dc1394bayer_method_t BayerMethod_;
121  dc1394stereo_method_t stereoMethod_;
124 
125  void SafeCleanup();
126  void findBayerPattern(const char*);
127  bool findBayerMethod(const char*);
128  bool findStereoMethod(const char* method);
129  };
130 };
131 
132 #endif // DEV_CAMERA1394_HH
boost::shared_ptr< Features > features_
void setOperationalParameters(sensor_msgs::CameraInfo &ci)
bool readData(sensor_msgs::Image &image, sensor_msgs::Image &image2)
bool active(void)
Definition: format7.h:78
void setOperationalParameters(sensor_msgs::CameraInfo &cinfo)
Camera1394 Features class.
bool checkCameraInfo(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &ci)
Camera1394 Format7 interface.
DEF_EXCEPTION(Exception, std::runtime_error)
A standard Camera1394 exception.
int open(camera1394stereo::Camera1394StereoConfig &newconfig)
bool checkCameraInfo(const sensor_msgs::CameraInfo &cinfo)


camera1394stereo
Author(s): Joan Pau Beltran
autogenerated on Mon Jun 10 2019 12:52:45