00001 /* -*- mode: C++ -*- */ 00002 /* $Id$ */ 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 <diagnostic_updater/diagnostic_updater.h> 00043 #include <diagnostic_updater/publisher.h> 00044 #include <dynamic_reconfigure/server.h> 00045 #include <image_transport/image_transport.h> 00046 #include <sensor_msgs/CameraInfo.h> 00047 00048 #include "dev_camera1394.h" 00049 #include "camera1394/Camera1394Config.h" 00050 #include "camera1394/GetCameraRegisters.h" 00051 #include "camera1394/SetCameraRegisters.h" 00052 00053 typedef camera1394::Camera1394Config Config; 00054 00061 namespace camera1394_driver 00062 { 00063 00064 // Dynamic reconfiguration levels 00065 // 00066 // Must agree with SensorLevels class in cfg/Camera1394.cfg 00067 class Levels 00068 { 00069 public: 00070 static const uint32_t RECONFIGURE_CLOSE = 3; // Close the device to change 00071 static const uint32_t RECONFIGURE_STOP = 1; // Stop the device to change 00072 static const uint32_t RECONFIGURE_RUNNING = 0; // Parameters that can change any time 00073 }; 00074 00075 class Camera1394Driver 00076 { 00077 public: 00078 00079 // driver states 00080 static const uint8_t CLOSED = 0; // Not connected to the device 00081 static const uint8_t OPENED = 1; // Connected to the camera, ready to stream 00082 static const uint8_t RUNNING = 2; // Streaming images 00083 00084 // public methods 00085 Camera1394Driver(ros::NodeHandle priv_nh, 00086 ros::NodeHandle camera_nh); 00087 ~Camera1394Driver(); 00088 void poll(void); 00089 void setup(void); 00090 void shutdown(void); 00091 00092 private: 00093 00094 // private methods 00095 void closeCamera(); 00096 bool openCamera(Config &newconfig); 00097 void publish(const sensor_msgs::ImagePtr &image); 00098 bool read(sensor_msgs::ImagePtr &image); 00099 void reconfig(camera1394::Camera1394Config &newconfig, uint32_t level); 00100 00101 bool getCameraRegisters(camera1394::GetCameraRegisters::Request &request, 00102 camera1394::GetCameraRegisters::Response &response); 00103 bool setCameraRegisters(camera1394::SetCameraRegisters::Request &request, 00104 camera1394::SetCameraRegisters::Response &response); 00105 00107 boost::mutex mutex_; 00108 00110 volatile uint8_t state_; // current driver state 00111 volatile bool reconfiguring_; // true when reconfig() running 00112 ros::NodeHandle priv_nh_; // private node handle 00113 ros::NodeHandle camera_nh_; // camera name space handle 00114 std::string camera_name_; // camera name 00115 ros::Rate cycle_; // polling rate when closed 00116 uint32_t retries_; // count of openCamera() retries 00117 uint32_t consecutive_read_errors_; // number of consecutive read errors 00118 00120 boost::shared_ptr<camera1394::Camera1394> dev_; 00121 00123 camera1394::Camera1394Config config_; 00124 dynamic_reconfigure::Server<camera1394::Camera1394Config> srv_; 00125 00127 boost::shared_ptr<camera_info_manager::CameraInfoManager> cinfo_; 00128 bool calibration_matches_; // CameraInfo matches video mode 00129 00131 boost::shared_ptr<image_transport::ImageTransport> it_; 00132 image_transport::CameraPublisher image_pub_; 00133 00135 ros::ServiceServer get_camera_registers_srv_; 00136 ros::ServiceServer set_camera_registers_srv_; 00137 00139 diagnostic_updater::Updater diagnostics_; 00140 double topic_diagnostics_min_freq_; 00141 double topic_diagnostics_max_freq_; 00142 diagnostic_updater::TopicDiagnostic topic_diagnostics_; 00143 00144 }; // end class Camera1394Driver 00145 00146 }; // end namespace camera1394_driver