37 #include <boost/format.hpp> 42 #include "camera1394stereo/Camera1394StereoConfig.h" 73 typedef camera1394stereo::Camera1394StereoConfig
Config;
80 state_(Driver::CLOSED),
81 reconfiguring_(false),
83 camera_nh_(camera_nh),
84 camera_name_(
"stereo_camera"),
127 bool success =
false;
133 if (0 ==
dev_->open(newconfig))
146 <<
"] name not valid" 147 <<
" for camera_info_manger");
151 << newconfig.video_mode <<
", " 152 << newconfig.frame_rate <<
" fps, " 153 << newconfig.iso_speed <<
" Mb/s");
160 catch (camera1394stereo::Exception& e)
166 <<
"] exception opening device (retrying): " 169 if ( system(
"dc1394_reset_bus") == 0 )
170 ROS_WARN_STREAM(
"Bus reset system call successful");
172 ROS_WARN_STREAM(
"Bus reset system call failure");
176 <<
"] device open failed: " << e.what());
179 while (!success && --retries >= 0);
195 bool do_sleep =
true;
198 boost::mutex::scoped_lock lock(
mutex_);
205 image[i] = sensor_msgs::ImagePtr(
new sensor_msgs::Image);
229 image[i]->header.frame_id =
config_.frame_id;
232 sensor_msgs::CameraInfoPtr
233 ci(
new sensor_msgs::CameraInfo(
cinfo_[i]->getCameraInfo()));
236 if (!
dev_->checkCameraInfo(*(image[i]), *ci))
246 <<
"] calibration does not match video mode " 247 <<
"(publishing uncalibrated data)");
249 ci.reset(
new sensor_msgs::CameraInfo());
250 ci->height = image[i]->height;
251 ci->width = image[i]->width;
259 <<
"] calibration matches video mode now");
263 dev_->setOperationalParameters(*ci);
265 ci->header.frame_id =
config_.frame_id;
266 ci->header.stamp = image[i]->header.stamp;
291 catch (camera1394stereo::Exception& e)
294 <<
"] Exception reading data: " << e.what());
314 boost::mutex::scoped_lock lock(
mutex_);
315 ROS_DEBUG(
"dynamic reconfigure level 0x%x", level);
318 if (newconfig.frame_id ==
"")
319 newconfig.frame_id =
"camera";
322 newconfig.frame_id =
tf::resolve(tf_prefix, newconfig.frame_id);
342 camera_info_url[
LEFT] =
config_.camera_info_url_left;
345 new_camera_info_url[
LEFT] = newconfig.camera_info_url_left;
346 new_camera_info_url[
RIGHT] = newconfig.camera_info_url_right;
350 if (camera_info_url[i] != new_camera_info_url[i])
353 if (
cinfo_[i]->validateURL(new_camera_info_url[i]))
355 cinfo_[i]->loadCameraInfo(new_camera_info_url[i]);
362 <<
"] not updating calibration to invalid URL " 363 << new_camera_info_url[i] );
370 if (level & Levels::RECONFIGURE_CLOSE)
373 if (
false ==
dev_->features_->initialize(&newconfig))
376 <<
"] feature initialization failure");
384 dev_->features_->reconfigure(&newconfig);
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);
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 uint8_t CLOSED
bool openCamera(Config &newconfig)
static const std::string CameraSelectorString[NUM_CAMERAS]
std::string resolve(const std::string &prefix, const std::string &frame_name)
Camera1394 features interface.
static const int NUM_CAMERAS
boost::shared_ptr< camera1394stereo::Camera1394Stereo > dev_
camera1394stereo::Camera1394StereoConfig Config
camera1394stereo::Camera1394StereoConfig config_
ros::NodeHandle single_camera_nh_[NUM_CAMERAS]
void publish(const sensor_msgs::ImagePtr image[NUM_CAMERAS])
ros::NodeHandle camera_nh_
#define ROS_WARN_STREAM(args)
static const uint8_t OPENED
#define ROS_DEBUG_STREAM(args)
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_
bool calibration_matches_[NUM_CAMERAS]
#define ROS_ERROR_STREAM(args)
static const uint32_t RECONFIGURE_CLOSE
Camera1394StereoDriver Driver
~Camera1394StereoDriver()
ROS driver interface for IIDC-compatible IEEE 1394 digital cameras.
boost::shared_ptr< image_transport::ImageTransport > it_
volatile bool reconfiguring_
Camera1394StereoDriver(ros::NodeHandle priv_nh, ros::NodeHandle camera_nh)