$search
00001 // $Id: driver1394.cpp 36902 2011-05-26 23:20:18Z joq $ 00002 00003 /********************************************************************* 00004 * Software License Agreement (BSD License) 00005 * 00006 * Copyright (C) 2009, 2010 Jack O'Quin, Patrick Beeson 00007 * All rights reserved. 00008 * 00009 * Redistribution and use in source and binary forms, with or without 00010 * modification, are permitted provided that the following conditions 00011 * are met: 00012 * 00013 * * Redistributions of source code must retain the above copyright 00014 * notice, this list of conditions and the following disclaimer. 00015 * * Redistributions in binary form must reproduce the above 00016 * copyright notice, this list of conditions and the following 00017 * disclaimer in the documentation and/or other materials provided 00018 * with the distribution. 00019 * * Neither the name of the author nor other contributors may be 00020 * used to endorse or promote products derived from this software 00021 * without specific prior written permission. 00022 * 00023 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00024 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00025 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00026 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00027 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00028 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00029 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00030 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00031 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00032 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00033 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00034 * POSSIBILITY OF SUCH DAMAGE. 00035 *********************************************************************/ 00036 00037 #include <boost/format.hpp> 00038 00039 #include <driver_base/SensorLevels.h> 00040 #include <tf/transform_listener.h> 00041 00042 #include "driver1394.h" 00043 #include "camera1394/Camera1394Config.h" 00044 #include "features.h" 00045 00064 namespace camera1394_driver 00065 { 00066 // some convenience typedefs 00067 typedef camera1394::Camera1394Config Config; 00068 typedef driver_base::Driver Driver; 00069 typedef driver_base::SensorLevels Levels; 00070 00071 Camera1394Driver::Camera1394Driver(ros::NodeHandle priv_nh, 00072 ros::NodeHandle camera_nh): 00073 state_(Driver::CLOSED), 00074 reconfiguring_(false), 00075 priv_nh_(priv_nh), 00076 camera_nh_(camera_nh), 00077 camera_name_("camera"), 00078 dev_(new camera1394::Camera1394()), 00079 srv_(priv_nh), 00080 cycle_(1.0), // slow poll when closed 00081 cinfo_(new camera_info_manager::CameraInfoManager(camera_nh_)), 00082 calibration_matches_(true), 00083 it_(new image_transport::ImageTransport(camera_nh_)), 00084 image_pub_(it_->advertiseCamera("image_raw", 1)) 00085 {} 00086 00087 Camera1394Driver::~Camera1394Driver() 00088 {} 00089 00094 void Camera1394Driver::closeCamera() 00095 { 00096 if (state_ != Driver::CLOSED) 00097 { 00098 ROS_INFO_STREAM("[" << camera_name_ << "] closing device"); 00099 dev_->close(); 00100 state_ = Driver::CLOSED; 00101 } 00102 } 00103 00113 bool Camera1394Driver::openCamera(Config &newconfig) 00114 { 00115 bool success = false; 00116 int retries = 2; // number of retries, if open fails 00117 do 00118 { 00119 try 00120 { 00121 if (0 == dev_->open(newconfig)) 00122 { 00123 if (camera_name_ != dev_->device_id_) 00124 { 00125 camera_name_ = dev_->device_id_; 00126 if (!cinfo_->setCameraName(camera_name_)) 00127 { 00128 // GUID is 16 hex digits, which should be valid. 00129 // If not, use it for log messages anyway. 00130 ROS_WARN_STREAM("[" << camera_name_ 00131 << "] name not valid" 00132 << " for camera_info_manger"); 00133 } 00134 } 00135 ROS_INFO_STREAM("[" << camera_name_ << "] opened: " 00136 << newconfig.video_mode << ", " 00137 << newconfig.frame_rate << " fps, " 00138 << newconfig.iso_speed << " Mb/s"); 00139 state_ = Driver::OPENED; 00140 calibration_matches_ = true; 00141 success = true; 00142 } 00143 00144 } 00145 catch (camera1394::Exception& e) 00146 { 00147 state_ = Driver::CLOSED; // since the open() failed 00148 if (retries > 0) 00149 ROS_WARN_STREAM("[" << camera_name_ 00150 << "] exception opening device (retrying): " 00151 << e.what()); 00152 else 00153 ROS_ERROR_STREAM("[" << camera_name_ 00154 << "] device open failed: " << e.what()); 00155 } 00156 } 00157 while (!success && --retries >= 0); 00158 00159 return success; 00160 } 00161 00162 00164 void Camera1394Driver::poll(void) 00165 { 00166 // Do not run concurrently with reconfig(). 00167 // 00168 // The mutex lock should be sufficient, but the Linux pthreads 00169 // implementation does not guarantee fairness, and the reconfig() 00170 // callback thread generally suffers from lock starvation for many 00171 // seconds before getting to run. So, we avoid acquiring the lock 00172 // if there is a reconfig() pending. 00173 bool do_sleep = true; 00174 if (!reconfiguring_) 00175 { 00176 boost::mutex::scoped_lock lock(mutex_); 00177 do_sleep = (state_ == Driver::CLOSED); 00178 if (!do_sleep) 00179 { 00180 // driver is open, read the next image still holding lock 00181 sensor_msgs::ImagePtr image(new sensor_msgs::Image); 00182 if (read(image)) 00183 { 00184 publish(image); 00185 } 00186 } 00187 } 00188 00189 if (do_sleep) 00190 { 00191 // device was closed or poll is not running, sleeping avoids 00192 // busy wait (DO NOT hold the lock while sleeping) 00193 cycle_.sleep(); 00194 } 00195 } 00196 00201 void Camera1394Driver::publish(const sensor_msgs::ImagePtr &image) 00202 { 00203 image->header.frame_id = config_.frame_id; 00204 00205 // get current CameraInfo data 00206 sensor_msgs::CameraInfoPtr 00207 ci(new sensor_msgs::CameraInfo(cinfo_->getCameraInfo())); 00208 00209 // check whether CameraInfo matches current video mode 00210 if (!dev_->checkCameraInfo(*image, *ci)) 00211 { 00212 // image size does not match: publish a matching uncalibrated 00213 // CameraInfo instead 00214 if (calibration_matches_) 00215 { 00216 // warn user once 00217 calibration_matches_ = false; 00218 ROS_WARN_STREAM("[" << camera_name_ 00219 << "] calibration does not match video mode " 00220 << "(publishing uncalibrated data)"); 00221 } 00222 ci.reset(new sensor_msgs::CameraInfo()); 00223 ci->height = image->height; 00224 ci->width = image->width; 00225 } 00226 else if (!calibration_matches_) 00227 { 00228 // calibration OK now 00229 calibration_matches_ = true; 00230 ROS_WARN_STREAM("[" << camera_name_ 00231 << "] calibration matches video mode now"); 00232 } 00233 00234 // fill in operational parameters 00235 dev_->setOperationalParameters(*ci); 00236 00237 ci->header.frame_id = config_.frame_id; 00238 ci->header.stamp = image->header.stamp; 00239 00240 // @todo log a warning if (filtered) time since last published 00241 // image is not reasonably close to configured frame_rate 00242 00243 // Publish via image_transport 00244 image_pub_.publish(image, ci); 00245 } 00246 00252 bool Camera1394Driver::read(sensor_msgs::ImagePtr &image) 00253 { 00254 bool success = true; 00255 try 00256 { 00257 // Read data from the Camera 00258 ROS_DEBUG_STREAM("[" << camera_name_ << "] reading data"); 00259 dev_->readData(*image); 00260 ROS_DEBUG_STREAM("[" << camera_name_ << "] read returned"); 00261 } 00262 catch (camera1394::Exception& e) 00263 { 00264 ROS_WARN_STREAM("[" << camera_name_ 00265 << "] Exception reading data: " << e.what()); 00266 success = false; 00267 } 00268 return success; 00269 } 00270 00280 void Camera1394Driver::reconfig(Config &newconfig, uint32_t level) 00281 { 00282 // Do not run concurrently with poll(). Tell it to stop running, 00283 // and wait on the lock until it does. 00284 reconfiguring_ = true; 00285 boost::mutex::scoped_lock lock(mutex_); 00286 ROS_DEBUG("dynamic reconfigure level 0x%x", level); 00287 00288 // resolve frame ID using tf_prefix parameter 00289 if (newconfig.frame_id == "") 00290 newconfig.frame_id = "camera"; 00291 std::string tf_prefix = tf::getPrefixParam(priv_nh_); 00292 ROS_DEBUG_STREAM("tf_prefix: " << tf_prefix); 00293 newconfig.frame_id = tf::resolve(tf_prefix, newconfig.frame_id); 00294 00295 if (state_ != Driver::CLOSED && (level & Levels::RECONFIGURE_CLOSE)) 00296 { 00297 // must close the device before updating these parameters 00298 closeCamera(); // state_ --> CLOSED 00299 } 00300 00301 if (state_ == Driver::CLOSED) 00302 { 00303 // open with new values 00304 if (openCamera(newconfig)) 00305 { 00306 // update GUID string parameter 00307 // TODO move into dev_->open() 00308 newconfig.guid = camera_name_; 00309 } 00310 } 00311 00312 if (config_.camera_info_url != newconfig.camera_info_url) 00313 { 00314 // set the new URL and load CameraInfo (if any) from it 00315 if (cinfo_->validateURL(newconfig.camera_info_url)) 00316 { 00317 cinfo_->loadCameraInfo(newconfig.camera_info_url); 00318 } 00319 else 00320 { 00321 // new URL not valid, use the old one 00322 newconfig.camera_info_url = config_.camera_info_url; 00323 } 00324 } 00325 00326 if (state_ != Driver::CLOSED) // openCamera() succeeded? 00327 { 00328 // configure IIDC features 00329 if (level & Levels::RECONFIGURE_CLOSE) 00330 { 00331 // initialize all features for newly opened device 00332 if (false == dev_->features_->initialize(&newconfig)) 00333 { 00334 ROS_ERROR_STREAM("[" << camera_name_ 00335 << "] feature initialization failure"); 00336 closeCamera(); // can't continue 00337 } 00338 } 00339 else 00340 { 00341 // update any features that changed 00342 // TODO replace this with a dev_->reconfigure(&newconfig); 00343 dev_->features_->reconfigure(&newconfig); 00344 } 00345 } 00346 00347 config_ = newconfig; // save new parameters 00348 reconfiguring_ = false; // let poll() run again 00349 00350 ROS_DEBUG_STREAM("[" << camera_name_ 00351 << "] reconfigured: frame_id " << newconfig.frame_id 00352 << ", camera_info_url " << newconfig.camera_info_url); 00353 } 00354 00355 00362 void Camera1394Driver::setup(void) 00363 { 00364 srv_.setCallback(boost::bind(&Camera1394Driver::reconfig, this, _1, _2)); 00365 } 00366 00367 00369 void Camera1394Driver::shutdown(void) 00370 { 00371 closeCamera(); 00372 } 00373 00374 }; // end namespace camera1394_driver