43 #include <boost/algorithm/string/replace.hpp> 44 #include <log4cxx/logger.h> 50 DriverNodelet::~DriverNodelet ()
53 init_thread_.interrupt();
57 close_diagnostics_ =
true;
58 diagnostics_thread_.join();
61 close_tiltThread_ =
true;
71 void DriverNodelet::onInit ()
76 init_thread_ = boost::thread(boost::bind(&DriverNodelet::onInitImpl,
this));
79 void DriverNodelet::onInitImpl ()
97 rgb_frame_counter_ = depth_frame_counter_ = ir_frame_counter_ = 0;
98 publish_rgb_ = publish_ir_ = publish_depth_ =
true;
102 param_nh.
param(
"debug" , libfreenect_debug_,
false);
108 param_nh.
param(
"motor_processing", motor_processing_,
false);
109 param_nh.
param(
"audio_processing", audio_processing_,
true);
110 param_nh.
param(
"rgb_processing", rgb_processing_,
false);
111 param_nh.
param(
"ir_processing", ir_processing_,
false);
112 param_nh.
param(
"depth_processing", depth_processing_,
false);
114 if(!(motor_processing_||audio_processing_||rgb_processing_||ir_processing_||depth_processing_))
119 if(audio_processing_)
131 reconfigure_server_->setCallback(boost::bind(&DriverNodelet::configCb,
this, _1, _2));
133 param_nh.
param(
"rgb_frame_id", rgb_frame_id_,
string(
"/openni_rgb_optical_frame"));
134 param_nh.
param(
"depth_frame_id", depth_frame_id_,
string(
"/openni_depth_optical_frame"));
135 NODELET_INFO(
"rgb_frame_id = '%s' ", rgb_frame_id_.c_str());
136 NODELET_INFO(
"depth_frame_id = '%s' ", depth_frame_id_.c_str());
146 std::string serial_number = device_->getSerialNumber();
148 if (serial_number.empty())
155 rgb_name =
"rgb_" + serial_number;
156 ir_name =
"depth_" + serial_number;
159 std::string rgb_info_url, ir_info_url;
160 param_nh.
param(
"rgb_camera_info_url", rgb_info_url, std::string());
161 param_nh.
param(
"depth_camera_info_url", ir_info_url, std::string());
163 double diagnostics_max_frequency, diagnostics_min_frequency;
164 double diagnostics_tolerance, diagnostics_window_time;
167 param_nh.
param(
"enable_rgb_diagnostics", enable_rgb_diagnostics_,
false);
170 param_nh.
param(
"enable_ir_diagnostics", enable_ir_diagnostics_,
false);
173 param_nh.
param(
"enable_depth_diagnostics", enable_depth_diagnostics_,
false);
176 param_nh.
param(
"diagnostics_max_frequency", diagnostics_max_frequency, 30.0);
179 param_nh.
param(
"diagnostics_min_frequency", diagnostics_min_frequency, 30.0);
182 param_nh.
param(
"diagnostics_tolerance", diagnostics_tolerance, 0.05);
185 param_nh.
param(
"diagnostics_window_time", diagnostics_window_time, 5.0);
188 log4cxx::LoggerPtr logger_ccp = log4cxx::Logger::getLogger(
"ros.camera_calibration_parsers");
189 log4cxx::LoggerPtr logger_cim = log4cxx::Logger::getLogger(
"ros.camera_info_manager");
190 logger_ccp->setLevel(log4cxx::Level::getFatal());
191 logger_cim->setLevel(log4cxx::Level::getWarn());
196 log4cxx::LoggerPtr logger_its = log4cxx::Logger::getLogger(
"ros.image_transport.sync");
197 logger_its->setLevel(log4cxx::Level::getError());
201 rgb_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(rgb_nh, rgb_name, rgb_info_url);
202 ir_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(ir_nh, ir_name, ir_info_url);
204 if (!rgb_info_manager_->isCalibrated())
205 NODELET_WARN(
"Using default parameters for RGB camera calibration.");
206 if (!ir_info_manager_->isCalibrated())
207 NODELET_WARN(
"Using default parameters for IR camera calibration.");
215 boost::lock_guard<boost::mutex> lock(connect_mutex_);
218 pub_freq_max_ = diagnostics_max_frequency;
219 pub_freq_min_ = diagnostics_min_frequency;
223 std::string hardware_id = std::string(device_->getProductName()) +
"-" +
224 std::string(device_->getSerialNumber());
225 diagnostic_updater_->setHardwareID(hardware_id);
229 if (device_->hasImageStream()&&rgb_processing_)
233 pub_rgb_ = rgb_it.
advertiseCamera(
"image_raw", 1, itssc, itssc, rssc, rssc);
234 if (enable_rgb_diagnostics_) {
235 pub_rgb_freq_.reset(
new TopicDiagnostic(
"RGB Image", *diagnostic_updater_,
237 diagnostics_tolerance, diagnostics_window_time)));
241 if (device_->hasIRStream()&&ir_processing_)
245 pub_ir_ = ir_it.
advertiseCamera(
"image_raw", 1, itssc, itssc, rssc, rssc);
246 if (enable_ir_diagnostics_) {
247 pub_ir_freq_.reset(
new TopicDiagnostic(
"IR Image", *diagnostic_updater_,
249 diagnostics_tolerance, diagnostics_window_time)));
253 if (device_->hasDepthStream()&&depth_processing_)
257 pub_depth_ = depth_it.
advertiseCamera(
"image_raw", 1, itssc, itssc, rssc, rssc);
258 if (enable_depth_diagnostics_) {
259 pub_depth_freq_.reset(
new TopicDiagnostic(
"Depth Image", *diagnostic_updater_,
261 diagnostics_tolerance, diagnostics_window_time)));
264 pub_projector_info_ = projector_nh.
advertise<sensor_msgs::CameraInfo>(
"camera_info", 1, rssc, rssc);
266 if (device_->isDepthRegistrationSupported()) {
267 pub_depth_registered_ = depth_registered_it.
advertiseCamera(
"image_raw", 1, itssc, itssc, rssc, rssc);
275 stopSynchronization();
276 if(!depth_processing_ && device_->isDepthStreamRunning())
278 device_->stopDepthStream();
280 if(!rgb_processing_ && device_->isImageStreamRunning())
282 device_->stopImageStream();
284 if(!ir_processing_ && device_->isIRStreamRunning())
286 device_->stopIRStream();
288 startSynchronization();
291 close_diagnostics_ =
false;
292 diagnostics_thread_ = boost::thread(boost::bind(&DriverNodelet::updateDiagnostics,
this));
295 param_nh.
param<
double>(
"time_out", time_out_, 5.0);
301 device_->publishersAreReady();
304 if(motor_processing_)
306 close_tiltThread_ =
false;
307 tiltDriver_=
TiltDriver(device_,&close_tiltThread_);
308 tilt_thread_ = boost::thread(boost::bind(&TiltDriver::run, &tiltDriver_));
314 void DriverNodelet::updateDiagnostics() {
315 while (!close_diagnostics_) {
316 diagnostic_updater_->update();
317 boost::this_thread::sleep(boost::posix_time::milliseconds(10));
321 void DriverNodelet::setupDevice ()
327 if (libfreenect_debug_)
335 NODELET_INFO (
"No devices connected.... waiting for devices to be connected");
336 boost::this_thread::sleep(boost::posix_time::seconds(3));
341 for (
unsigned deviceIdx = 0; deviceIdx < driver.
getNumberDevices (); ++deviceIdx)
343 NODELET_INFO(
"%u. device on bus %03u:%02u is a %s (%03x) from %s (%03x) with serial id \'%s\'",
352 if (!getPrivateNodeHandle().getParam(
"device_id", device_id))
354 NODELET_WARN (
"~device_id is not set! Using first device.");
357 else if (device_id.find (
'@') != string::npos)
359 size_t pos = device_id.find (
'@');
360 unsigned bus = atoi (device_id.substr (0, pos).c_str ());
361 unsigned address = atoi (device_id.substr (pos + 1, device_id.length () - pos - 1).c_str ());
362 NODELET_INFO (
"Searching for device with bus@address = %d@%d", bus, address);
365 else if (device_id[0] ==
'#')
367 unsigned index = atoi (device_id.c_str() + 1);
368 NODELET_INFO (
"Searching for device with index = %d", index);
373 NODELET_INFO (
"Searching for device with serial number = '%s'", device_id.c_str ());
381 NODELET_INFO (
"No matching device found.... waiting for devices. Reason: %s", e.what ());
382 boost::this_thread::sleep(boost::posix_time::seconds(3));
387 NODELET_FATAL (
"Could not retrieve device. Reason: %s", e.what ());
393 NODELET_INFO (
"Opened '%s' on bus %d:%d with serial number '%s'", device_->getProductName (),
394 device_->getBus (), device_->getAddress (), device_->getSerialNumber ());
397 if(subdevs_&FREENECT_DEVICE_CAMERA) device_->registerDepthCallback(&DriverNodelet::depthCb, *
this);
398 if(subdevs_&FREENECT_DEVICE_CAMERA) device_->registerIRCallback (&DriverNodelet::irCb, *
this);
403 void DriverNodelet::rgbConnectCb()
406 boost::lock_guard<boost::mutex> lock(connect_mutex_);
408 bool need_rgb = pub_rgb_.getNumSubscribers() > 0;
411 if (need_rgb && !device_->isImageStreamRunning())
414 if (device_->isIRStreamRunning())
416 NODELET_ERROR(
"Cannot stream RGB and IR at the same time. Streaming RGB only.");
417 device_->stopIRStream();
420 device_->startImageStream();
421 startSynchronization();
424 else if (!need_rgb && device_->isImageStreamRunning())
426 stopSynchronization();
427 device_->stopImageStream();
430 bool need_ir = pub_ir_.getNumSubscribers() > 0;
431 if (need_ir && !device_->isIRStreamRunning())
433 device_->startIRStream();
440 void DriverNodelet::depthConnectCb()
443 boost::lock_guard<boost::mutex> lock(connect_mutex_);
447 device_->isDepthRegistered() ? pub_depth_registered_.getNumSubscribers() > 0 : pub_depth_.getNumSubscribers() > 0;
451 if (need_depth && !device_->isDepthStreamRunning())
453 device_->startDepthStream();
454 startSynchronization();
458 else if (!need_depth && device_->isDepthStreamRunning())
460 stopSynchronization();
461 device_->stopDepthStream();
466 void DriverNodelet::irConnectCb()
468 boost::lock_guard<boost::mutex> lock(connect_mutex_);
469 bool need_ir = pub_ir_.getNumSubscribers() > 0;
471 if (need_ir && !device_->isIRStreamRunning())
474 if (device_->isImageStreamRunning())
476 NODELET_ERROR(
"Cannot stream RGB and IR at the same time. Streaming RGB only.");
480 device_->startIRStream();
486 device_->stopIRStream();
493 void DriverNodelet::checkFrameCounters()
495 if (max(rgb_frame_counter_, max(depth_frame_counter_, ir_frame_counter_)) > config_.data_skip) {
497 rgb_frame_counter_ = 0;
498 depth_frame_counter_ = 0;
499 ir_frame_counter_ = 0;
503 publish_depth_ =
true;
511 rgb_time_stamp_ = time;
513 bool publish =
false;
515 boost::unique_lock<boost::mutex> counter_lock(counter_mutex_);
516 rgb_frame_counter_++;
517 checkFrameCounters();
518 publish = publish_rgb_;
521 rgb_frame_counter_ = 0;
525 publishRgbImage(image, time);
527 publish_rgb_ =
false;
530 void DriverNodelet::depthCb(
const ImageBuffer& depth_image,
void* cookie)
533 depth_time_stamp_ = time;
534 if((num_frame_%3==0))
540 bool publish =
false;
542 boost::unique_lock<boost::mutex> counter_lock(counter_mutex_);
543 depth_frame_counter_++;
544 checkFrameCounters();
545 publish = publish_depth_;
548 depth_frame_counter_ = 0;
552 publishDepthImage(depth_image, time);
554 publish_depth_ =
false;
557 void DriverNodelet::irCb(
const ImageBuffer& ir_image,
void* cookie)
560 ir_time_stamp_ = time;
562 bool publish =
false;
564 boost::unique_lock<boost::mutex> counter_lock(counter_mutex_);
566 checkFrameCounters();
567 publish = publish_ir_;
570 ir_frame_counter_ = 0;
574 publishIrImage(ir_image, time);
581 sensor_msgs::ImagePtr rgb_msg = boost::make_shared<sensor_msgs::Image >();
582 rgb_msg->header.stamp = time;
583 rgb_msg->header.frame_id = rgb_frame_id_;
589 rgb_msg->step = rgb_msg->width * 3;
593 rgb_msg->step = rgb_msg->width;
597 rgb_msg->step = rgb_msg->width * 2;
600 NODELET_ERROR(
"Unknown RGB image format received from libfreenect");
604 rgb_msg->data.resize(rgb_msg->height * rgb_msg->step);
605 fillImage(image, reinterpret_cast<void*>(&rgb_msg->data[0]));
607 pub_rgb_.publish(rgb_msg, getRgbCameraInfo(image, time));
608 if (enable_rgb_diagnostics_)
609 pub_rgb_freq_->tick();
617 sensor_msgs::ImagePtr depth_msg = boost::make_shared<sensor_msgs::Image>();
618 depth_msg->header.stamp = time;
622 depth_msg->step = depth_msg->width *
sizeof(short);
623 depth_msg->data.resize(depth_msg->height * depth_msg->step);
625 fillImage(depth, reinterpret_cast<void*>(&depth_msg->data[0]));
627 if (z_offset_mm_ != 0)
630 for (
unsigned int i = 0; i < depth_msg->width * depth_msg->height; ++i)
632 data[i] += z_offset_mm_;
638 depth_msg->header.frame_id = rgb_frame_id_;
639 pub_depth_registered_.publish(depth_msg, getRgbCameraInfo(depth, time));
644 depth_msg->header.frame_id = depth_frame_id_;
645 pub_depth_.publish(depth_msg, getDepthCameraInfo(depth, time));
647 if (enable_depth_diagnostics_)
648 pub_depth_freq_->tick();
651 if (pub_projector_info_.getNumSubscribers() > 0)
653 pub_projector_info_.publish(getProjectorCameraInfo(depth, time));
659 sensor_msgs::ImagePtr ir_msg = boost::make_shared<sensor_msgs::Image>();
660 ir_msg->header.stamp = time;
661 ir_msg->header.frame_id = depth_frame_id_;
665 ir_msg->step = ir_msg->width *
sizeof(
uint16_t);
666 ir_msg->data.resize(ir_msg->height * ir_msg->step);
668 fillImage(ir, reinterpret_cast<void*>(&ir_msg->data[0]));
670 pub_ir_.publish(ir_msg, getIrCameraInfo(ir, time));
672 if (enable_ir_diagnostics_)
673 pub_ir_freq_->tick();
676 sensor_msgs::CameraInfoPtr DriverNodelet::getDefaultCameraInfo(
int width,
int height,
double f)
const 678 sensor_msgs::CameraInfoPtr info = boost::make_shared<sensor_msgs::CameraInfo>();
681 info->height = height;
684 info->D.resize(5, 0.0);
689 info->K[0] = info->K[4] = f;
690 info->K[2] = (width / 2) - 0.5;
693 info->K[5] = (width * (3./8.)) - 0.5;
698 info->R[0] = info->R[4] = info->R[8] = 1.0;
702 info->P[0] = info->P[5] = f;
703 info->P[2] = info->K[2];
704 info->P[6] = info->K[5];
713 sensor_msgs::CameraInfoPtr info;
715 if (rgb_info_manager_->isCalibrated())
717 info = boost::make_shared<sensor_msgs::CameraInfo>(rgb_info_manager_->getCameraInfo());
726 info->header.stamp = time;
727 info->header.frame_id = rgb_frame_id_;
732 sensor_msgs::CameraInfoPtr DriverNodelet::getIrCameraInfo(
734 sensor_msgs::CameraInfoPtr info;
736 if (ir_info_manager_->isCalibrated())
738 info = boost::make_shared<sensor_msgs::CameraInfo>(ir_info_manager_->getCameraInfo());
747 info->header.stamp = time;
748 info->header.frame_id = depth_frame_id_;
753 sensor_msgs::CameraInfoPtr DriverNodelet::getDepthCameraInfo(
759 sensor_msgs::CameraInfoPtr info = getIrCameraInfo(image, time);
760 info->K[2] -= depth_ir_offset_x_;
761 info->K[5] -= depth_ir_offset_y_;
762 info->P[2] -= depth_ir_offset_x_;
763 info->P[6] -= depth_ir_offset_y_;
769 sensor_msgs::CameraInfoPtr DriverNodelet::getProjectorCameraInfo(
774 sensor_msgs::CameraInfoPtr info = getDepthCameraInfo(image, time);
776 info->P[3] = -device_->getBaseline() * info->P[0];
782 depth_ir_offset_x_ = config.depth_ir_offset_x;
783 depth_ir_offset_y_ = config.depth_ir_offset_y;
784 z_offset_mm_ = config.z_offset_mm;
787 OutputMode old_image_mode, image_mode, compatible_image_mode;
788 if (device_->hasImageStream ())
790 old_image_mode = device_->getImageOutputMode ();
793 image_mode = mapConfigMode2OutputMode (config.image_mode);
795 if (!device_->findCompatibleImageMode (image_mode, compatible_image_mode))
797 OutputMode default_mode = device_->getDefaultImageMode();
798 NODELET_WARN(
"Could not find any compatible image output mode for %d. " 799 "Falling back to default image output mode %d.",
803 config.image_mode = mapMode2ConfigMode(default_mode);
804 image_mode = compatible_image_mode = default_mode;
808 OutputMode old_depth_mode, depth_mode, compatible_depth_mode;
809 old_depth_mode = device_->getDepthOutputMode();
810 depth_mode = mapConfigMode2OutputMode (config.depth_mode);
811 if (!device_->findCompatibleDepthMode (depth_mode, compatible_depth_mode))
813 OutputMode default_mode = device_->getDefaultDepthMode();
814 NODELET_WARN(
"Could not find any compatible depth output mode for %d. " 815 "Falling back to default depth output mode %d.",
819 config.depth_mode = mapMode2ConfigMode(default_mode);
820 depth_mode = compatible_depth_mode = default_mode;
824 if ( (device_->hasImageStream () && compatible_image_mode != old_image_mode) ||
825 compatible_depth_mode != old_depth_mode)
828 stopSynchronization();
830 if (device_->hasImageStream () && compatible_image_mode != old_image_mode)
831 device_->setImageOutputMode (compatible_image_mode);
833 if (compatible_depth_mode != old_depth_mode)
834 device_->setDepthOutputMode (compatible_depth_mode);
836 startSynchronization ();
840 if (device_->isDepthRegistered () && !config.depth_registration)
842 device_->setDepthRegistration (
false);
844 else if (!device_->isDepthRegistered () && config.depth_registration)
846 device_->setDepthRegistration (
true);
853 void DriverNodelet::startSynchronization()
855 if (device_->isSynchronizationSupported() &&
856 !device_->isSynchronized() &&
857 device_->isImageStreamRunning() &&
858 device_->isDepthStreamRunning() )
860 device_->setSynchronization(
true);
864 void DriverNodelet::stopSynchronization()
866 if (device_->isSynchronizationSupported() &&
867 device_->isSynchronized())
869 device_->setSynchronization(
false);
873 void DriverNodelet::updateModeMaps ()
878 mode2config_map_[output_mode] = Freenect_SXGA;
879 config2mode_map_[Freenect_SXGA] = output_mode;
882 mode2config_map_[output_mode] = Freenect_VGA;
883 config2mode_map_[Freenect_VGA] = output_mode;
886 int DriverNodelet::mapMode2ConfigMode (
const OutputMode& output_mode)
const 888 std::map<OutputMode, int>::const_iterator it = mode2config_map_.find (output_mode);
890 if (it == mode2config_map_.end ())
899 OutputMode DriverNodelet::mapConfigMode2OutputMode (
int mode)
const 901 std::map<int, OutputMode>::const_iterator it = config2mode_map_.find (mode);
902 if (it == config2mode_map_.end ())
913 bool timed_out =
false;
914 if (!rgb_time_stamp_.isZero() && device_->isImageStreamRunning()) {
916 timed_out = timed_out || duration.
toSec() > time_out_;
918 if (!depth_time_stamp_.isZero() && device_->isDepthStreamRunning()) {
920 timed_out = timed_out || duration.
toSec() > time_out_;
922 if (!ir_time_stamp_.isZero() && device_->isIRStreamRunning()) {
924 timed_out = timed_out || duration.
toSec() > time_out_;
928 ROS_INFO(
"Device timed out. Flushing device.");
dynamic_reconfigure::Server< Config > ReconfigureServer
const std::string BAYER_GRBG8
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
#define NODELET_ERROR(...)
void fillImage(const ImageBuffer &buffer, void *data)
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
#define NODELET_WARN(...)
boost::shared_ptr< FreenectDevice > getDeviceByAddress(unsigned bus, unsigned address)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
unsigned getNumberDevices()
Holds an image buffer with all the metadata required to transmit the image over ROS channels...
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
unsigned getVendorID(unsigned device_idx)
boost::shared_ptr< FreenectDevice > getDeviceByIndex(unsigned device_idx)
unsigned getBus(unsigned device_idx)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
const std::string PLUMB_BOB
const std::string TYPE_16UC1
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::shared_ptr< FreenectDevice > getDeviceBySerialNumber(std::string serial)
const char * getSerialNumber(unsigned device_idx)
freenect_frame_mode metadata
#define NODELET_INFO(...)
FREENECT_RESOLUTION_MEDIUM
const char * getProductName(unsigned device_idx)
unsigned getAddress(unsigned device_idx)
#define NODELET_FATAL(...)
const char * getVendorName(unsigned device_idx)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
unsigned getProductID(unsigned device_idx)
freenect_video_format video_format