00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #include <boost/format.hpp>
00036
00037 #include <tf/transform_listener.h>
00038
00039 #include "driver1394.h"
00040 #include "camera1394/Camera1394Config.h"
00041 #include "features.h"
00042
00061 namespace camera1394_driver
00062 {
00063
00064 typedef camera1394::Camera1394Config Config;
00065 typedef Camera1394Driver Driver;
00066
00067 Camera1394Driver::Camera1394Driver(ros::NodeHandle priv_nh,
00068 ros::NodeHandle camera_nh):
00069 state_(Driver::CLOSED),
00070 reconfiguring_(false),
00071 priv_nh_(priv_nh),
00072 camera_nh_(camera_nh),
00073 camera_name_("camera"),
00074 cycle_(1.0),
00075 retries_(0),
00076 consecutive_read_errors_(0),
00077 dev_(new camera1394::Camera1394()),
00078 srv_(priv_nh),
00079 cinfo_(new camera_info_manager::CameraInfoManager(camera_nh_)),
00080 calibration_matches_(true),
00081 it_(new image_transport::ImageTransport(camera_nh_)),
00082 image_pub_(it_->advertiseCamera("image_raw", 1)),
00083 get_camera_registers_srv_(camera_nh_.advertiseService(
00084 "get_camera_registers",
00085 &Camera1394Driver::getCameraRegisters, this)),
00086 set_camera_registers_srv_(camera_nh_.advertiseService(
00087 "set_camera_registers",
00088 &Camera1394Driver::setCameraRegisters, this)),
00089 diagnostics_(),
00090 topic_diagnostics_min_freq_(0.),
00091 topic_diagnostics_max_freq_(1000.),
00092 topic_diagnostics_("image_raw", diagnostics_,
00093 diagnostic_updater::FrequencyStatusParam
00094 (&topic_diagnostics_min_freq_,
00095 &topic_diagnostics_max_freq_, 0.1, 10),
00096 diagnostic_updater::TimeStampStatusParam())
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
00142
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_;
00155 retries_ = 0;
00156 success = true;
00157 }
00158 }
00159 catch (camera1394::Exception& e)
00160 {
00161 state_ = Driver::CLOSED;
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
00172 diagnostics_.setHardwareID(camera_name_);
00173 double delta = newconfig.frame_rate * 0.1;
00174 topic_diagnostics_min_freq_ = newconfig.frame_rate - delta;
00175 topic_diagnostics_max_freq_ = newconfig.frame_rate + delta;
00176
00177 consecutive_read_errors_ = 0;
00178 return success;
00179 }
00180
00181
00183 void Camera1394Driver::poll(void)
00184 {
00185
00186
00187
00188
00189
00190
00191
00192 bool do_sleep = true;
00193 if (!reconfiguring_)
00194 {
00195 boost::mutex::scoped_lock lock(mutex_);
00196 if (state_ == Driver::CLOSED)
00197 {
00198 openCamera(config_);
00199 }
00200 do_sleep = (state_ == Driver::CLOSED);
00201 if (!do_sleep)
00202 {
00203
00204 sensor_msgs::ImagePtr image(new sensor_msgs::Image);
00205 if (read(image))
00206 {
00207 publish(image);
00208 consecutive_read_errors_ = 0;
00209 }
00210 else if (++consecutive_read_errors_ > config_.max_consecutive_errors
00211 && config_.max_consecutive_errors > 0)
00212 {
00213 ROS_WARN("reached %u consecutive read errrors, disconnecting",
00214 consecutive_read_errors_ );
00215 closeCamera();
00216 }
00217 }
00218 }
00219
00220
00221 diagnostics_.update();
00222
00223 if (do_sleep)
00224 {
00225
00226
00227 cycle_.sleep();
00228 }
00229 }
00230
00235 void Camera1394Driver::publish(const sensor_msgs::ImagePtr &image)
00236 {
00237 image->header.frame_id = config_.frame_id;
00238
00239
00240 sensor_msgs::CameraInfoPtr
00241 ci(new sensor_msgs::CameraInfo(cinfo_->getCameraInfo()));
00242
00243
00244 if (!dev_->checkCameraInfo(*image, *ci))
00245 {
00246
00247
00248 if (calibration_matches_)
00249 {
00250
00251 calibration_matches_ = false;
00252 ROS_WARN_STREAM("[" << camera_name_
00253 << "] calibration does not match video mode "
00254 << "(publishing uncalibrated data)");
00255 }
00256 ci.reset(new sensor_msgs::CameraInfo());
00257 ci->height = image->height;
00258 ci->width = image->width;
00259 }
00260 else if (!calibration_matches_)
00261 {
00262
00263 calibration_matches_ = true;
00264 ROS_WARN_STREAM("[" << camera_name_
00265 << "] calibration matches video mode now");
00266 }
00267
00268
00269 dev_->setOperationalParameters(*ci);
00270
00271 ci->header.frame_id = config_.frame_id;
00272 ci->header.stamp = image->header.stamp;
00273
00274
00275 image_pub_.publish(image, ci);
00276
00277
00278
00279
00280 topic_diagnostics_.tick(image->header.stamp);
00281 }
00282
00288 bool Camera1394Driver::read(sensor_msgs::ImagePtr &image)
00289 {
00290 bool success = true;
00291 try
00292 {
00293
00294 ROS_DEBUG_STREAM("[" << camera_name_ << "] reading data");
00295 success = dev_->readData(*image);
00296 ROS_DEBUG_STREAM("[" << camera_name_ << "] read returned");
00297 }
00298 catch (camera1394::Exception& e)
00299 {
00300 ROS_WARN_STREAM("[" << camera_name_
00301 << "] Exception reading data: " << e.what());
00302 success = false;
00303 }
00304 return success;
00305 }
00306
00316 void Camera1394Driver::reconfig(Config &newconfig, uint32_t level)
00317 {
00318
00319
00320 reconfiguring_ = true;
00321 boost::mutex::scoped_lock lock(mutex_);
00322 ROS_DEBUG("dynamic reconfigure level 0x%x", level);
00323
00324
00325 if (newconfig.frame_id == "")
00326 newconfig.frame_id = "camera";
00327 std::string tf_prefix = tf::getPrefixParam(priv_nh_);
00328 ROS_DEBUG_STREAM("tf_prefix: " << tf_prefix);
00329 newconfig.frame_id = tf::resolve(tf_prefix, newconfig.frame_id);
00330
00331 if (state_ != Driver::CLOSED && (level & Levels::RECONFIGURE_CLOSE))
00332 {
00333
00334 closeCamera();
00335 }
00336
00337 if (state_ == Driver::CLOSED)
00338 {
00339
00340 openCamera(newconfig);
00341 }
00342
00343 if (config_.camera_info_url != newconfig.camera_info_url)
00344 {
00345
00346 if (cinfo_->validateURL(newconfig.camera_info_url))
00347 {
00348 cinfo_->loadCameraInfo(newconfig.camera_info_url);
00349 }
00350 else
00351 {
00352
00353 newconfig.camera_info_url = config_.camera_info_url;
00354 }
00355 }
00356
00357 if (state_ != Driver::CLOSED)
00358 {
00359
00360 if (level & Levels::RECONFIGURE_CLOSE)
00361 {
00362
00363 if (false == dev_->features_->initialize(&newconfig))
00364 {
00365 ROS_ERROR_STREAM("[" << camera_name_
00366 << "] feature initialization failure");
00367 closeCamera();
00368 }
00369 }
00370 else
00371 {
00372
00373
00374
00375 dev_->features_->reconfigure(&newconfig);
00376 }
00377 }
00378
00379 config_ = newconfig;
00380 reconfiguring_ = false;
00381
00382 ROS_DEBUG_STREAM("[" << camera_name_
00383 << "] reconfigured: frame_id " << newconfig.frame_id
00384 << ", camera_info_url " << newconfig.camera_info_url);
00385 }
00386
00387
00394 void Camera1394Driver::setup(void)
00395 {
00396 srv_.setCallback(boost::bind(&Camera1394Driver::reconfig, this, _1, _2));
00397 }
00398
00399
00401 void Camera1394Driver::shutdown(void)
00402 {
00403 closeCamera();
00404 }
00405
00407 bool Camera1394Driver::getCameraRegisters(
00408 camera1394::GetCameraRegisters::Request &request,
00409 camera1394::GetCameraRegisters::Response &response)
00410 {
00411 typedef camera1394::GetCameraRegisters::Request Request;
00412 boost::mutex::scoped_lock lock(mutex_);
00413 if (state_ == Driver::CLOSED)
00414 {
00415 return false;
00416 }
00417 if (request.num_regs < 1
00418 || (request.type != Request::TYPE_CONTROL
00419 && request.type != Request::TYPE_ADVANCED_CONTROL))
00420 {
00421 request.num_regs = 1;
00422 }
00423 response.value.resize(request.num_regs);
00424
00425 bool success = false;
00426 switch (request.type)
00427 {
00428 case Request::TYPE_CONTROL:
00429 success = dev_->registers_->getControlRegisters(
00430 request.offset, request.num_regs, response.value);
00431 break;
00432 case Request::TYPE_ABSOLUTE:
00433 success = dev_->registers_->getAbsoluteRegister(
00434 request.offset, request.mode, response.value[0]);
00435 break;
00436 case Request::TYPE_FORMAT7:
00437 success = dev_->registers_->getFormat7Register(
00438 request.offset, request.mode, response.value[0]);
00439 break;
00440 case Request::TYPE_ADVANCED_CONTROL:
00441 success = dev_->registers_->getAdvancedControlRegisters(
00442 request.offset, request.num_regs, response.value);
00443 break;
00444 case Request::TYPE_PIO:
00445 success = dev_->registers_->getPIORegister(
00446 request.offset, response.value[0]);
00447 break;
00448 case Request::TYPE_SIO:
00449 success = dev_->registers_->getSIORegister(
00450 request.offset, response.value[0]);
00451 break;
00452 case Request::TYPE_STROBE:
00453 success = dev_->registers_->getStrobeRegister(
00454 request.offset, response.value[0]);
00455 break;
00456 }
00457
00458 if (!success)
00459 {
00460 ROS_WARN("[%s] getting register failed: type %u, offset %lu",
00461 camera_name_.c_str(), request.type, request.offset);
00462 }
00463 return success;
00464 }
00465
00467 bool Camera1394Driver::setCameraRegisters(
00468 camera1394::SetCameraRegisters::Request &request,
00469 camera1394::SetCameraRegisters::Response &response)
00470 {
00471 typedef camera1394::SetCameraRegisters::Request Request;
00472 if (request.value.size() == 0)
00473 return true;
00474 boost::mutex::scoped_lock lock(mutex_);
00475 if (state_ == Driver::CLOSED)
00476 return false;
00477 bool success = false;
00478 switch (request.type)
00479 {
00480 case Request::TYPE_CONTROL:
00481 success = dev_->registers_->setControlRegisters(
00482 request.offset, request.value);
00483 break;
00484 case Request::TYPE_ABSOLUTE:
00485 success = dev_->registers_->setAbsoluteRegister(
00486 request.offset, request.mode, request.value[0]);
00487 break;
00488 case Request::TYPE_FORMAT7:
00489 success = dev_->registers_->setFormat7Register(
00490 request.offset, request.mode, request.value[0]);
00491 break;
00492 case Request::TYPE_ADVANCED_CONTROL:
00493 success = dev_->registers_->setAdvancedControlRegisters(
00494 request.offset, request.value);
00495 break;
00496 case Request::TYPE_PIO:
00497 success = dev_->registers_->setPIORegister(
00498 request.offset, request.value[0]);
00499 break;
00500 case Request::TYPE_SIO:
00501 success = dev_->registers_->setSIORegister(
00502 request.offset, request.value[0]);
00503 break;
00504 case Request::TYPE_STROBE:
00505 success = dev_->registers_->setStrobeRegister(
00506 request.offset, request.value[0]);
00507 break;
00508 }
00509
00510 if (!success)
00511 {
00512 ROS_WARN("[%s] setting register failed: type %u, offset %lu",
00513 camera_name_.c_str(), request.type, request.offset);
00514 }
00515 return success;
00516 }
00517
00518 };