47 #include <boost/algorithm/string/replace.hpp>    49 #include <log4cxx/logger.h>    55 inline bool operator == (
const XnMapOutputMode& mode1, 
const XnMapOutputMode& mode2)
    57   return (mode1.nXRes == mode2.nXRes && mode1.nYRes == mode2.nYRes && mode1.nFPS == mode2.nFPS);
    59 inline bool operator != (
const XnMapOutputMode& mode1, 
const XnMapOutputMode& mode2)
    61   return !(mode1 == mode2);
    64 DriverNodelet::~DriverNodelet ()
    67   init_thread_.interrupt();
    79 void DriverNodelet::onInit ()
    91   reconfigure_server_->setCallback(boost::bind(&DriverNodelet::configCb, 
this, _1, _2));
    95   init_thread_ = boost::thread(boost::bind(&DriverNodelet::onInitImpl, 
this));
    98 void DriverNodelet::onInitImpl ()
   115   rgb_frame_counter_ = depth_frame_counter_ = ir_frame_counter_ = 0;
   116   publish_rgb_ = publish_ir_ = publish_depth_ = 
true;
   120   param_nh.
param(
"rgb_frame_id",   rgb_frame_id_,   
string(
"/openni_rgb_optical_frame"));
   121   param_nh.
param(
"depth_frame_id", depth_frame_id_, 
string(
"/openni_depth_optical_frame"));
   122   NODELET_INFO(
"rgb_frame_id = '%s' ",   rgb_frame_id_.c_str());
   123   NODELET_INFO(
"depth_frame_id = '%s' ", depth_frame_id_.c_str());
   133   std::string serial_number = device_->getSerialNumber();
   134   std::string rgb_name, ir_name;
   135   if (serial_number.empty())
   142     rgb_name = 
"rgb_"   + serial_number;
   143     ir_name  = 
"depth_" + serial_number;
   146   std::string rgb_info_url, ir_info_url;
   147   param_nh.
param(
"rgb_camera_info_url", rgb_info_url, std::string());
   148   param_nh.
param(
"depth_camera_info_url", ir_info_url, std::string());
   151   log4cxx::LoggerPtr logger_ccp = log4cxx::Logger::getLogger(
"ros.camera_calibration_parsers");
   152   log4cxx::LoggerPtr logger_cim = log4cxx::Logger::getLogger(
"ros.camera_info_manager");
   153   logger_ccp->setLevel(log4cxx::Level::getFatal());
   154   logger_cim->setLevel(log4cxx::Level::getWarn());
   159   log4cxx::LoggerPtr logger_its = log4cxx::Logger::getLogger(
"ros.image_transport.sync");
   160   logger_its->setLevel(log4cxx::Level::getError());
   164   rgb_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(rgb_nh, rgb_name, rgb_info_url);
   165   ir_info_manager_  = boost::make_shared<camera_info_manager::CameraInfoManager>(ir_nh,  ir_name,  ir_info_url);
   167   if (!rgb_info_manager_->isCalibrated())
   168     NODELET_WARN(
"Using default parameters for RGB camera calibration.");
   169   if (!ir_info_manager_->isCalibrated())
   170     NODELET_WARN(
"Using default parameters for IR camera calibration.");
   178     boost::lock_guard<boost::mutex> lock(connect_mutex_);
   181     if (device_->hasImageStream())
   185       pub_rgb_ = rgb_it.
advertiseCamera(
"image_raw", 1, itssc, itssc, rssc, rssc);
   188     if (device_->hasIRStream())
   192       pub_ir_ = ir_it.
advertiseCamera(
"image_raw", 1, itssc, itssc, rssc, rssc);
   195     if (device_->hasDepthStream())
   199       pub_depth_ = depth_it.
advertiseCamera(
"image_raw", 1, itssc, itssc, rssc, rssc);
   200       pub_projector_info_ = projector_nh.
advertise<sensor_msgs::CameraInfo>(
"camera_info", 1, rssc, rssc);
   202       if (device_->isDepthRegistrationSupported())
   203         pub_depth_registered_ = depth_registered_it.
