driver1394.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (C) 2009, 2010 Jack O'Quin, Patrick Beeson
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the author nor other contributors may be
18 * used to endorse or promote products derived from this software
19 * without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #include <boost/format.hpp>
36 
37 #include <tf/transform_listener.h>
38 
39 #include "driver1394.h"
40 #include "camera1394/Camera1394Config.h"
41 #include "features.h"
42 
62 {
63  // some convenience typedefs
64  typedef camera1394::Camera1394Config Config;
66 
68  ros::NodeHandle camera_nh):
69  state_(Driver::CLOSED),
70  reconfiguring_(false),
71  priv_nh_(priv_nh),
72  camera_nh_(camera_nh),
73  camera_name_("camera"),
74  cycle_(1.0), // slow poll when closed
75  retries_(0),
76  consecutive_read_errors_(0),
77  dev_(new camera1394::Camera1394()),
78  srv_(priv_nh),
79  cinfo_(new camera_info_manager::CameraInfoManager(camera_nh_)),
80  calibration_matches_(true),
81  it_(new image_transport::ImageTransport(camera_nh_)),
82  image_pub_(it_->advertiseCamera("image_raw", 1)),
83  get_camera_registers_srv_(camera_nh_.advertiseService(
84  "get_camera_registers",
85  &Camera1394Driver::getCameraRegisters, this)),
86  set_camera_registers_srv_(camera_nh_.advertiseService(
87  "set_camera_registers",
88  &Camera1394Driver::setCameraRegisters, this)),
89  diagnostics_(),
90  topic_diagnostics_min_freq_(0.),
91  topic_diagnostics_max_freq_(1000.),
92  topic_diagnostics_("image_raw", diagnostics_,
93  diagnostic_updater::FrequencyStatusParam
94  (&topic_diagnostics_min_freq_,
95  &topic_diagnostics_max_freq_, 0.1, 10),
96  diagnostic_updater::TimeStampStatusParam())
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 
128  bool Camera1394Driver::openCamera(Config &newconfig)
129  {
130  bool success = false;
131 
132  try
133  {
134  if (0 == dev_->open(newconfig))
135  {
136  if (camera_name_ != dev_->device_id_)
137  {
138  camera_name_ = dev_->device_id_;
139  if (!cinfo_->setCameraName(camera_name_))
140  {
141  // GUID is 16 hex digits, which should be valid.
142  // If not, use it for log messages anyway.
144  << "] name not valid"
145  << " for camera_info_manger");
146  }
147  }
148  ROS_INFO_STREAM("[" << camera_name_ << "] opened: "
149  << newconfig.video_mode << ", "
150  << newconfig.frame_rate << " fps, "
151  << newconfig.iso_speed << " Mb/s");
153  calibration_matches_ = true;
154  newconfig.guid = camera_name_; // update configuration parameter
155  retries_ = 0;
156  success = true;
157  }
158  }
159  catch (camera1394::Exception& e)
160  {
161  state_ = Driver::CLOSED; // since the open() failed
162  if (retries_++ > 0)
164  << "] exception opening device (retrying): "
165  << e.what());
166  else
168  << "] device open failed: " << e.what());
169  }
170 
171  // update diagnostics parameters
173  double delta = newconfig.frame_rate * 0.1; // allow 10% error margin
174  topic_diagnostics_min_freq_ = newconfig.frame_rate - delta;
175  topic_diagnostics_max_freq_ = newconfig.frame_rate + delta;
176 
178  return success;
179  }
180 
181 
184  {
185  // Do not run concurrently with reconfig().
186  //
187  // The mutex lock should be sufficient, but the Linux pthreads
188  // implementation does not guarantee fairness, and the reconfig()
189  // callback thread generally suffers from lock starvation for many
190  // seconds before getting to run. So, we avoid acquiring the lock
191  // if there is a reconfig() pending.
192  bool do_sleep = true;
193  if (!reconfiguring_)
194  {
195  boost::mutex::scoped_lock lock(mutex_);
196  if (state_ == Driver::CLOSED)
197  {
198  openCamera(config_); // open with current configuration
199  }
200  do_sleep = (state_ == Driver::CLOSED);
201  if (!do_sleep) // openCamera() succeeded?
202  {
203  // driver is open, read the next image still holding lock
204  sensor_msgs::ImagePtr image(new sensor_msgs::Image);
205  if (read(image))
206  {
207  publish(image);
209  }
210  else if (++consecutive_read_errors_ > config_.max_consecutive_errors
211  && config_.max_consecutive_errors > 0)
212  {
213  ROS_WARN("reached %u consecutive read errrors, disconnecting",
215  closeCamera();
216  }
217  }
218  } // release mutex lock
219 
220  // Always run the diagnostics updater: no lock required.
222 
223  if (do_sleep)
224  {
225  // device was closed or poll is not running, sleeping avoids
226  // busy wait (DO NOT hold the lock while sleeping)
227  cycle_.sleep();
228  }
229  }
230 
235  void Camera1394Driver::publish(const sensor_msgs::ImagePtr &image)
236  {
237  image->header.frame_id = config_.frame_id;
238 
239  // get current CameraInfo data
240  sensor_msgs::CameraInfoPtr
241  ci(new sensor_msgs::CameraInfo(cinfo_->getCameraInfo()));
242 
243  // check whether CameraInfo matches current video mode
244  if (!dev_->checkCameraInfo(*image, *ci))
245  {
246  // image size does not match: publish a matching uncalibrated
247  // CameraInfo instead
249  {
250  // warn user once
251  calibration_matches_ = false;
253  << "] calibration does not match video mode "
254  << "(publishing uncalibrated data)");
255  }
256  ci.reset(new sensor_msgs::CameraInfo());
257  ci->height = image->height;
258  ci->width = image->width;
259  }
260  else if (!calibration_matches_)
261  {
262  // calibration OK now
263  calibration_matches_ = true;
265  << "] calibration matches video mode now");
266  }
267 
268  // fill in operational parameters
269  dev_->setOperationalParameters(*ci);
270 
271  ci->header.frame_id = config_.frame_id;
272  ci->header.stamp = image->header.stamp;
273 
274  // Publish via image_transport
275  image_pub_.publish(image, ci);
276 
277  // Notify diagnostics that a message has been published. That will
278  // generate a warning if messages are not published at nearly the
279  // configured frame_rate.
280  topic_diagnostics_.tick(image->header.stamp);
281  }
282 
288  bool Camera1394Driver::read(sensor_msgs::ImagePtr &image)
289  {
290  bool success = true;
291  try
292  {
293  // Read data from the Camera
294  ROS_DEBUG_STREAM("[" << camera_name_ << "] reading data");
295  success = dev_->readData(*image);
296  ROS_DEBUG_STREAM("[" << camera_name_ << "] read returned");
297  }
298  catch (camera1394::Exception& e)
299  {
301  << "] Exception reading data: " << e.what());
302  success = false;
303  }
304  return success;
305  }
306 
316  void Camera1394Driver::reconfig(Config &newconfig, uint32_t level)
317  {
318  // Do not run concurrently with poll(). Tell it to stop running,
319  // and wait on the lock until it does.
320  reconfiguring_ = true;
321  boost::mutex::scoped_lock lock(mutex_);
322  ROS_DEBUG("dynamic reconfigure level 0x%x", level);
323 
324  // resolve frame ID using tf_prefix parameter
325  if (newconfig.frame_id == "")
326  newconfig.frame_id = "camera";
327  std::string tf_prefix = tf::getPrefixParam(priv_nh_);
328  ROS_DEBUG_STREAM("tf_prefix: " << tf_prefix);
329  newconfig.frame_id = tf::resolve(tf_prefix, newconfig.frame_id);
330 
331  if (state_ != Driver::CLOSED && (level & Levels::RECONFIGURE_CLOSE))
332  {
333  // must close the device before updating these parameters
334  closeCamera(); // state_ --> CLOSED
335  }
336 
337  if (state_ == Driver::CLOSED)
338  {
339  // open with new values
340  openCamera(newconfig);
341  }
342 
343  if (config_.camera_info_url != newconfig.camera_info_url)
344  {
345  // set the new URL and load CameraInfo (if any) from it
346  if (cinfo_->validateURL(newconfig.camera_info_url))
347  {
348  cinfo_->loadCameraInfo(newconfig.camera_info_url);
349  }
350  else
351  {
352  // new URL not valid, use the old one
353  newconfig.camera_info_url = config_.camera_info_url;
354  }
355  }
356 
357  if (state_ != Driver::CLOSED) // openCamera() succeeded?
358  {
359  // configure IIDC features
360  if (level & Levels::RECONFIGURE_CLOSE)
361  {
362  // initialize all features for newly opened device
363  if (false == dev_->features_->initialize(&newconfig))
364  {
366  << "] feature initialization failure");
367  closeCamera(); // can't continue
368  }
369  }
370  else
371  {
372  // update any features that changed
373  // TODO replace this with a direct call to
374  // Feature::reconfigure(&newconfig);
375  dev_->features_->reconfigure(&newconfig);
376  }
377  }
378 
379  config_ = newconfig; // save new parameters
380  reconfiguring_ = false; // let poll() run again
381 
383  << "] reconfigured: frame_id " << newconfig.frame_id
384  << ", camera_info_url " << newconfig.camera_info_url);
385  }
386 
387 
395  {
396  srv_.setCallback(boost::bind(&Camera1394Driver::reconfig, this, _1, _2));
397  }
398 
399 
402  {
403  closeCamera();
404  }
405 
408  camera1394::GetCameraRegisters::Request &request,
409  camera1394::GetCameraRegisters::Response &response)
410  {
411  typedef camera1394::GetCameraRegisters::Request Request;
412  boost::mutex::scoped_lock lock(mutex_);
413  if (state_ == Driver::CLOSED)
414  {
415  return false;
416  }
417  if (request.num_regs < 1
418  || (request.type != Request::TYPE_CONTROL
419  && request.type != Request::TYPE_ADVANCED_CONTROL))
420  {
421  request.num_regs = 1;
422  }
423  response.value.resize(request.num_regs);
424 
425  bool success = false;
426  switch (request.type)
427  {
428  case Request::TYPE_CONTROL:
429  success = dev_->registers_->getControlRegisters(
430  request.offset, request.num_regs, response.value);
431  break;
432  case Request::TYPE_ABSOLUTE:
433  success = dev_->registers_->getAbsoluteRegister(
434  request.offset, request.mode, response.value[0]);
435  break;
436  case Request::TYPE_FORMAT7:
437  success = dev_->registers_->getFormat7Register(
438  request.offset, request.mode, response.value[0]);
439  break;
440  case Request::TYPE_ADVANCED_CONTROL:
441  success = dev_->registers_->getAdvancedControlRegisters(
442  request.offset, request.num_regs, response.value);
443  break;
444  case Request::TYPE_PIO:
445  success = dev_->registers_->getPIORegister(
446  request.offset, response.value[0]);
447  break;
448  case Request::TYPE_SIO:
449  success = dev_->registers_->getSIORegister(
450  request.offset, response.value[0]);
451  break;
452  case Request::TYPE_STROBE:
453  success = dev_->registers_->getStrobeRegister(
454  request.offset, response.value[0]);
455  break;
456  }
457 
458  if (!success)
459  {
460  ROS_WARN("[%s] getting register failed: type %u, offset %lu",
461  camera_name_.c_str(), request.type, request.offset);
462  }
463  return success;
464  }
465 
468  camera1394::SetCameraRegisters::Request &request,
469  camera1394::SetCameraRegisters::Response &response)
470  {
471  typedef camera1394::SetCameraRegisters::Request Request;
472  if (request.value.size() == 0)
473  return true;
474  boost::mutex::scoped_lock lock(mutex_);
475  if (state_ == Driver::CLOSED)
476  return false;
477  bool success = false;
478  switch (request.type)
479  {
480  case Request::TYPE_CONTROL:
481  success = dev_->registers_->setControlRegisters(
482  request.offset, request.value);
483  break;
484  case Request::TYPE_ABSOLUTE:
485  success = dev_->registers_->setAbsoluteRegister(
486  request.offset, request.mode, request.value[0]);
487  break;
488  case Request::TYPE_FORMAT7:
489  success = dev_->registers_->setFormat7Register(
490  request.offset, request.mode, request.value[0]);
491  break;
492  case Request::TYPE_ADVANCED_CONTROL:
493  success = dev_->registers_->setAdvancedControlRegisters(
494  request.offset, request.value);
495  break;
496  case Request::TYPE_PIO:
497  success = dev_->registers_->setPIORegister(
498  request.offset, request.value[0]);
499  break;
500  case Request::TYPE_SIO:
501  success = dev_->registers_->setSIORegister(
502  request.offset, request.value[0]);
503  break;
504  case Request::TYPE_STROBE:
505  success = dev_->registers_->setStrobeRegister(
506  request.offset, request.value[0]);
507  break;
508  }
509 
510  if (!success)
511  {
512  ROS_WARN("[%s] setting register failed: type %u, offset %lu",
513  camera_name_.c_str(), request.type, request.offset);
514  }
515  return success;
516  }
517 
518 }; // end namespace camera1394_driver
boost::shared_ptr< camera_info_manager::CameraInfoManager > cinfo_
Definition: driver1394.h:127
dynamic_reconfigure::Server< camera1394::Camera1394Config > srv_
Definition: driver1394.h:124
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
bool setCameraRegisters(camera1394::SetCameraRegisters::Request &request, camera1394::SetCameraRegisters::Response &response)
Definition: driver1394.cpp:467
std::string getPrefixParam(ros::NodeHandle &nh)
static const uint32_t RECONFIGURE_CLOSE
Definition: driver1394.h:70
void setHardwareID(const std::string &hwid)
diagnostic_updater::TopicDiagnostic topic_diagnostics_
Definition: driver1394.h:142
static const uint8_t CLOSED
Definition: driver1394.h:80
static const uint8_t OPENED
Definition: driver1394.h:81
ServiceServer advertiseService(ros::NodeHandle n, std::string name, boost::function< bool(const typename ActionSpec::_action_goal_type::_goal_type &, typename ActionSpec::_action_result_type::_result_type &result)> service_cb)
Camera1394Driver(ros::NodeHandle priv_nh, ros::NodeHandle camera_nh)
Definition: driver1394.cpp:67
diagnostic_updater::Updater diagnostics_
Definition: driver1394.h:139
#define ROS_WARN(...)
bool read(sensor_msgs::ImagePtr &image)
Definition: driver1394.cpp:288
std::string resolve(const std::string &prefix, const std::string &frame_name)
Camera1394Driver Driver
Definition: driver1394.cpp:65
image_transport::CameraPublisher image_pub_
Definition: driver1394.h:132
ROS driver interface for IIDC-compatible IEEE 1394 digital cameras.
bool openCamera(Config &newconfig)
Definition: driver1394.cpp:128
bool getCameraRegisters(camera1394::GetCameraRegisters::Request &request, camera1394::GetCameraRegisters::Response &response)
Definition: driver1394.cpp:407
boost::shared_ptr< camera1394::Camera1394 > dev_
Definition: driver1394.h:120
camera1394::Camera1394Config Config
Definition: driver1394.cpp:64
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
camera1394::Camera1394Config config_
Definition: driver1394.h:123
bool sleep()
void reconfig(camera1394::Camera1394Config &newconfig, uint32_t level)
Definition: driver1394.cpp:316
#define ROS_INFO_STREAM(args)
#define ROS_ERROR_STREAM(args)
Camera1394 features interface.
void publish(const sensor_msgs::ImagePtr &image)
Definition: driver1394.cpp:235
#define ROS_DEBUG(...)


camera1394
Author(s): Jack O'Quin, Ken Tossell, Patrick Beeson, Nate Koenig, Andrew Howard, Damien Douxchamps, Dan Dennedy
autogenerated on Mon Jun 10 2019 12:52:31