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
00035
00036
00037
00038 #include <sensor_msgs/point_cloud_conversion.h>
00039
00040 int
00041 sensor_msgs::getPointCloud2FieldIndex (const sensor_msgs::PointCloud2 &cloud,
00042 const std::string &field_name)
00043 {
00044
00045 for (size_t d = 0; d < cloud.fields.size (); ++d)
00046 if (cloud.fields[d].name == field_name)
00047 return (d);
00048 return (-1);
00049 }
00050
00051 bool
00052 sensor_msgs::convertPointCloudToPointCloud2 (const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output)
00053 {
00054 output.header = input.header;
00055 output.width = input.points.size ();
00056 output.height = 1;
00057 output.fields.resize (3 + input.channels.size ());
00058
00059 output.fields[0].name = "x"; output.fields[1].name = "y"; output.fields[2].name = "z";
00060 int offset = 0;
00061
00062 for (size_t d = 0; d < output.fields.size (); ++d, offset += 4)
00063 {
00064 output.fields[d].offset = offset;
00065 output.fields[d].datatype = sensor_msgs::PointField::FLOAT32;
00066 output.fields[d].count = 1;
00067 }
00068 output.point_step = offset;
00069 output.row_step = output.point_step * output.width;
00070
00071 for (size_t d = 0; d < input.channels.size (); ++d)
00072 output.fields[3 + d].name = input.channels[d].name;
00073 output.data.resize (input.points.size () * output.point_step);
00074 output.is_bigendian = false;
00075 output.is_dense = false;
00076
00077
00078 for (size_t cp = 0; cp < input.points.size (); ++cp)
00079 {
00080 memcpy (&output.data[cp * output.point_step + output.fields[0].offset], &input.points[cp].x, sizeof (float));
00081 memcpy (&output.data[cp * output.point_step + output.fields[1].offset], &input.points[cp].y, sizeof (float));
00082 memcpy (&output.data[cp * output.point_step + output.fields[2].offset], &input.points[cp].z, sizeof (float));
00083 for (size_t d = 0; d < input.channels.size (); ++d)
00084 {
00085 if (input.channels[d].values.size() == input.points.size())
00086 {
00087 memcpy (&output.data[cp * output.point_step + output.fields[3 + d].offset], &input.channels[d].values[cp], sizeof (float));
00088 }
00089 }
00090 }
00091 return (true);
00092 }
00093
00094 bool
00095 sensor_msgs::convertPointCloud2ToPointCloud (const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud &output)
00096 {
00097
00098 for (size_t d = 0; d < input.fields.size (); ++d)
00099 {
00100 if (input.fields[d].datatype != sensor_msgs::PointField::FLOAT32)
00101 {
00102 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);
00103 }
00104 }
00105
00106 output.header = input.header;
00107 output.points.resize (input.width * input.height);
00108 output.channels.resize (input.fields.size () - 3);
00109
00110 int x_idx = getPointCloud2FieldIndex (input, "x");
00111 int y_idx = getPointCloud2FieldIndex (input, "y");
00112 int z_idx = getPointCloud2FieldIndex (input, "z");
00113 if (x_idx == -1 || y_idx == -1 || z_idx == -1)
00114 {
00115 ROS_ERROR ("x/y/z coordinates not found! Cannot convert to sensor_msgs::PointCloud!");
00116 return (false);
00117 }
00118 int x_offset = input.fields[x_idx].offset;
00119 int y_offset = input.fields[y_idx].offset;
00120 int z_offset = input.fields[z_idx].offset;
00121
00122
00123 int cur_c = 0;
00124 for (size_t d = 0; d < input.fields.size (); ++d)
00125 {
00126 if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset)
00127 continue;
00128 output.channels[cur_c].name = input.fields[d].name;
00129 output.channels[cur_c].values.resize (output.points.size ());
00130 cur_c++;
00131 }
00132
00133
00134 for (size_t cp = 0; cp < output.points.size (); ++cp)
00135 {
00136
00137 memcpy (&output.points[cp].x, &input.data[cp * input.point_step + x_offset], sizeof (float));
00138 memcpy (&output.points[cp].y, &input.data[cp * input.point_step + y_offset], sizeof (float));
00139 memcpy (&output.points[cp].z, &input.data[cp * input.point_step + z_offset], sizeof (float));
00140
00141 int cur_c = 0;
00142 for (size_t d = 0; d < input.fields.size (); ++d)
00143 {
00144 if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset)
00145 continue;
00146 memcpy (&output.channels[cur_c++].values[cp], &input.data[cp * input.point_step + input.fields[d].offset], sizeof (float));
00147 }
00148 }
00149 return (true);
00150 }