$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id:$ 00005 * 00006 * Copyright (C) Brno University of Technology 00007 * 00008 * This file is part of software developed by dcgm-robotics@FIT group. 00009 * 00010 * Author: Vit Stancl (stancl@fit.vutbr.cz) 00011 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00012 * Date: 10.7.2012 00013 * 00014 * This file is free software: you can redistribute it and/or modify 00015 * it under the terms of the GNU Lesser General Public License as published by 00016 * the Free Software Foundation, either version 3 of the License, or 00017 * (at your option) any later version. 00018 * 00019 * This file is distributed in the hope that it will be useful, 00020 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00021 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00022 * GNU Lesser General Public License for more details. 00023 * 00024 * You should have received a copy of the GNU Lesser General Public License 00025 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00026 */ 00027 00028 #include "ros/ros.h" 00029 #include <message_filters/subscriber.h> 00030 #include <sensor_msgs/PointCloud2.h> 00031 #include <sensor_msgs/Image.h> 00032 #include <sensor_msgs/image_encodings.h> 00033 #include <tf/message_filter.h> 00034 00035 #define POINTCLOUD_TOPIC_NAME std::string("/cam3d/depth/points") 00036 #define IMAGE_TOPIC_NAME std::string("/srs_ui_but/depth/image") 00037 00038 namespace srs_ui_but 00039 { 00040 00041 class CPCTransformer 00042 { 00043 protected: 00045 typedef sensor_msgs::PointCloud2 tIncommingPointCloud; 00046 00048 typedef sensor_msgs::Image tImage; 00049 00050 public: 00052 CPCTransformer() 00053 : m_pcFrameId("/head_cam3d_link") 00054 { 00055 } 00056 00057 bool init() 00058 { 00059 ros::NodeHandle nh; 00060 00061 // Try to get point cloud publisher name 00062 nh.param("pointcloud_topic_name", m_pcTopicName, POINTCLOUD_TOPIC_NAME ); 00063 00064 // Try to get publishing topic name 00065 nh.param("image_topic_name", m_imageTopicName, IMAGE_TOPIC_NAME ); 00066 00067 // Create publisher 00068 m_publisher = nh.advertise<tImage> (m_imageTopicName, 100, false); 00069 00070 // Try to subscribe 00071 m_pcSubscriber = new message_filters::Subscriber<tIncommingPointCloud>(nh, m_pcTopicName, 5); 00072 00073 if (!m_pcSubscriber) 00074 { 00075 ROS_ERROR("Not subscribed..."); 00076 //PERROR( "Not subscirbed to point clouds subscriber..."); 00077 return false; 00078 } 00079 00080 // std::cerr << "Subscribed..." << std::endl; 00081 00082 // Create message filter 00083 m_tfPointCloudSub = new tf::MessageFilter<tIncommingPointCloud>( *m_pcSubscriber, m_tfListener, m_pcFrameId, 5); 00084 m_tfPointCloudSub->registerCallback(boost::bind( &CPCTransformer::insertCloudCallback, this, _1)); 00085 00086 return true; 00087 } 00088 00089 protected: 00090 void insertCloudCallback(const tIncommingPointCloud::ConstPtr& cloud) 00091 { 00092 // No subscribers - no need to publish data... 00093 if( m_publisher.getNumSubscribers() == 0 ) 00094 return; 00095 00096 // std::cerr << "Insert cloud callback. " << std::endl; 00097 00098 sensor_msgs::ImagePtr ptrImage( new sensor_msgs::Image ); 00099 00100 // Set image parameters 00101 std::size_t width = ptrImage->width = cloud->width; 00102 std::size_t height = ptrImage->height = cloud->height; 00103 00104 // No data? 00105 if( width * height == 0 ) 00106 { 00107 std::cerr << "Not a dense cloud." << std::endl; 00108 return; 00109 } 00110 00111 ptrImage->encoding = sensor_msgs::image_encodings::MONO16; 00112 ptrImage->step = ptrImage->width * sizeof( uint16_t ); 00113 ptrImage->data.resize( height * ptrImage->step ); 00114 00115 // Get appropriate index 00116 int depth_index = -1; 00117 for (size_t d = 0; d < cloud->fields.size (); ++d) 00118 if (cloud->fields[d].name == "z") 00119 { 00120 depth_index = (int) d; 00121 break; 00122 } 00123 00124 if( depth_index == -1 ) 00125 { 00126 std::cerr << "No depth information found" << std::endl; 00127 return; 00128 } 00129 00130 // std::cerr << "Image size: " << width << "x" << height << std::endl; 00131 00132 // Get data 00133 int depth_offset = cloud->fields[depth_index].offset; 00134 int point_step = cloud->point_step; 00135 00136 float min(1000000.0), max(-10000000.0 ); 00137 00138 for (size_t y = 0; y < height; y++) 00139 { 00140 for (size_t x = 0; x < width; x++, depth_offset += point_step) 00141 { 00142 uint16_t * pixel = reinterpret_cast<uint16_t *>(&(ptrImage->data[y * ptrImage->step + x * sizeof(uint16_t)])); 00143 00144 float v(*reinterpret_cast<const float *>( &cloud->data[depth_offset] )); 00145 00146 // Cut on kinect resolution distance (avg 6m) 00147 // if( v > 10.0 ) 00148 // v = 10.0; 00149 00150 if( v > max ) max = v; 00151 if( v < min ) min = v; 00152 00153 *pixel = uint16_t( v * 1000.0 ); 00154 } 00155 } 00156 00157 // std::cerr << "Publishing. < " << min << ", " << max << " >" << std::endl; 00158 00159 // all done, publish image 00160 m_publisher.publish( *ptrImage ); 00161 00162 } 00163 00164 00165 protected: 00167 std::string m_pcTopicName; 00168 00170 std::string m_imageTopicName; 00171 00173 message_filters::Subscriber<tIncommingPointCloud> *m_pcSubscriber; 00174 00176 tf::MessageFilter<tIncommingPointCloud> *m_tfPointCloudSub; 00177 00179 ros::Publisher m_publisher; 00180 00182 tf::TransformListener m_tfListener; 00183 00185 std::string m_pcFrameId; 00186 00187 00188 00189 }; // class CPCTransformer 00190 00191 } // namespace srs_ui_but 00192 00196 int main(int argc, char **argv) 00197 { 00198 ros::init(argc, argv, "but_depthtoimage_node"); 00199 00200 srs_ui_but::CPCTransformer transformer; 00201 00202 if( !transformer.init() ) 00203 return 0; 00204 00205 ros::Rate loop_rate(10); 00206 00207 while( ros::ok() ) 00208 { 00209 ros::spinOnce(); 00210 loop_rate.sleep(); 00211 00212 } 00213 00214 return 0; 00215 } // main 00216 00217