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
00006 namespace openni_camera {
00007
00008 namespace enc = sensor_msgs::image_encodings;
00009
00010 class MetricDepthNodelet : public nodelet::Nodelet
00011 {
00012
00013 boost::shared_ptr<image_transport::ImageTransport> it_;
00014 image_transport::Subscriber sub_raw_;
00015 bool subscribed_;
00016
00017
00018 image_transport::Publisher pub_depth_;
00019
00020 virtual void onInit();
00021
00022 void connectCb();
00023
00024 void depthCb(const sensor_msgs::ImageConstPtr& raw_msg);
00025 };
00026
00027 void MetricDepthNodelet::onInit()
00028 {
00029 ros::NodeHandle& nh = getNodeHandle();
00030 it_.reset(new image_transport::ImageTransport(nh));
00031
00032
00033 subscribed_ = false;
00034 image_transport::SubscriberStatusCallback connect_cb = boost::bind(&MetricDepthNodelet::connectCb, this);
00035 pub_depth_ = it_->advertise("image_rect", 1, connect_cb, connect_cb);
00036 }
00037
00038
00039 void MetricDepthNodelet::connectCb()
00040 {
00041 if (pub_depth_.getNumSubscribers() == 0)
00042 {
00043 sub_raw_.shutdown();
00044 subscribed_ = false;
00045 }
00046 else if (!subscribed_)
00047 {
00048 image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00049 sub_raw_ = it_->subscribe("image_rect_raw", 1, &MetricDepthNodelet::depthCb, this, hints);
00050 subscribed_ = true;
00051 }
00052 }
00053
00054 void MetricDepthNodelet::depthCb(const sensor_msgs::ImageConstPtr& raw_msg)
00055 {
00056 if (raw_msg->encoding != enc::TYPE_16UC1)
00057 {
00058 NODELET_ERROR("Expected data of type [%s], got [%s]", enc::TYPE_16UC1.c_str(),
00059 raw_msg->encoding.c_str());
00060 return;
00061 }
00062
00063
00064 sensor_msgs::ImagePtr depth_msg( new sensor_msgs::Image );
00065 depth_msg->header = raw_msg->header;
00066 depth_msg->encoding = enc::TYPE_32FC1;
00067 depth_msg->height = raw_msg->height;
00068 depth_msg->width = raw_msg->width;
00069 depth_msg->step = raw_msg->width * sizeof (float);
00070 depth_msg->data.resize( depth_msg->height * depth_msg->step);
00071
00072 float bad_point = std::numeric_limits<float>::quiet_NaN ();
00073
00074
00075 const uint16_t* raw_data = reinterpret_cast<const uint16_t*>(&raw_msg->data[0]);
00076 float* depth_data = reinterpret_cast<float*>(&depth_msg->data[0]);
00077 for (unsigned index = 0; index < depth_msg->height * depth_msg->width; ++index)
00078 {
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 }
00088
00089
00090 #include <pluginlib/class_list_macros.h>
00091 PLUGINLIB_DECLARE_CLASS (openni_camera, convert_metric, openni_camera::MetricDepthNodelet, nodelet::Nodelet);