00001 /* -*- mode: C++ -*- */ 00002 /* $Id: driver1394.h 35611 2011-01-30 05:49:18Z joq $ */ 00003 00004 /********************************************************************* 00005 * Software License Agreement (BSD License) 00006 * 00007 * Copyright (c) 2010 Jack O'Quin 00008 * All rights reserved. 00009 * 00010 * Redistribution and use in source and binary forms, with or without 00011 * modification, are permitted provided that the following conditions 00012 * are met: 00013 * 00014 * * Redistributions of source code must retain the above copyright 00015 * notice, this list of conditions and the following disclaimer. 00016 * * Redistributions in binary form must reproduce the above 00017 * copyright notice, this list of conditions and the following 00018 * disclaimer in the documentation and/or other materials provided 00019 * with the distribution. 00020 * * Neither the name of the author nor other contributors may be 00021 * used to endorse or promote products derived from this software 00022 * without specific prior written permission. 00023 * 00024 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00025 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00026 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00027 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00028 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00029 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00030 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00031 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00032 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00033 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00034 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00035 * POSSIBILITY OF SUCH DAMAGE. 00036 *********************************************************************/ 00037 00038 #include <boost/thread/mutex.hpp> 00039 00040 #include <ros/ros.h> 00041 #include <camera_info_manager/camera_info_manager.h> 00042 #include <driver_base/driver.h> 00043 #include <dynamic_reconfigure/server.h> 00044 #include <image_transport/image_transport.h> 00045 #include <sensor_msgs/CameraInfo.h> 00046 00047 #include "dev_camera1394stereo.h" 00048 #include "camera1394stereo/Camera1394StereoConfig.h" 00049 typedef camera1394stereo::Camera1394StereoConfig Config; 00050 00057 namespace camera1394stereo_driver 00058 { 00059 00060 class Camera1394StereoDriver 00061 { 00062 public: 00063 00064 // public methods 00065 Camera1394StereoDriver(ros::NodeHandle priv_nh, 00066 ros::NodeHandle camera_nh); 00067 ~Camera1394StereoDriver(); 00068 void poll(void); 00069 void setup(void); 00070 void shutdown(void); 00071 00072 private: 00073 00074 enum CameraSelector {LEFT=0,RIGHT=1}; 00075 static const int NUM_CAMERAS = 2; 00076 static const std::string CameraSelectorString[NUM_CAMERAS]; // = {"left","right"}; 00077 00078 // private methods 00079 void closeCamera(); 00080 bool openCamera(Config &newconfig); 00081 void publish(const sensor_msgs::ImagePtr image[NUM_CAMERAS]); 00082 bool read(sensor_msgs::ImagePtr image[NUM_CAMERAS]); 00083 void reconfig(camera1394stereo::Camera1394StereoConfig &newconfig, uint32_t level); 00084 00086 boost::mutex mutex_; 00087 00088 volatile driver_base::Driver::state_t state_; // current driver state 00089 volatile bool reconfiguring_; // true when reconfig() running 00090 00091 ros::NodeHandle priv_nh_; // private node handle 00092 ros::NodeHandle camera_nh_; // camera name space handle 00093 ros::NodeHandle single_camera_nh_[NUM_CAMERAS]; // left/right camera name space handle 00094 std::string camera_name_; // camera name 00095 00097 boost::shared_ptr<camera1394stereo::Camera1394Stereo> dev_; 00098 00100 camera1394stereo::Camera1394StereoConfig config_; 00101 dynamic_reconfigure::Server<camera1394stereo::Camera1394StereoConfig> srv_; 00102 ros::Rate cycle_; // polling rate when closed 00103 00105 boost::shared_ptr<camera_info_manager::CameraInfoManager> cinfo_[NUM_CAMERAS]; 00106 bool calibration_matches_[NUM_CAMERAS]; // CameraInfo matches video mode 00107 00109 boost::shared_ptr<image_transport::ImageTransport> it_; 00110 image_transport::CameraPublisher image_pub_[NUM_CAMERAS]; 00111 00112 }; // end class Camera1394Driver 00113 00114 }; // end namespace camera1394_driver