Go to the documentation of this file.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 #include <ros/ros.h>
00035 #include <nodelet/nodelet.h>
00036 #include <image_transport/image_transport.h>
00037 #include <sensor_msgs/image_encodings.h>
00038 #include <boost/thread.hpp>
00039
00040 namespace depth_image_proc {
00041
00042 namespace enc = sensor_msgs::image_encodings;
00043
00044 class ConvertMetricNodelet : public nodelet::Nodelet
00045 {
00046
00047 boost::shared_ptr<image_transport::ImageTransport> it_;
00048 image_transport::Subscriber sub_raw_;
00049
00050
00051 boost::mutex connect_mutex_;
00052 image_transport::Publisher pub_depth_;
00053
00054 virtual void onInit();
00055
00056 void connectCb();
00057
00058 void depthCb(const sensor_msgs::ImageConstPtr& raw_msg);
00059 };
00060
00061 void ConvertMetricNodelet::onInit()
00062 {
00063 ros::NodeHandle& nh = getNodeHandle();
00064 it_.reset(new image_transport::ImageTransport(nh));
00065
00066
00067 image_transport::SubscriberStatusCallback connect_cb = boost::bind(&ConvertMetricNodelet::connectCb, this);
00068
00069 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00070 pub_depth_ = it_->advertise("image", 1, connect_cb, connect_cb);
00071 }
00072
00073
00074 void ConvertMetricNodelet::connectCb()
00075 {
00076 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00077 if (pub_depth_.getNumSubscribers() == 0)
00078 {
00079 sub_raw_.shutdown();
00080 }
00081 else if (!sub_raw_)
00082 {
00083 image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00084 sub_raw_ = it_->subscribe("image_raw", 1, &ConvertMetricNodelet::depthCb, this, hints);
00085 }
00086 }
00087
00088 void ConvertMetricNodelet::depthCb(const sensor_msgs::ImageConstPtr& raw_msg)
00089 {
00090
00091 sensor_msgs::ImagePtr depth_msg( new sensor_msgs::Image );
00092 depth_msg->header = raw_msg->header;
00093 depth_msg->height = raw_msg->height;
00094 depth_msg->width = raw_msg->width;
00095
00096
00097 if (raw_msg->encoding == enc::TYPE_16UC1)
00098 {
00099 depth_msg->encoding = enc::TYPE_32FC1;
00100 depth_msg->step = raw_msg->width * (enc::bitDepth(depth_msg->encoding) / 8);
00101 depth_msg->data.resize(depth_msg->height * depth_msg->step);
00102
00103 float bad_point = std::numeric_limits<float>::quiet_NaN ();
00104 const uint16_t* raw_data = reinterpret_cast<const uint16_t*>(&raw_msg->data[0]);
00105 float* depth_data = reinterpret_cast<float*>(&depth_msg->data[0]);
00106 for (unsigned index = 0; index < depth_msg->height * depth_msg->width; ++index)
00107 {
00108 uint16_t raw = raw_data[index];
00109 depth_data[index] = (raw == 0) ? bad_point : (float)raw * 0.001f;
00110 }
00111 }
00112 else if (raw_msg->encoding == enc::TYPE_32FC1)
00113 {
00114 depth_msg->encoding = enc::TYPE_16UC1;
00115 depth_msg->step = raw_msg->width * (enc::bitDepth(depth_msg->encoding) / 8);
00116 depth_msg->data.resize(depth_msg->height * depth_msg->step);
00117
00118 uint16_t bad_point = 0;
00119 const float* raw_data = reinterpret_cast<const float*>(&raw_msg->data[0]);
00120 uint16_t* depth_data = reinterpret_cast<uint16_t*>(&depth_msg->data[0]);
00121 for (unsigned index = 0; index < depth_msg->height * depth_msg->width; ++index)
00122 {
00123 float raw = raw_data[index];
00124 depth_data[index] = std::isnan(raw) ? bad_point : (uint16_t)(raw * 1000);
00125 }
00126 }
00127 else
00128 {
00129 ROS_ERROR("Unsupported image conversion from %s.", raw_msg->encoding.c_str());
00130 return;
00131 }
00132
00133 pub_depth_.publish(depth_msg);
00134 }
00135
00136 }
00137
00138
00139 #include <pluginlib/class_list_macros.h>
00140 PLUGINLIB_EXPORT_CLASS(depth_image_proc::ConvertMetricNodelet,nodelet::Nodelet);