driver1394stereo.cpp
Go to the documentation of this file.
1 // $Id: driver1394.cpp 35691 2011-02-02 04:28:58Z joq $
2 
3 /*********************************************************************
4 * Software License Agreement (BSD License)
5 *
6 * Copyright (C) 2009, 2010 Jack O'Quin, Patrick Beeson
7 * All rights reserved.
8 *
9 * Redistribution and use in source and binary forms, with or without
10 * modification, are permitted provided that the following conditions
11 * are met:
12 *
13 * * Redistributions of source code must retain the above copyright
14 * notice, this list of conditions and the following disclaimer.
15 * * Redistributions in binary form must reproduce the above
16 * copyright notice, this list of conditions and the following
17 * disclaimer in the documentation and/or other materials provided
18 * with the distribution.
19 * * Neither the name of the author nor other contributors may be
20 * used to endorse or promote products derived from this software
21 * without specific prior written permission.
22 *
23 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34 * POSSIBILITY OF SUCH DAMAGE.
35 *********************************************************************/
36 
37 #include <boost/format.hpp>
38 
39 #include <tf/transform_listener.h>
40 
41 #include "driver1394stereo.h"
42 #include "camera1394stereo/Camera1394StereoConfig.h"
43 #include "featuresstereo.h"
44 
71 {
72  // some convenience typedefs
73  typedef camera1394stereo::Camera1394StereoConfig Config;
75 
76  const std::string Camera1394StereoDriver::CameraSelectorString[NUM_CAMERAS] = {"left","right"};
77 
79  ros::NodeHandle camera_nh):
80  state_(Driver::CLOSED),
81  reconfiguring_(false),
82  priv_nh_(priv_nh),
83  camera_nh_(camera_nh),
84  camera_name_("stereo_camera"),
85  dev_(new camera1394stereo::Camera1394Stereo()),
86  srv_(priv_nh),
87  cycle_(1.0), // slow poll when closed
88  it_(new image_transport::ImageTransport(camera_nh_))
89  {
90  for (int i=0; i< NUM_CAMERAS; i++)
91  {
92  single_camera_nh_[i] = ros::NodeHandle(camera_nh_,CameraSelectorString[i]); // for i-th CameraInfoManager
94  calibration_matches_[i] = true;
95  image_pub_[i] = it_->advertiseCamera(CameraSelectorString[i]+"/image_raw", 1);
96  }
97  }
98 
100  {}
101 
107  {
108  if (state_ != Driver::CLOSED)
109  {
110  ROS_INFO_STREAM("[" << camera_name_ << "] closing device");
111  dev_->close();
113  }
114  }
115 
125  bool Camera1394StereoDriver::openCamera(Config &newconfig)
126  {
127  bool success = false;
128  int retries = 2; // number of retries, if open fails
129  do
130  {
131  try
132  {
133  if (0 == dev_->open(newconfig))
134  {
135  if (camera_name_ != dev_->device_id_)
136  {
137  camera_name_ = dev_->device_id_;
138  for (int i=0; i<NUM_CAMERAS; i++)
139  if ( ! cinfo_[i]->setCameraName(camera_name_ + "_" +
140  CameraSelectorString[i] ) )
141  {
142  // GUID is 16 hex digits, which should be valid.
143  // If not, use it for log messages anyway.
145  <<"_"<<CameraSelectorString[i]
146  << "] name not valid"
147  << " for camera_info_manger");
148  }
149  }
150  ROS_INFO_STREAM("[" << camera_name_ << "] opened: "
151  << newconfig.video_mode << ", "
152  << newconfig.frame_rate << " fps, "
153  << newconfig.iso_speed << " Mb/s");
155  for (int i=0; i<NUM_CAMERAS; i++)
156  calibration_matches_[i] = true;
157  success = true;
158  }
159  }
160  catch (camera1394stereo::Exception& e)
161  {
162  state_ = Driver::CLOSED; // since the open() failed
163  if (retries > 0)
164  {
166  << "] exception opening device (retrying): "
167  << e.what());
168  ROS_WARN_STREAM("Trying to reset bus with system call...");
169  if ( system("dc1394_reset_bus") == 0 )
170  ROS_WARN_STREAM("Bus reset system call successful");
171  else
172  ROS_WARN_STREAM("Bus reset system call failure");
173  }
174  else
176  << "] device open failed: " << e.what());
177  }
178  }
179  while (!success && --retries >= 0);
180 
181  return success;
182  }
183 
184 
187  {
188  // Do not run concurrently with reconfig().
189  //
190  // The mutex lock should be sufficient, but the Linux pthreads
191  // implementation does not guarantee fairness, and the reconfig()
192  // callback thread generally suffers from lock starvation for many
193  // seconds before getting to run. So, we avoid acquiring the lock
194  // if there is a reconfig() pending.
195  bool do_sleep = true;
196  if (!reconfiguring_)
197  {
198  boost::mutex::scoped_lock lock(mutex_);
199  do_sleep = (state_ == Driver::CLOSED);
200  if (!do_sleep)
201  {
202  // driver is open, read the next image still holding lock
203  sensor_msgs::ImagePtr image[NUM_CAMERAS];
204  for (int i=0; i<NUM_CAMERAS; i++)
205  image[i] = sensor_msgs::ImagePtr(new sensor_msgs::Image);
206  if (read(image))
207  {
208  publish(image);
209  }
210  }
211  }
212 
213  if (do_sleep)
214  {
215  // device was closed or poll is not running, sleeping avoids
216  // busy wait (DO NOT hold the lock while sleeping)
217  cycle_.sleep();
218  }
219  }
220 
225  void Camera1394StereoDriver::publish(const sensor_msgs::ImagePtr image[NUM_CAMERAS])
226  {
227  for (int i=0; i<NUM_CAMERAS; i++)
228  {
229  image[i]->header.frame_id = config_.frame_id;
230 
231  // get current CameraInfo data
232  sensor_msgs::CameraInfoPtr
233  ci(new sensor_msgs::CameraInfo(cinfo_[i]->getCameraInfo()));
234 
235  // check whether CameraInfo matches current video mode
236  if (!dev_->checkCameraInfo(*(image[i]), *ci))
237  {
238  // image size does not match: publish a matching uncalibrated
239  // CameraInfo instead
240  if (calibration_matches_[i])
241  {
242  // warn user once
243  calibration_matches_[i] = false;
245  << "_" << CameraSelectorString[i]
246  << "] calibration does not match video mode "
247  << "(publishing uncalibrated data)");
248  }
249  ci.reset(new sensor_msgs::CameraInfo());
250  ci->height = image[i]->height;
251  ci->width = image[i]->width;
252  }
253  else if (!calibration_matches_[i])
254  {
255  // calibration OK now
256  calibration_matches_[i] = true;
258  << "_" << CameraSelectorString[i]
259  << "] calibration matches video mode now");
260  }
261 
262  // fill in operational parameters
263  dev_->setOperationalParameters(*ci);
264 
265  ci->header.frame_id = config_.frame_id;
266  ci->header.stamp = image[i]->header.stamp;
267 
268  // @todo log a warning if (filtered) time since last published
269  // image is not reasonably close to configured frame_rate
270 
271  // Publish via image_transport
272  image_pub_[i].publish(image[i], ci);
273  }
274  }
275 
281  bool Camera1394StereoDriver::read(sensor_msgs::ImagePtr image[NUM_CAMERAS])
282  {
283  bool success = true;
284  try
285  {
286  // Read data from the Camera
287  ROS_DEBUG_STREAM("[" << camera_name_ << "] reading data");
288  success = dev_->readData(*(image[LEFT]), *(image[RIGHT]));
289  ROS_DEBUG_STREAM("[" << camera_name_ << "] read returned");
290  }
291  catch (camera1394stereo::Exception& e)
292  {
294  << "] Exception reading data: " << e.what());
295  success = false;
296  }
297  return success;
298  }
299 
309  void Camera1394StereoDriver::reconfig(Config &newconfig, uint32_t level)
310  {
311  // Do not run concurrently with poll(). Tell it to stop running,
312  // and wait on the lock until it does.
313  reconfiguring_ = true;
314  boost::mutex::scoped_lock lock(mutex_);
315  ROS_DEBUG("dynamic reconfigure level 0x%x", level);
316 
317  // resolve frame ID using tf_prefix parameter
318  if (newconfig.frame_id == "")
319  newconfig.frame_id = "camera";
320  std::string tf_prefix = tf::getPrefixParam(priv_nh_);
321  ROS_DEBUG_STREAM("tf_prefix: " << tf_prefix);
322  newconfig.frame_id = tf::resolve(tf_prefix, newconfig.frame_id);
323 
324  if (state_ != Driver::CLOSED && (level & Levels::RECONFIGURE_CLOSE))
325  {
326  // must close the device before updating these parameters
327  closeCamera(); // state_ --> CLOSED
328  }
329 
330  if (state_ == Driver::CLOSED)
331  {
332  // open with new values
333  if (openCamera(newconfig))
334  {
335  // update GUID string parameter
336  // TODO move into dev_->open()
337  newconfig.guid = camera_name_;
338  }
339  }
340 
341  std::string camera_info_url[NUM_CAMERAS];
342  camera_info_url[LEFT] = config_.camera_info_url_left;
343  camera_info_url[RIGHT] = config_.camera_info_url_right;
344  std::string new_camera_info_url[NUM_CAMERAS];
345  new_camera_info_url[LEFT] = newconfig.camera_info_url_left;
346  new_camera_info_url[RIGHT] = newconfig.camera_info_url_right;
347 
348  for (int i=0; i<NUM_CAMERAS; i++)
349  {
350  if (camera_info_url[i] != new_camera_info_url[i])
351  {
352  // set the new URL and load CameraInfo (if any) from it
353  if (cinfo_[i]->validateURL(new_camera_info_url[i]))
354  {
355  cinfo_[i]->loadCameraInfo(new_camera_info_url[i]);
356  }
357  else
358  {
359  // new URL not valid, use the old one
361  << "_" << CameraSelectorString[i]
362  << "] not updating calibration to invalid URL "
363  << new_camera_info_url[i] );
364  }
365  }
366  }
367  if (state_ != Driver::CLOSED) // openCamera() succeeded?
368  {
369  // configure IIDC features
370  if (level & Levels::RECONFIGURE_CLOSE)
371  {
372  // initialize all features for newly opened device
373  if (false == dev_->features_->initialize(&newconfig))
374  {
376  << "] feature initialization failure");
377  closeCamera(); // can't continue
378  }
379  }
380  else
381  {
382  // update any features that changed
383  // TODO replace this with a dev_->reconfigure(&newconfig);
384  dev_->features_->reconfigure(&newconfig);
385  }
386  }
387 
388  config_ = newconfig; // save new parameters
389  reconfiguring_ = false; // let poll() run again
390 
392  << "] reconfigured: frame_id " << newconfig.frame_id
393  << ", camera_info_url_left " << newconfig.camera_info_url_left
394  << ", camera_info_url_right " << newconfig.camera_info_url_right);
395  }
396 
397 
405  {
406  srv_.setCallback(boost::bind(&Camera1394StereoDriver::reconfig, this, _1, _2));
407  }
408 
409 
412  {
413  closeCamera();
414  }
415 
416 }; // end namespace camera1394_driver
image_transport::CameraPublisher image_pub_[NUM_CAMERAS]
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
void reconfig(camera1394stereo::Camera1394StereoConfig &newconfig, uint32_t level)
std::string getPrefixParam(ros::NodeHandle &nh)
static const std::string CameraSelectorString[NUM_CAMERAS]
std::string resolve(const std::string &prefix, const std::string &frame_name)
Camera1394 features interface.
boost::shared_ptr< camera1394stereo::Camera1394Stereo > dev_
camera1394stereo::Camera1394StereoConfig Config
camera1394stereo::Camera1394StereoConfig config_
void publish(const sensor_msgs::ImagePtr image[NUM_CAMERAS])
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
bool sleep()
boost::shared_ptr< camera_info_manager::CameraInfoManager > cinfo_[NUM_CAMERAS]
bool read(sensor_msgs::ImagePtr image[NUM_CAMERAS])
#define ROS_INFO_STREAM(args)
dynamic_reconfigure::Server< camera1394stereo::Camera1394StereoConfig > srv_
#define ROS_ERROR_STREAM(args)
static const uint32_t RECONFIGURE_CLOSE
Camera1394StereoDriver Driver
ROS driver interface for IIDC-compatible IEEE 1394 digital cameras.
boost::shared_ptr< image_transport::ImageTransport > it_
#define ROS_DEBUG(...)
Camera1394StereoDriver(ros::NodeHandle priv_nh, ros::NodeHandle camera_nh)


camera1394stereo
Author(s): Joan Pau Beltran
autogenerated on Mon Jun 10 2019 12:52:45