00001 /* -*- mode: C++ -*- */ 00003 // 00004 // Copyright (C) 2009, 2010 Patrick Beeson, Jack O'Quin 00005 // ROS port of the Player 1394 camera driver. 00006 // 00007 // Copyright (C) 2004 Nate Koenig, Andrew Howard 00008 // Player driver for IEEE 1394 digital camera capture 00009 // 00010 // Copyright (C) 2000-2003 Damien Douxchamps, Dan Dennedy 00011 // Bayer filtering from libdc1394 00012 // 00013 // NOTE: On 4 Jan. 2011, this file was re-licensed under the GNU LGPL 00014 // with permission of the original GPL authors: Nate Koenig, Andrew 00015 // Howard, Damien Douxchamps and Dan Dennedy. 00016 // 00017 // This program is free software; you can redistribute it and/or 00018 // modify it under the terms of the GNU Lesser General Public License 00019 // as published by the Free Software Foundation; either version 2 of 00020 // the License, or (at your option) any later version. 00021 // 00022 // This program is distributed in the hope that it will be useful, but 00023 // WITHOUT ANY WARRANTY; without even the implied warranty of 00024 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 00025 // Lesser General Public License for more details. 00026 // 00027 // You should have received a copy of the GNU Lesser General Public 00028 // License along with this program; if not, write to the Free Software 00029 // Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA 00030 // 02111-1307, USA. 00031 // 00033 00034 // $Id$ 00035 00042 #ifndef DEV_CAMERA1394_HH 00043 #define DEV_CAMERA1394_HH 00044 00045 #include <dc1394/dc1394.h> 00046 00047 // ROS includes 00048 #include <sensor_msgs/Image.h> 00049 #include <sensor_msgs/CameraInfo.h> 00050 #include "camera1394/Camera1394Config.h" 00051 #include "registers.h" 00052 #include "format7.h" 00053 00054 class Features; // actually defined in features.h 00055 00056 namespace camera1394 00057 { 00059 // (std::runtime_error should be top parent) 00060 // code borrowed from drivers/laser/hokuyo_driver/hokuyo.h 00061 #define DEF_EXCEPTION(name, parent) \ 00062 class name : public parent { \ 00063 public: \ 00064 name (const char* msg) : parent (msg) {} \ 00065 } 00066 00068 DEF_EXCEPTION(Exception, std::runtime_error); 00069 00070 class Camera1394 00071 { 00072 public: 00073 Camera1394(); 00074 ~Camera1394 (); 00075 00076 int open(camera1394::Camera1394Config &newconfig); 00077 int close(); 00078 bool readData (sensor_msgs::Image &image); 00079 00086 bool checkCameraInfo(const sensor_msgs::Image &image, 00087 const sensor_msgs::CameraInfo &ci) 00088 00089 { 00090 if (format7_.active()) 00091 return format7_.checkCameraInfo(ci); 00092 else 00093 return (ci.width == image.width && ci.height == image.height); 00094 } 00095 00104 void setOperationalParameters(sensor_msgs::CameraInfo &ci) 00105 { 00106 if (format7_.active()) 00107 format7_.setOperationalParameters(ci); 00108 } 00109 00110 std::string device_id_; 00111 boost::shared_ptr<Features> features_; 00112 boost::shared_ptr<Registers> registers_; 00113 00114 private: 00115 00116 // private data 00117 dc1394camera_t *camera_; 00118 dc1394video_mode_t videoMode_; 00119 dc1394color_filter_t BayerPattern_; 00120 dc1394bayer_method_t BayerMethod_; 00121 bool DoBayerConversion_; 00122 Format7 format7_; 00123 bool use_ros_time_; 00124 float time_offset_; 00125 00126 void SafeCleanup(); 00127 void findBayerPattern(const char*); 00128 bool findBayerMethod(const char*); 00129 }; 00130 }; 00131 00132 #endif // DEV_CAMERA1394_HH