$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, 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 Willow Garage, Inc. 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 * $Id: point_cloud_conversion.h 32910 2010-09-27 22:48:42Z tfoote $ 00035 * 00036 */ 00037 00038 #include <ros/console.h> 00039 #include <sensor_msgs/point_cloud_conversion.h> 00040 00041 int 00042 sensor_msgs::getPointCloud2FieldIndex (const sensor_msgs::PointCloud2 &cloud, 00043 const std::string &field_name) 00044 { 00045 // Get the index we need 00046 for (size_t d = 0; d < cloud.fields.size (); ++d) 00047 if (cloud.fields[d].name == field_name) 00048 return (d); 00049 return (-1); 00050 } 00051 00052 bool 00053 sensor_msgs::convertPointCloudToPointCloud2 (const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output) 00054 { 00055 output.header = input.header; 00056 output.width = input.points.size (); 00057 output.height = 1; 00058 output.fields.resize (3 + input.channels.size ()); 00059 // Convert x/y/z to fields 00060 output.fields[0].name = "x"; output.fields[1].name = "y"; output.fields[2].name = "z"; 00061 int offset = 0; 00062 // All offsets are *4, as all field data types are float32 00063 for (size_t d = 0; d < output.fields.size (); ++d, offset += 4) 00064 { 00065 output.fields[d].offset = offset; 00066 output.fields[d].datatype = sensor_msgs::PointField::FLOAT32; 00067 output.fields[d].count = 1; 00068 } 00069 output.point_step = offset; 00070 output.row_step = output.point_step * output.width; 00071 // Convert the remaining of the channels to fields 00072 for (size_t d = 0; d < input.channels.size (); ++d) 00073 output.fields[3 + d].name = input.channels[d].name; 00074 output.data.resize (input.points.size () * output.point_step); 00075 output.is_bigendian = false; // @todo ? 00076 output.is_dense = false; 00077 00078 // Copy the data points 00079 for (size_t cp = 0; cp < input.points.size (); ++cp) 00080 { 00081 memcpy (&output.data[cp * output.point_step + output.fields[0].offset], &input.points[cp].x, sizeof (float)); 00082 memcpy (&output.data[cp * output.point_step + output.fields[1].offset], &input.points[cp].y, sizeof (float)); 00083 memcpy (&output.data[cp * output.point_step + output.fields[2].offset], &input.points[cp].z, sizeof (float)); 00084 for (size_t d = 0; d < input.channels.size (); ++d) 00085 { 00086 if (input.channels[d].values.size() == input.points.size()) 00087 { 00088 memcpy (&output.data[cp * output.point_step + output.fields[3 + d].offset], &input.channels[d].values[cp], sizeof (float)); 00089 } 00090 } 00091 } 00092 return (true); 00093 } 00094 00095 bool 00096 sensor_msgs::convertPointCloud2ToPointCloud (const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud &output) 00097 { 00098 // Get all fields size and check if we have non-float32 values 00099 for (size_t d = 0; d < input.fields.size (); ++d) 00100 { 00101 if (input.fields[d].datatype != sensor_msgs::PointField::FLOAT32) 00102 { 00103 ROS_WARN ("sensor_msgs::PointCloud accepts only float32 values, but field %d (%s) has field type %d!", (int)d, input.fields[d].name.c_str (), input.fields[d].datatype); 00104 } 00105 } 00106 00107 output.header = input.header; 00108 output.points.resize (input.width * input.height); 00109 output.channels.resize (input.fields.size () - 3); 00110 // Get the x/y/z field offsets 00111 int x_idx = getPointCloud2FieldIndex (input, "x"); 00112 int y_idx = getPointCloud2FieldIndex (input, "y"); 00113 int z_idx = getPointCloud2FieldIndex (input, "z"); 00114 if (x_idx == -1 || y_idx == -1 || z_idx == -1) 00115 { 00116 ROS_ERROR ("x/y/z coordinates not found! Cannot convert to sensor_msgs::PointCloud!"); 00117 return (false); 00118 } 00119 int x_offset = input.fields[x_idx].offset; 00120 int y_offset = input.fields[y_idx].offset; 00121 int z_offset = input.fields[z_idx].offset; 00122 00123 // Convert the fields to channels 00124 int cur_c = 0; 00125 for (size_t d = 0; d < input.fields.size (); ++d) 00126 { 00127 if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset) 00128 continue; 00129 output.channels[cur_c].name = input.fields[d].name; 00130 output.channels[cur_c].values.resize (output.points.size ()); 00131 cur_c++; 00132 } 00133 00134 // Copy the data points 00135 for (size_t cp = 0; cp < output.points.size (); ++cp) 00136 { 00137 // Copy x/y/z 00138 memcpy (&output.points[cp].x, &input.data[cp * input.point_step + x_offset], sizeof (float)); 00139 memcpy (&output.points[cp].y, &input.data[cp * input.point_step + y_offset], sizeof (float)); 00140 memcpy (&output.points[cp].z, &input.data[cp * input.point_step + z_offset], sizeof (float)); 00141 // Copy the rest of the data 00142 int cur_c = 0; 00143 for (size_t d = 0; d < input.fields.size (); ++d) 00144 { 00145 if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset) 00146 continue; 00147 memcpy (&output.channels[cur_c++].values[cp], &input.data[cp * input.point_step + input.fields[d].offset], sizeof (float)); 00148 } 00149 } 00150 return (true); 00151 }