convert_metric.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
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   // Subscriptions
00047   boost::shared_ptr<image_transport::ImageTransport> it_;
00048   image_transport::Subscriber sub_raw_;
00049 
00050   // Publications
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   // Monitor whether anyone is subscribed to the output
00067   image_transport::SubscriberStatusCallback connect_cb = boost::bind(&ConvertMetricNodelet::connectCb, this);
00068   // Make sure we don't enter connectCb() between advertising and assigning to pub_depth_
00069   boost::lock_guard<boost::mutex> lock(connect_mutex_);
00070   pub_depth_ = it_->advertise("image", 1, connect_cb, connect_cb);
00071 }
00072 
00073 // Handles (un)subscribing when clients (un)subscribe
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   if (raw_msg->encoding != enc::TYPE_16UC1)
00091   {
00092     NODELET_ERROR_THROTTLE(2, "Expected data of type [%s], got [%s]", enc::TYPE_16UC1.c_str(),
00093                            raw_msg->encoding.c_str());
00094     return;
00095   }
00096 
00097   // Allocate new Image message
00098   sensor_msgs::ImagePtr depth_msg( new sensor_msgs::Image );
00099   depth_msg->header   = raw_msg->header;
00100   depth_msg->encoding = enc::TYPE_32FC1;
00101   depth_msg->height   = raw_msg->height;
00102   depth_msg->width    = raw_msg->width;
00103   depth_msg->step     = raw_msg->width * sizeof (float);
00104   depth_msg->data.resize( depth_msg->height * depth_msg->step);
00105 
00106   float bad_point = std::numeric_limits<float>::quiet_NaN ();
00107 
00108   // Fill in the depth image data, converting mm to m
00109   const uint16_t* raw_data = reinterpret_cast<const uint16_t*>(&raw_msg->data[0]);
00110   float* depth_data = reinterpret_cast<float*>(&depth_msg->data[0]);
00111   for (unsigned index = 0; index < depth_msg->height * depth_msg->width; ++index)
00112   {
00113     uint16_t raw = raw_data[index];
00114     depth_data[index] = (raw == 0) ? bad_point : (float)raw * 0.001f;
00115   }
00116 
00117   pub_depth_.publish(depth_msg);
00118 }
00119 
00120 } // namespace depth_image_proc
00121 
00122 // Register as nodelet
00123 #include <pluginlib/class_list_macros.h>
00124 PLUGINLIB_EXPORT_CLASS(depth_image_proc::ConvertMetricNodelet,nodelet::Nodelet);


depth_image_proc
Author(s): Patrick Mihelich
autogenerated on Wed Aug 26 2015 11:57:40