35 #include <boost/format.hpp> 40 #include "camera1394/Camera1394Config.h" 64 typedef camera1394::Camera1394Config
Config;
69 state_(Driver::CLOSED),
70 reconfiguring_(false),
72 camera_nh_(camera_nh),
73 camera_name_(
"camera"),
76 consecutive_read_errors_(0),
80 calibration_matches_(true),
82 image_pub_(it_->advertiseCamera(
"image_raw", 1)),
84 "get_camera_registers",
87 "set_camera_registers",
90 topic_diagnostics_min_freq_(0.),
91 topic_diagnostics_max_freq_(1000.),
92 topic_diagnostics_(
"image_raw", diagnostics_,
94 (&topic_diagnostics_min_freq_,
95 &topic_diagnostics_max_freq_, 0.1, 10),
130 bool success =
false;
134 if (0 ==
dev_->open(newconfig))
144 <<
"] name not valid" 145 <<
" for camera_info_manger");
149 << newconfig.video_mode <<
", " 150 << newconfig.frame_rate <<
" fps, " 151 << newconfig.iso_speed <<
" Mb/s");
159 catch (camera1394::Exception& e)
164 <<
"] exception opening device (retrying): " 168 <<
"] device open failed: " << e.what());
173 double delta = newconfig.frame_rate * 0.1;
192 bool do_sleep =
true;
195 boost::mutex::scoped_lock lock(
mutex_);
204 sensor_msgs::ImagePtr image(
new sensor_msgs::Image);
211 &&
config_.max_consecutive_errors > 0)
213 ROS_WARN(
"reached %u consecutive read errrors, disconnecting",
237 image->header.frame_id =
config_.frame_id;
240 sensor_msgs::CameraInfoPtr
241 ci(
new sensor_msgs::CameraInfo(
cinfo_->getCameraInfo()));
244 if (!
dev_->checkCameraInfo(*image, *ci))
253 <<
"] calibration does not match video mode " 254 <<
"(publishing uncalibrated data)");
256 ci.reset(
new sensor_msgs::CameraInfo());
257 ci->height = image->height;
258 ci->width = image->width;
265 <<
"] calibration matches video mode now");
269 dev_->setOperationalParameters(*ci);
271 ci->header.frame_id =
config_.frame_id;
272 ci->header.stamp = image->header.stamp;
295 success =
dev_->readData(*image);
298 catch (camera1394::Exception& e)
301 <<
"] Exception reading data: " << e.what());
321 boost::mutex::scoped_lock lock(
mutex_);
322 ROS_DEBUG(
"dynamic reconfigure level 0x%x", level);
325 if (newconfig.frame_id ==
"")
326 newconfig.frame_id =
"camera";
329 newconfig.frame_id =
tf::resolve(tf_prefix, newconfig.frame_id);
343 if (
config_.camera_info_url != newconfig.camera_info_url)
346 if (
cinfo_->validateURL(newconfig.camera_info_url))
348 cinfo_->loadCameraInfo(newconfig.camera_info_url);
353 newconfig.camera_info_url =
config_.camera_info_url;
360 if (level & Levels::RECONFIGURE_CLOSE)
363 if (
false ==
dev_->features_->initialize(&newconfig))
366 <<
"] feature initialization failure");
375 dev_->features_->reconfigure(&newconfig);
383 <<
"] reconfigured: frame_id " << newconfig.frame_id
384 <<
", camera_info_url " << newconfig.camera_info_url);
408 camera1394::GetCameraRegisters::Request &request,
409 camera1394::GetCameraRegisters::Response &response)
411 typedef camera1394::GetCameraRegisters::Request Request;
412 boost::mutex::scoped_lock lock(
mutex_);
417 if (request.num_regs < 1
418 || (request.type != Request::TYPE_CONTROL
419 && request.type != Request::TYPE_ADVANCED_CONTROL))
421 request.num_regs = 1;
423 response.value.resize(request.num_regs);
425 bool success =
false;
426 switch (request.type)
428 case Request::TYPE_CONTROL:
429 success =
dev_->registers_->getControlRegisters(
430 request.offset, request.num_regs, response.value);
432 case Request::TYPE_ABSOLUTE:
433 success =
dev_->registers_->getAbsoluteRegister(
434 request.offset, request.mode, response.value[0]);
436 case Request::TYPE_FORMAT7:
437 success =
dev_->registers_->getFormat7Register(
438 request.offset, request.mode, response.value[0]);
440 case Request::TYPE_ADVANCED_CONTROL:
441 success =
dev_->registers_->getAdvancedControlRegisters(
442 request.offset, request.num_regs, response.value);
444 case Request::TYPE_PIO:
445 success =
dev_->registers_->getPIORegister(
446 request.offset, response.value[0]);
448 case Request::TYPE_SIO:
449 success =
dev_->registers_->getSIORegister(
450 request.offset, response.value[0]);
452 case Request::TYPE_STROBE:
453 success =
dev_->registers_->getStrobeRegister(
454 request.offset, response.value[0]);
460 ROS_WARN(
"[%s] getting register failed: type %u, offset %lu",
468 camera1394::SetCameraRegisters::Request &request,
469 camera1394::SetCameraRegisters::Response &response)
471 typedef camera1394::SetCameraRegisters::Request Request;
472 if (request.value.size() == 0)
474 boost::mutex::scoped_lock lock(
mutex_);
477 bool success =
false;
478 switch (request.type)
480 case Request::TYPE_CONTROL:
481 success =
dev_->registers_->setControlRegisters(
482 request.offset, request.value);
484 case Request::TYPE_ABSOLUTE:
485 success =
dev_->registers_->setAbsoluteRegister(
486 request.offset, request.mode, request.value[0]);
488 case Request::TYPE_FORMAT7:
489 success =
dev_->registers_->setFormat7Register(
490 request.offset, request.mode, request.value[0]);
492 case Request::TYPE_ADVANCED_CONTROL:
493 success =
dev_->registers_->setAdvancedControlRegisters(
494 request.offset, request.value);
496 case Request::TYPE_PIO:
497 success =
dev_->registers_->setPIORegister(
498 request.offset, request.value[0]);
500 case Request::TYPE_SIO:
501 success =
dev_->registers_->setSIORegister(
502 request.offset, request.value[0]);
504 case Request::TYPE_STROBE:
505 success =
dev_->registers_->setStrobeRegister(
506 request.offset, request.value[0]);
512 ROS_WARN(
"[%s] setting register failed: type %u, offset %lu",
uint32_t consecutive_read_errors_
boost::shared_ptr< camera_info_manager::CameraInfoManager > cinfo_
dynamic_reconfigure::Server< camera1394::Camera1394Config > srv_
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
bool setCameraRegisters(camera1394::SetCameraRegisters::Request &request, camera1394::SetCameraRegisters::Response &response)
std::string getPrefixParam(ros::NodeHandle &nh)
static const uint32_t RECONFIGURE_CLOSE
void setHardwareID(const std::string &hwid)
diagnostic_updater::TopicDiagnostic topic_diagnostics_
static const uint8_t CLOSED
static const uint8_t OPENED
volatile bool reconfiguring_
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)
double topic_diagnostics_max_freq_
diagnostic_updater::Updater diagnostics_
bool read(sensor_msgs::ImagePtr &image)
std::string resolve(const std::string &prefix, const std::string &frame_name)
image_transport::CameraPublisher image_pub_
ROS driver interface for IIDC-compatible IEEE 1394 digital cameras.
bool openCamera(Config &newconfig)
bool calibration_matches_
bool getCameraRegisters(camera1394::GetCameraRegisters::Request &request, camera1394::GetCameraRegisters::Response &response)
boost::shared_ptr< camera1394::Camera1394 > dev_
camera1394::Camera1394Config Config
#define ROS_WARN_STREAM(args)
#define ROS_DEBUG_STREAM(args)
camera1394::Camera1394Config config_
void reconfig(camera1394::Camera1394Config &newconfig, uint32_t level)
#define ROS_INFO_STREAM(args)
#define ROS_ERROR_STREAM(args)
Camera1394 features interface.
double topic_diagnostics_min_freq_
void publish(const sensor_msgs::ImagePtr &image)