advertiseCamera(
"image_raw", 1, itssc, itssc, rssc, rssc);
   208   if (param_nh.
getParam(
"time_out", time_out_) && time_out_ > 0.0)
   215 void DriverNodelet::setupDevice ()
   225       NODELET_INFO (
"No devices connected.... waiting for devices to be connected");
   226       boost::this_thread::sleep(boost::posix_time::seconds(3));
   231     for (
unsigned deviceIdx = 0; deviceIdx < driver.
getNumberDevices (); ++deviceIdx)
   233       NODELET_INFO(
"%u. device on bus %03u:%02u is a %s (%03x) from %s (%03x) with serial id \'%s\'",
   243       if (!getPrivateNodeHandle().getParam(
"device_id", device_id) &&
   244           !getPrivateNodeHandle().getParam(
"device_id", device_id_int))
   247         NODELET_WARN (
"~device_id is not set! Using first device.");
   250       else if (device_id.find (
'@') != string::npos)
   252         size_t pos = device_id.find (
'@');
   253         unsigned bus = atoi (device_id.substr (0, pos).c_str ());
   254         unsigned address = atoi (device_id.substr (pos + 1, device_id.length () - pos - 1).c_str ());
   255         NODELET_INFO (
"Searching for device with bus@address = %d@%d", bus, address);
   258       else if (device_id[0] == 
'#')
   260         unsigned index = atoi (device_id.c_str () + 1);
   261         NODELET_INFO (
"Searching for device with index = %d", index);
   266         if (device_id.empty()) 
   268             std::stringstream ss;
   270             device_id = ss.str();
   272         NODELET_INFO (
"Searching for device with serial number = '%s'", device_id.c_str ());
   280         NODELET_INFO (
"No matching device found.... waiting for devices. Reason: %s", exception.
what ());
   281         boost::this_thread::sleep(boost::posix_time::seconds(3));
   292   NODELET_INFO (
"Opened '%s' on bus %d:%d with serial number '%s'", device_->getProductName (),
   293                 device_->getBus (), device_->getAddress (), device_->getSerialNumber ());
   295   device_->registerImageCallback(&DriverNodelet::rgbCb,   *
this);
   296   device_->registerDepthCallback(&DriverNodelet::depthCb, *
this);
   297   device_->registerIRCallback   (&DriverNodelet::irCb,    *
this);
   300 void DriverNodelet::rgbConnectCb()
   302   boost::lock_guard<boost::mutex> lock(connect_mutex_);
   303   bool need_rgb = pub_rgb_.getNumSubscribers() > 0;
   305   if (need_rgb && !device_->isImageStreamRunning())
   308     if (device_->isIRStreamRunning())
   310       NODELET_ERROR(
"Cannot stream RGB and IR at the same time. Streaming RGB only.");
   311       device_->stopIRStream();
   314     device_->startImageStream();
   315     startSynchronization();
   318   else if (!need_rgb && device_->isImageStreamRunning())
   320     stopSynchronization();
   321     device_->stopImageStream();
   324     bool need_ir = pub_ir_.getNumSubscribers() > 0;
   325     if (need_ir && !device_->isIRStreamRunning())
   327       device_->startIRStream();
   333 void DriverNodelet::depthConnectCb()
   335   boost::lock_guard<boost::mutex> lock(connect_mutex_);
   338     device_->isDepthRegistered() ? pub_depth_registered_.getNumSubscribers() > 0 : pub_depth_.getNumSubscribers() > 0;
   341   if (need_depth && !device_->isDepthStreamRunning())
   343     device_->startDepthStream();
   344     startSynchronization();
   347   else if (!need_depth && device_->isDepthStreamRunning())
   349     stopSynchronization();
   350     device_->stopDepthStream();
   354 void DriverNodelet::irConnectCb()
   356   boost::lock_guard<boost::mutex> lock(connect_mutex_);
   357   bool need_ir = pub_ir_.getNumSubscribers() > 0;
   359   if (need_ir && !device_->isIRStreamRunning())
   362     if (device_->isImageStreamRunning())
   364       NODELET_ERROR(
"Cannot stream RGB and IR at the same time. Streaming RGB only.");
   368       device_->startIRStream();
   374     device_->stopIRStream();
   381 void DriverNodelet::checkFrameCounters()
   383     if (max(rgb_frame_counter_, max(depth_frame_counter_, ir_frame_counter_)) > config_.data_skip) {
   385         rgb_frame_counter_   = 0;
   386         depth_frame_counter_ = 0;
   387         ir_frame_counter_    = 0;
   391         publish_depth_ = 
true;
   404   bool publish = 
false;
   406       boost::unique_lock<boost::mutex> counter_lock(counter_mutex_);
   407       rgb_frame_counter_++;
   408       checkFrameCounters();
   409       publish = publish_rgb_;
   412           rgb_frame_counter_ = 0; 
   416       publishRgbImage(*image, time);
   418   publish_rgb_ = 
false;
   429   bool publish = 
false;
   431       boost::unique_lock<boost::mutex> counter_lock(counter_mutex_);
   432       depth_frame_counter_++;
   433       checkFrameCounters();
   434       publish = publish_depth_;
   437           depth_frame_counter_ = 0; 
   441       publishDepthImage(*depth_image, time);
   443   publish_depth_ = 
false;
   454   bool publish = 
false;
   456       boost::unique_lock<boost::mutex> counter_lock(counter_mutex_);
   458       checkFrameCounters();
   459       publish = publish_ir_;
   462           ir_frame_counter_ = 0; 
   466       publishIrImage(*ir_image, time);
   472   sensor_msgs::ImagePtr rgb_msg = boost::make_shared<sensor_msgs::Image >();
   473   rgb_msg->header.stamp = time;
   474   rgb_msg->header.frame_id = rgb_frame_id_;
   475   bool downscale = 
false;
   482       rgb_msg->step = image_width_;
   488       rgb_msg->step = image_width_ * 3;
   498       rgb_msg->step = image_width_ * 2; 
   504       rgb_msg->step = image_width_ * 3;
   508   rgb_msg->height = image_height_;
   509   rgb_msg->width = image_width_;
   510   rgb_msg->data.resize(rgb_msg->height * rgb_msg->step);
   519         bayer_image.
fillRGB(image_width_, image_height_, &rgb_msg->data[0]);
   524         yuv_image.
fillRGB(image_width_, image_height_, &rgb_msg->data[0]);
   528       image.
fillRaw(&rgb_msg->data[0]);
   535   pub_rgb_.publish(rgb_msg, getRgbCameraInfo(rgb_msg->width,rgb_msg->height,time));
   540   bool registered = device_->isDepthRegistered();
   543   sensor_msgs::ImagePtr depth_msg = boost::make_shared<sensor_msgs::Image>();
   544   depth_msg->header.stamp    = time;
   546   depth_msg->width           = depth_width_;
   547   depth_msg->height          = depth_height_;
   548   depth_msg->step            = depth_msg->width * 
sizeof(short);
   549   depth_msg->data.resize(depth_msg->height * depth_msg->step);
   553     depth.
fillDepthImageRaw(depth_msg->width, depth_msg->height, reinterpret_cast<unsigned short*>(&depth_msg->data[0]),
   561   if (fabs(z_scaling_ - 1.0) > 1e-6)
   563     uint16_t* data = 
reinterpret_cast<uint16_t*
>(&depth_msg->data[0]);
   564     for (
unsigned int i = 0; i < depth_msg->width * depth_msg->height; ++i)
   566             data[i] = 
static_cast<uint16_t
>(data[i] * z_scaling_);
   569   if (z_offset_mm_ != 0)
   571     uint16_t* data = 
reinterpret_cast<uint16_t*
>(&depth_msg->data[0]);
   572     for (
unsigned int i = 0; i < depth_msg->width * depth_msg->height; ++i)
   574             data[i] += z_offset_mm_;
   580     depth_msg->header.frame_id = rgb_frame_id_;
   581     pub_depth_registered_.publish(depth_msg, getRgbCameraInfo(depth_msg->width, depth_msg->height, time));
   586     depth_msg->header.frame_id = depth_frame_id_;
   587     pub_depth_.publish(depth_msg, getDepthCameraInfo(depth_msg->width, depth_msg->height, time));
   591   if (pub_projector_info_.getNumSubscribers() > 0)
   593     pub_projector_info_.publish(getProjectorCameraInfo(depth_msg->width, depth_msg->height, time));
   599   sensor_msgs::ImagePtr ir_msg = boost::make_shared<sensor_msgs::Image>();
   600   ir_msg->header.stamp    = time;
   601   ir_msg->header.frame_id = depth_frame_id_;
   605   ir_msg->step            = ir_msg->width * 
sizeof(uint16_t);
   606   ir_msg->data.resize(ir_msg->height * ir_msg->step);
   620 sensor_msgs::CameraInfoPtr DriverNodelet::getDefaultCameraInfo(
int width, 
int height, 
double f)
 const   622   sensor_msgs::CameraInfoPtr info = boost::make_shared<sensor_msgs::CameraInfo>();
   625   info->height = height;
   628   info->D.resize(5, 0.0);
   633   info->K[0] = info->K[4] = 
f;
   634   info->K[2] = (width / 2) - 0.5;
   637   info->K[5] = (width * (3./8.)) - 0.5;
   642   info->R[0] = info->R[4] = info->R[8] = 1.0;
   646   info->P[0]  = info->P[5] = 
f; 
   647   info->P[2]  = info->K[2];     
   648   info->P[6]  = info->K[5];     
   655 sensor_msgs::CameraInfoPtr DriverNodelet::getRgbCameraInfo(
int width, 
int height, 
ros::Time time)
 const   657   sensor_msgs::CameraInfoPtr info;
   659   if (rgb_info_manager_->isCalibrated())
   661     info = boost::make_shared<sensor_msgs::CameraInfo>(rgb_info_manager_->getCameraInfo());
   662     if ( info->width != width )
   665       ROS_WARN_ONCE(
"Image resolution doesn't match calibration of the RGB camera. Using default parameters.");
   666       info = getDefaultCameraInfo(width, height, device_->getImageFocalLength(width));
   672     info = getDefaultCameraInfo(width, height, device_->getImageFocalLength(width));
   676   info->header.stamp    = time;
   677   info->header.frame_id = rgb_frame_id_;
   682 sensor_msgs::CameraInfoPtr DriverNodelet::getIrCameraInfo(
int width, 
int height, 
ros::Time time)
 const   684   sensor_msgs::CameraInfoPtr info;
   686   if (ir_info_manager_->isCalibrated())
   688     info = boost::make_shared<sensor_msgs::CameraInfo>(ir_info_manager_->getCameraInfo());
   689     if ( info->width != width )
   692       ROS_WARN_ONCE(
"Image resolution doesn't match calibration of the IR camera. Using default parameters.");
   693       info = getDefaultCameraInfo(width, height, device_->getImageFocalLength(width));
   699     info = getDefaultCameraInfo(width, height, device_->getDepthFocalLength(width));
   703   info->header.stamp    = time;
   704   info->header.frame_id = depth_frame_id_;
   709 sensor_msgs::CameraInfoPtr DriverNodelet::getDepthCameraInfo(
int width, 
int height, 
ros::Time time)
 const   715   double scaling = (double)width / 640;
   717   sensor_msgs::CameraInfoPtr info = getIrCameraInfo(width, height, time);
   718   info->K[2] -= depth_ir_offset_x_*scaling; 
   719   info->K[5] -= depth_ir_offset_y_*scaling; 
   720   info->P[2] -= depth_ir_offset_x_*scaling; 
   721   info->P[6] -= depth_ir_offset_y_*scaling; 
   727 sensor_msgs::CameraInfoPtr DriverNodelet::getProjectorCameraInfo(
int width, 
int height, 
ros::Time time)
 const   732   sensor_msgs::CameraInfoPtr info = getDepthCameraInfo(width, height, time);
   734   info->P[3] = -device_->getBaseline() * info->P[0];
   738 void DriverNodelet::configCb(
Config &config, uint32_t level)
   740   depth_ir_offset_x_ = config.depth_ir_offset_x;
   741   depth_ir_offset_y_ = config.depth_ir_offset_y;
   742   z_offset_mm_ = config.z_offset_mm;
   743   z_scaling_ = config.z_scaling;
   752   bool depth_mode_changed = 
false;
   753   bool image_mode_changed = 
false;
   755   XnMapOutputMode compatible_image_mode;
   756   XnMapOutputMode compatible_depth_mode;
   758   if (device_->hasImageStream ())
   760     XnMapOutputMode image_mode = mapConfigMode2XnMode (config.image_mode);
   761     image_width_  = image_mode.nXRes;
   762     image_height_ = image_mode.nYRes;
   765     if (!device_->findCompatibleImageMode (image_mode, compatible_image_mode))
   767       XnMapOutputMode default_mode = device_->getDefaultImageMode();
   768       NODELET_WARN(
"Could not find any compatible image output mode for %d x %d @ %d. "   769                    "Falling back to default image output mode %d x %d @ %d.",
   770                     image_mode.nXRes, image_mode.nYRes, image_mode.nFPS,
   771                     default_mode.nXRes, default_mode.nYRes, default_mode.nFPS);
   773       config.image_mode = mapXnMode2ConfigMode(default_mode);
   774       image_mode = compatible_image_mode = default_mode;
   777     if ( compatible_image_mode != device_->getImageOutputMode () )
   779       image_mode_changed = 
true;
   783   if (device_->hasDepthStream())
   785     XnMapOutputMode depth_mode = mapConfigMode2XnMode (config.depth_mode);
   786     depth_width_  = depth_mode.nXRes;
   787     depth_height_ = depth_mode.nYRes;
   790     if (!device_->findCompatibleDepthMode (depth_mode, compatible_depth_mode))
   792       XnMapOutputMode default_mode = device_->getDefaultDepthMode();
   793       NODELET_WARN (
"Could not find any compatible depth output mode for %d x %d @ %d. "   794                     "Falling back to default depth output mode %d x %d @ %d.",
   795                     depth_mode.nXRes, depth_mode.nYRes, depth_mode.nFPS,
   796                     default_mode.nXRes, default_mode.nYRes, default_mode.nFPS);
   798       config.depth_mode = mapXnMode2ConfigMode(default_mode);
   799       depth_mode = compatible_depth_mode = default_mode;
   802     if ( compatible_depth_mode != device_->getDepthOutputMode () )
   804       depth_mode_changed = 
true;
   809   if ( image_mode_changed || depth_mode_changed )
   812     stopSynchronization();
   814     if ( image_mode_changed )
   816       device_->setImageOutputMode (compatible_image_mode);
   819     if ( depth_mode_changed )
   821       device_->setDepthOutputMode (compatible_depth_mode);
   824     startSynchronization ();
   828   if (device_->isDepthRegistered () && !config.depth_registration)
   830     device_->setDepthRegistration (
false);
   832   else if (!device_->isDepthRegistered () && config.depth_registration)
   834     device_->setDepthRegistration (
true);
   843 void DriverNodelet::startSynchronization()
   845   if (device_->isSynchronizationSupported() &&
   846       !device_->isSynchronized() &&
   847       device_->getImageOutputMode().nFPS == device_->getDepthOutputMode().nFPS &&
   848       device_->isImageStreamRunning() &&
   849       device_->isDepthStreamRunning() )
   851     device_->setSynchronization(
true);
   855 void DriverNodelet::stopSynchronization()
   857   if (device_->isSynchronizationSupported() &&
   858       device_->isSynchronized())
   860     device_->setSynchronization(
false);
   864 void DriverNodelet::updateModeMaps ()
   866   XnMapOutputMode output_mode;
   868   output_mode.nXRes = XN_SXGA_X_RES;
   869   output_mode.nYRes = XN_SXGA_Y_RES;
   870   output_mode.nFPS  = 15;
   871   xn2config_map_[output_mode] = OpenNI_SXGA_15Hz;
   872   config2xn_map_[OpenNI_SXGA_15Hz] = output_mode;
   874   output_mode.nXRes = XN_VGA_X_RES;
   875   output_mode.nYRes = XN_VGA_Y_RES;
   876   output_mode.nFPS  = 25;
   877   xn2config_map_[output_mode] = OpenNI_VGA_25Hz;
   878   config2xn_map_[OpenNI_VGA_25Hz] = output_mode;
   879   output_mode.nFPS  = 30;
   880   xn2config_map_[output_mode] = OpenNI_VGA_30Hz;
   881   config2xn_map_[OpenNI_VGA_30Hz] = output_mode;
   883   output_mode.nXRes = XN_QVGA_X_RES;
   884   output_mode.nYRes = XN_QVGA_Y_RES;
   885   output_mode.nFPS  = 25;
   886   xn2config_map_[output_mode] = OpenNI_QVGA_25Hz;
   887   config2xn_map_[OpenNI_QVGA_25Hz] = output_mode;
   888   output_mode.nFPS  = 30;
   889   xn2config_map_[output_mode] = OpenNI_QVGA_30Hz;
   890   config2xn_map_[OpenNI_QVGA_30Hz] = output_mode;
   891   output_mode.nFPS  = 60;
   892   xn2config_map_[output_mode] = OpenNI_QVGA_60Hz;
   893   config2xn_map_[OpenNI_QVGA_60Hz] = output_mode;
   895   output_mode.nXRes = XN_QQVGA_X_RES;
   896   output_mode.nYRes = XN_QQVGA_Y_RES;
   897   output_mode.nFPS  = 25;
   898   xn2config_map_[output_mode] = OpenNI_QQVGA_25Hz;
   899   config2xn_map_[OpenNI_QQVGA_25Hz] = output_mode;
   900   output_mode.nFPS  = 30;
   901   xn2config_map_[output_mode] = OpenNI_QQVGA_30Hz;
   902   config2xn_map_[OpenNI_QQVGA_30Hz] = output_mode;
   903   output_mode.nFPS  = 60;
   904   xn2config_map_[output_mode] = OpenNI_QQVGA_60Hz;
   905   config2xn_map_[OpenNI_QQVGA_60Hz] = output_mode;
   908 int DriverNodelet::mapXnMode2ConfigMode (
const XnMapOutputMode& output_mode)
 const   910   std::map<XnMapOutputMode, int, modeComp>::const_iterator it = xn2config_map_.find (output_mode);
   912   if (it == xn2config_map_.end ())
   914     NODELET_ERROR (
"mode %dx%d@%d could not be found", output_mode.nXRes, output_mode.nYRes, output_mode.nFPS);
   921 XnMapOutputMode DriverNodelet::mapConfigMode2XnMode (
int mode)
 const   923   std::map<int, XnMapOutputMode>::const_iterator it = config2xn_map_.find (mode);
   924   if (it == config2xn_map_.end ())
   936   if ( !time_stamp_.isZero() && (device_->isDepthStreamRunning() || device_->isImageStreamRunning()) )
   939     if (duration.
toSec() >= time_out_)
   942       watch_dog_timer_.stop();
   943       throw std::runtime_error(
"Timeout occured in DriverNodelet");
 unsigned char getBus(unsigned index) const 
const char * getSerialNumber(unsigned index) const 
const std::string BAYER_GRBG8
unsigned short getVendorID(unsigned index) const 
virtual Encoding getEncoding() const =0
virtual const char * what() const 
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void fillRaw(unsigned width, unsigned height, unsigned short *ir_buffer, unsigned line_step=0) const 
#define NODELET_ERROR(...)
unsigned updateDeviceList()
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
#define NODELET_WARN(...)
const char * getProductName(unsigned index) const 
const char * getVendorName(unsigned index) const 
Driver class implemented as Singleton. This class contains the xn::Context object used by all devices...
dynamic_reconfigure::Server< Config > ReconfigureServer
boost::shared_ptr< OpenNIDevice > getDeviceBySerialNumber(const std::string &serial_number) const 
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
Image class containing just a reference to image meta data. Thus this class just provides an interfac...
bool operator!=(const XnMapOutputMode &mode1, const XnMapOutputMode &mode2)
Concrete implementation of the interface Image for a YUV 422 image used by Primesense devices...
unsigned getNumberDevices() const 
unsigned short getProductID(unsigned index) const 
unsigned getWidth() const 
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
virtual void fillRGB(unsigned width, unsigned height, unsigned char *rgb_buffer, unsigned rgb_line_step=0) const 
void fillDepthImageRaw(unsigned width, unsigned height, unsigned short *depth_buffer, unsigned line_step=0) const 
virtual void fillRGB(unsigned width, unsigned height, unsigned char *rgb_buffer, unsigned rgb_line_step=0) const 
#define ROS_WARN_ONCE(...)
boost::shared_ptr< OpenNIDevice > getDeviceByAddress(unsigned char bus, unsigned char address) const 
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
unsigned getWidth() const 
This class provides methods to fill a RGB or Grayscale image buffer from underlying Bayer pattern ima...
#define ROS_ERROR_THROTTLE(period,...)
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 
boost::shared_ptr< OpenNIDevice > getDeviceByIndex(unsigned index) const 
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
unsigned getHeight() const 
#define NODELET_INFO(...)
bool getParam(const std::string &key, std::string &s) const 
void fillRaw(unsigned char *rgb_buffer) const 
This class provides methods to fill a depth or disparity image. 
const boost::shared_ptr< xn::ImageMetaData > getMetaDataPtr() const 
unsigned char getAddress(unsigned index) const 
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
unsigned getHeight() const 
Class containing just a reference to IR meta data.