dev_camera1394.h
Go to the documentation of this file.
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 "format7.h"
00052 
00053 class Features;
00054 
00055 namespace camera1394
00056 {
00058   //  (std::runtime_error should be top parent)
00059   // code borrowed from drivers/laser/hokuyo_driver/hokuyo.h
00060 #define DEF_EXCEPTION(name, parent)             \
00061   class name  : public parent {                 \
00062   public:                                       \
00063     name (const char* msg) : parent (msg) {}    \
00064   }
00065 
00067   DEF_EXCEPTION(Exception, std::runtime_error);
00068 
00069   class Camera1394
00070   {
00071   public:
00072     Camera1394 ();
00073     ~Camera1394 ();
00074 
00075     int open(camera1394::Camera1394Config &newconfig);
00076     int close();
00077     void readData (sensor_msgs::Image &image);
00078 
00085     bool checkCameraInfo(const sensor_msgs::Image &image,
00086                          const sensor_msgs::CameraInfo &ci)
00087                           
00088     {
00089       if (format7_.active())
00090         return format7_.checkCameraInfo(ci);
00091       else
00092         return (ci.width == image.width && ci.height == image.height);
00093     }
00094 
00103     void setOperationalParameters(sensor_msgs::CameraInfo &ci)
00104     {
00105       if (format7_.active())
00106         format7_.setOperationalParameters(ci);
00107     }
00108 
00109     std::string device_id_;
00110     boost::shared_ptr<Features> features_;
00111 
00112   private:
00113       
00114     // private data
00115     dc1394camera_t *camera_;
00116     dc1394video_mode_t videoMode_;
00117     dc1394color_filter_t BayerPattern_;
00118     dc1394bayer_method_t BayerMethod_;
00119     bool DoBayerConversion_;
00120     Format7 format7_;
00121     bool use_ros_time_;
00122 
00123     void SafeCleanup();
00124     void findBayerPattern(const char*);
00125     bool findBayerMethod(const char*);
00126   };
00127 };
00128 
00129 #endif // DEV_CAMERA1394_HH


camera1394
Author(s): Jack O'Quin, Ken Tossell, Patrick Beeson, Nate Koenig, Andrew Howard, Damien Douxchamps, Dan Dennedy
autogenerated on Sat Dec 28 2013 16:50:11