driver1394.cpp
Go to the documentation of this file.
00001 // $Id: driver1394.cpp 38809 2012-02-07 19:28:15Z 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     cycle_(1.0),                        // slow poll when closed
00079     retries_(0),
00080     dev_(new camera1394::Camera1394()),
00081     srv_(priv_nh),
00082     cinfo_(new camera_info_manager::CameraInfoManager(camera_nh_)),
00083     calibration_matches_(true),
00084     it_(new image_transport::ImageTransport(camera_nh_)),
00085     image_pub_(it_->advertiseCamera("image_raw", 1)),
00086 //    compressed_pub_(camera_nh_.advertise<sensor_msgs::CompressedImage>("image_raw/compressed", 1)),
00087 //    cinfo_pub_(camera_nh_.advertise<sensor_msgs::CameraInfo>("camera_info", 1)),
00088     diagnostics_(),
00089     topic_diagnostics_min_freq_(0.),
00090     topic_diagnostics_max_freq_(1000.),
00091     topic_diagnostics_("image_raw", diagnostics_,
00092                        diagnostic_updater::FrequencyStatusParam
00093                        (&topic_diagnostics_min_freq_,
00094                         &topic_diagnostics_max_freq_, 0.1, 10),
00095                        diagnostic_updater::TimeStampStatusParam
00096                        ())
00097   {}
00098 
00099   Camera1394Driver::~Camera1394Driver()
00100   {}
00101 
00106   void Camera1394Driver::closeCamera()
00107   {
00108     if (state_ != Driver::CLOSED)
00109       {
00110         ROS_INFO_STREAM("[" << camera_name_ << "] closing device");
00111         dev_->close();
00112         state_ = Driver::CLOSED;
00113       }
00114   }
00115 
00128   bool Camera1394Driver::openCamera(Config &newconfig)
00129   {
00130     bool success = false;
00131 
00132     try
00133       {
00134         if (0 == dev_->open(newconfig))
00135           {
00136             if (camera_name_ != dev_->device_id_)
00137               {
00138                 camera_name_ = dev_->device_id_;
00139                 if (!cinfo_->setCameraName(camera_name_))
00140                   {
00141                     // GUID is 16 hex digits, which should be valid.
00142                     // If not, use it for log messages anyway.
00143                     ROS_WARN_STREAM("[" << camera_name_
00144                                     << "] name not valid"
00145                                     << " for camera_info_manger");
00146                   }
00147               }
00148             ROS_INFO_STREAM("[" << camera_name_ << "] opened: "
00149                             << newconfig.video_mode << ", "
00150                             << newconfig.frame_rate << " fps, "
00151                             << newconfig.iso_speed << " Mb/s");
00152             state_ = Driver::OPENED;
00153             calibration_matches_ = true;
00154             newconfig.guid = camera_name_; // update configuration parameter
00155             retries_ = 0;
00156             success = true;
00157           }
00158       }
00159     catch (camera1394::Exception& e)
00160       {
00161         state_ = Driver::CLOSED;    // since the open() failed
00162         if (retries_++ > 0)
00163           ROS_DEBUG_STREAM("[" << camera_name_
00164                            << "] exception opening device (retrying): "
00165                            << e.what());
00166         else
00167           ROS_ERROR_STREAM("[" << camera_name_
00168                            << "] device open failed: " << e.what());
00169       }
00170 
00171     // update diagnostics parameters
00172     diagnostics_.setHardwareID(camera_name_);
00173     double delta = newconfig.frame_rate * 0.1; // allow 10% error margin
00174     topic_diagnostics_min_freq_ = newconfig.frame_rate - delta;
00175     topic_diagnostics_max_freq_ = newconfig.frame_rate + delta;
00176 
00177     return success;
00178   }
00179 
00180 
00182   void Camera1394Driver::poll(void)
00183   {
00184     // Do not run concurrently with reconfig().
00185     //
00186     // The mutex lock should be sufficient, but the Linux pthreads
00187     // implementation does not guarantee fairness, and the reconfig()
00188     // callback thread generally suffers from lock starvation for many
00189     // seconds before getting to run.  So, we avoid acquiring the lock
00190     // if there is a reconfig() pending.
00191     bool do_sleep = true;
00192     if (!reconfiguring_)
00193       {
00194         boost::mutex::scoped_lock lock(mutex_);
00195         if (state_ == Driver::CLOSED)
00196           {
00197             openCamera(config_);        // open with current configuration
00198           }
00199         do_sleep = (state_ == Driver::CLOSED);
00200         if (!do_sleep)                  // openCamera() succeeded?
00201           {
00202             // driver is open, read the next image still holding lock
00203             sensor_msgs::ImagePtr image(new sensor_msgs::Image);
00204             if (read(image))
00205               {
00206                 publish(image);
00207               }
00208           }
00209       } // release mutex lock
00210 
00211     // Always run the diagnostics updater: no lock required.
00212     diagnostics_.update();
00213 
00214     if (do_sleep)
00215       {
00216         // device was closed or poll is not running, sleeping avoids
00217         // busy wait (DO NOT hold the lock while sleeping)
00218         cycle_.sleep();
00219       }
00220   }
00221 
00226   void Camera1394Driver::publish(const sensor_msgs::ImagePtr &image)
00227   {
00228     image->header.frame_id = config_.frame_id;
00229 
00230     // get current CameraInfo data
00231     sensor_msgs::CameraInfoPtr
00232       ci(new sensor_msgs::CameraInfo(cinfo_->getCameraInfo()));
00233 
00234     // check whether CameraInfo matches current video mode
00235     if (!dev_->checkCameraInfo(*image, *ci))
00236       {
00237         // image size does not match: publish a matching uncalibrated
00238         // CameraInfo instead
00239         if (calibration_matches_)
00240           {
00241             // warn user once
00242             calibration_matches_ = false;
00243             ROS_WARN_STREAM("[" << camera_name_
00244                             << "] calibration does not match video mode "
00245                             << "(publishing uncalibrated data)");
00246           }
00247         ci.reset(new sensor_msgs::CameraInfo());
00248         ci->height = image->height;
00249         ci->width = image->width;
00250       }
00251     else if (!calibration_matches_)
00252       {
00253         // calibration OK now
00254         calibration_matches_ = true;
00255         ROS_WARN_STREAM("[" << camera_name_
00256                         << "] calibration matches video mode now");
00257       }
00258 
00259     // fill in operational parameters
00260     dev_->setOperationalParameters(*ci);
00261 
00262     ci->header.frame_id = config_.frame_id;
00263     ci->header.stamp = image->header.stamp;
00264 
00265 //    if (config_.video_mode == "format7_mode6")
00266 //      {
00267         // TP: Publish compressed images on image_raw/compressed.
00268         // Format7 modes are camera specific, this applies to Ladybug3 camera.
00269 //        sensor_msgs::CompressedImage::Ptr compressed(new sensor_msgs::CompressedImage);
00270 //        compressed->header = image->header;
00271 //        compressed->format = "jpeg";
00272 //        compressed->data = image->data;
00273 //        compressed_pub_.publish(compressed);
00274 //        cinfo_pub_.publish(ci);
00275 //      }
00276 //    else
00277 //      {
00278         // Publish via image_transport
00279         image_pub_.publish(image, ci);
00280 //      }
00281 
00282 
00283     // Notify diagnostics that a message has been published. That will
00284     // generate a warning if messages are not published at nearly the
00285     // configured frame_rate.
00286     topic_diagnostics_.tick(image->header.stamp);
00287   }
00288 
00294   bool Camera1394Driver::read(sensor_msgs::ImagePtr &image)
00295   {
00296     bool success = true;
00297     try
00298       {
00299         // Read data from the Camera
00300         ROS_DEBUG_STREAM("[" << camera_name_ << "] reading data");
00301         dev_->readData(*image);
00302         ROS_DEBUG_STREAM("[" << camera_name_ << "] read returned");
00303       }
00304     catch (camera1394::Exception& e)
00305       {
00306         ROS_WARN_STREAM("[" << camera_name_
00307                         << "] Exception reading data: " << e.what());
00308         success = false;
00309       }
00310     return success;
00311   }
00312 
00322   void Camera1394Driver::reconfig(Config &newconfig, uint32_t level)
00323   {
00324     // Do not run concurrently with poll().  Tell it to stop running,
00325     // and wait on the lock until it does.
00326     reconfiguring_ = true;
00327     boost::mutex::scoped_lock lock(mutex_);
00328     ROS_DEBUG("dynamic reconfigure level 0x%x", level);
00329 
00330     // resolve frame ID using tf_prefix parameter
00331     if (newconfig.frame_id == "")
00332       newconfig.frame_id = "camera";
00333     std::string tf_prefix = tf::getPrefixParam(priv_nh_);
00334     ROS_DEBUG_STREAM("tf_prefix: " << tf_prefix);
00335     newconfig.frame_id = tf::resolve(tf_prefix, newconfig.frame_id);
00336 
00337     if (state_ != Driver::CLOSED && (level & Levels::RECONFIGURE_CLOSE))
00338       {
00339         // must close the device before updating these parameters
00340         closeCamera();                  // state_ --> CLOSED
00341       }
00342 
00343     if (state_ == Driver::CLOSED)
00344       {
00345         // open with new values
00346         openCamera(newconfig);
00347       }
00348 
00349     if (config_.camera_info_url != newconfig.camera_info_url)
00350       {
00351         // set the new URL and load CameraInfo (if any) from it
00352         if (cinfo_->validateURL(newconfig.camera_info_url))
00353           {
00354             cinfo_->loadCameraInfo(newconfig.camera_info_url);
00355           }
00356         else
00357           {
00358             // new URL not valid, use the old one
00359             newconfig.camera_info_url = config_.camera_info_url;
00360           }
00361       }
00362 
00363     if (state_ != Driver::CLOSED)       // openCamera() succeeded?
00364       {
00365         // configure IIDC features
00366         if (level & Levels::RECONFIGURE_CLOSE)
00367           {
00368             // initialize all features for newly opened device
00369             if (false == dev_->features_->initialize(&newconfig))
00370               {
00371                 ROS_ERROR_STREAM("[" << camera_name_
00372                                  << "] feature initialization failure");
00373                 closeCamera();          // can't continue
00374               }
00375           }
00376         else
00377           {
00378             // update any features that changed
00379             // TODO replace this with a dev_->reconfigure(&newconfig);
00380             dev_->features_->reconfigure(&newconfig);
00381           }
00382       }
00383 
00384     config_ = newconfig;                // save new parameters
00385     reconfiguring_ = false;             // let poll() run again
00386 
00387     ROS_DEBUG_STREAM("[" << camera_name_
00388                      << "] reconfigured: frame_id " << newconfig.frame_id
00389                      << ", camera_info_url " << newconfig.camera_info_url);
00390   }
00391 
00392 
00399   void Camera1394Driver::setup(void)
00400   {
00401     srv_.setCallback(boost::bind(&Camera1394Driver::reconfig, this, _1, _2));
00402   }
00403 
00404 
00406   void Camera1394Driver::shutdown(void)
00407   {
00408     closeCamera();
00409   }
00410 
00411 }; // end namespace camera1394_driver
 All Classes Namespaces Files Functions Variables Typedefs Friends Defines


camera1394
Author(s): Jack O'Quin, Ken Tossell, Patrick Beeson, Nate Koenig, Andrew Howard, Damien Douxchamps, Dan Dennedy Tomas Petricek / petrito1@cmp.felk.cvut.cz
autogenerated on Tue Dec 10 2013 14:25:10