38 #include <boost/thread.hpp> 58 void depthCb(
const sensor_msgs::ImageConstPtr& raw_msg);
70 pub_depth_ =
it_->advertise(
"image", 1, connect_cb, connect_cb);
91 sensor_msgs::ImagePtr depth_msg(
new sensor_msgs::Image );
92 depth_msg->header = raw_msg->header;
93 depth_msg->height = raw_msg->height;
94 depth_msg->width = raw_msg->width;
97 if (raw_msg->encoding == enc::TYPE_16UC1)
99 depth_msg->encoding = enc::TYPE_32FC1;
100 depth_msg->step = raw_msg->width * (enc::bitDepth(depth_msg->encoding) / 8);
101 depth_msg->data.resize(depth_msg->height * depth_msg->step);
103 float bad_point = std::numeric_limits<float>::quiet_NaN ();
104 const uint16_t* raw_data =
reinterpret_cast<const uint16_t*
>(&raw_msg->data[0]);
105 float* depth_data =
reinterpret_cast<float*
>(&depth_msg->data[0]);
106 for (
unsigned index = 0; index < depth_msg->height * depth_msg->width; ++index)
108 uint16_t raw = raw_data[index];
109 depth_data[index] = (raw == 0) ? bad_point : (
float)raw * 0.001f;
112 else if (raw_msg->encoding == enc::TYPE_32FC1)
114 depth_msg->encoding = enc::TYPE_16UC1;
115 depth_msg->step = raw_msg->width * (enc::bitDepth(depth_msg->encoding) / 8);
116 depth_msg->data.resize(depth_msg->height * depth_msg->step);
118 uint16_t bad_point = 0;
119 const float* raw_data =
reinterpret_cast<const float*
>(&raw_msg->data[0]);
120 uint16_t* depth_data =
reinterpret_cast<uint16_t*
>(&depth_msg->data[0]);
121 for (
unsigned index = 0; index < depth_msg->height * depth_msg->width; ++index)
123 float raw = raw_data[index];
124 depth_data[index] = std::isnan(raw) ? bad_point : (uint16_t)(raw * 1000);
129 ROS_ERROR(
"Unsupported image conversion from %s.", raw_msg->encoding.c_str());
image_transport::Publisher pub_depth_
uint32_t getNumSubscribers() const
ros::NodeHandle & getNodeHandle() const
PLUGINLIB_EXPORT_CLASS(depth_image_proc::ConvertMetricNodelet, nodelet::Nodelet)
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
boost::mutex connect_mutex_
ros::NodeHandle & getPrivateNodeHandle() const
boost::shared_ptr< image_transport::ImageTransport > it_
image_transport::Subscriber sub_raw_
void publish(const sensor_msgs::Image &message) const
void depthCb(const sensor_msgs::ImageConstPtr &raw_msg)