convert_metric.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <nodelet/nodelet.h>
00003 #include <image_transport/image_transport.h>
00004 #include <sensor_msgs/image_encodings.h>
00005 #include <boost/thread.hpp>
00006 
00007 namespace depth_image_proc {
00008 
00009 namespace enc = sensor_msgs::image_encodings;
00010 
00011 class ConvertMetricNodelet : public nodelet::Nodelet
00012 {
00013   // Subscriptions
00014   boost::shared_ptr<image_transport::ImageTransport> it_;
00015   image_transport::Subscriber sub_raw_;
00016 
00017   // Publications
00018   boost::mutex connect_mutex_;
00019   image_transport::Publisher pub_depth_;
00020 
00021   virtual void onInit();
00022 
00023   void connectCb();
00024 
00025   void depthCb(const sensor_msgs::ImageConstPtr& raw_msg);
00026 };
00027 
00028 void ConvertMetricNodelet::onInit()
00029 {
00030   ros::NodeHandle& nh = getNodeHandle();
00031   it_.reset(new image_transport::ImageTransport(nh));
00032 
00033   // Monitor whether anyone is subscribed to the output
00034   image_transport::SubscriberStatusCallback connect_cb = boost::bind(&ConvertMetricNodelet::connectCb, this);
00035   // Make sure we don't enter connectCb() between advertising and assigning to pub_depth_
00036   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00037   pub_depth_ = it_->advertise("image", 1, connect_cb, connect_cb);
00038 }
00039 
00040 // Handles (un)subscribing when clients (un)subscribe
00041 void ConvertMetricNodelet::connectCb()
00042 {
00043   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00044   if (pub_depth_.getNumSubscribers() == 0)
00045   {
00046     sub_raw_.shutdown();
00047   }
00048   else if (!sub_raw_)
00049   {
00050     image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00051     sub_raw_ = it_->subscribe("image_raw", 1, &ConvertMetricNodelet::depthCb, this, hints);
00052   }
00053 }
00054 
00055 void ConvertMetricNodelet::depthCb(const sensor_msgs::ImageConstPtr& raw_msg)
00056 {
00057   if (raw_msg->encoding != enc::TYPE_16UC1)
00058   {
00059     NODELET_ERROR_THROTTLE(2, "Expected data of type [%s], got [%s]", enc::TYPE_16UC1.c_str(),
00060                            raw_msg->encoding.c_str());
00061     return;
00062   }
00063 
00064   // Allocate new Image message
00065   sensor_msgs::ImagePtr depth_msg( new sensor_msgs::Image );
00066   depth_msg->header   = raw_msg->header;
00067   depth_msg->encoding = enc::TYPE_32FC1;
00068   depth_msg->height   = raw_msg->height;
00069   depth_msg->width    = raw_msg->width;
00070   depth_msg->step     = raw_msg->width * sizeof (float);
00071   depth_msg->data.resize( depth_msg->height * depth_msg->step);
00072 
00073   float bad_point = std::numeric_limits<float>::quiet_NaN ();
00074 
00075   // Fill in the depth image data, converting mm to m
00076   const uint16_t* raw_data = reinterpret_cast<const uint16_t*>(&raw_msg->data[0]);
00077   float* depth_data = reinterpret_cast<float*>(&depth_msg->data[0]);
00078   for (unsigned index = 0; index < depth_msg->height * depth_msg->width; ++index)
00079   {
00080     uint16_t raw = raw_data[index];
00081     depth_data[index] = (raw == 0) ? bad_point : (float)raw * 0.001f;
00082   }
00083 
00084   pub_depth_.publish(depth_msg);
00085 }
00086 
00087 } // namespace depth_image_proc
00088 
00089 // Register as nodelet
00090 #include <pluginlib/class_list_macros.h>
00091 PLUGINLIB_DECLARE_CLASS (depth_image_proc, convert_metric, depth_image_proc::ConvertMetricNodelet, nodelet::Nodelet);


depth_image_proc
Author(s): Patrick Mihelich
autogenerated on Fri Jan 3 2014 11:24:53