Go to the documentation of this file.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 #ifndef SENSOR_MSGS_POINT_CLOUD_CONVERSION_H
00039 #define SENSOR_MSGS_POINT_CLOUD_CONVERSION_H
00040
00041 #include <sensor_msgs/PointCloud.h>
00042 #include <sensor_msgs/PointCloud2.h>
00043 #include <sensor_msgs/point_field_conversion.h>
00044
00049 namespace sensor_msgs
00050 {
00052
00056 static inline int getPointCloud2FieldIndex (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name)
00057 {
00058
00059 for (size_t d = 0; d < cloud.fields.size (); ++d)
00060 if (cloud.fields[d].name == field_name)
00061 return (d);
00062 return (-1);
00063 }
00064
00066
00070 static inline bool convertPointCloudToPointCloud2 (const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output)
00071 {
00072 output.header = input.header;
00073 output.width = input.points.size ();
00074 output.height = 1;
00075 output.fields.resize (3 + input.channels.size ());
00076
00077 output.fields[0].name = "x"; output.fields[1].name = "y"; output.fields[2].name = "z";
00078 int offset = 0;
00079
00080 for (size_t d = 0; d < output.fields.size (); ++d, offset += 4)
00081 {
00082 output.fields[d].offset = offset;
00083 output.fields[d].datatype = sensor_msgs::PointField::FLOAT32;
00084 output.fields[d].count = 1;
00085 }
00086 output.point_step = offset;
00087 output.row_step = output.point_step * output.width;
00088
00089 for (size_t d = 0; d < input.channels.size (); ++d)
00090 output.fields[3 + d].name = input.channels[d].name;
00091 output.data.resize (input.points.size () * output.point_step);
00092 output.is_bigendian = false;
00093 output.is_dense = false;
00094
00095
00096 for (size_t cp = 0; cp < input.points.size (); ++cp)
00097 {
00098 memcpy (&output.data[cp * output.point_step + output.fields[0].offset], &input.points[cp].x, sizeof (float));
00099 memcpy (&output.data[cp * output.point_step + output.fields[1].offset], &input.points[cp].y, sizeof (float));
00100 memcpy (&output.data[cp * output.point_step + output.fields[2].offset], &input.points[cp].z, sizeof (float));
00101 for (size_t d = 0; d < input.channels.size (); ++d)
00102 {
00103 if (input.channels[d].values.size() == input.points.size())
00104 {
00105 memcpy (&output.data[cp * output.point_step + output.fields[3 + d].offset], &input.channels[d].values[cp], sizeof (float));
00106 }
00107 }
00108 }
00109 return (true);
00110 }
00111
00113
00117 static inline bool convertPointCloud2ToPointCloud (const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud &output)
00118 {
00119
00120 output.header = input.header;
00121 output.points.resize (input.width * input.height);
00122 output.channels.resize (input.fields.size () - 3);
00123
00124 int x_idx = getPointCloud2FieldIndex (input, "x");
00125 int y_idx = getPointCloud2FieldIndex (input, "y");
00126 int z_idx = getPointCloud2FieldIndex (input, "z");
00127 if (x_idx == -1 || y_idx == -1 || z_idx == -1)
00128 {
00129 std::cerr << "x/y/z coordinates not found! Cannot convert to sensor_msgs::PointCloud!" << std::endl;
00130 return (false);
00131 }
00132 int x_offset = input.fields[x_idx].offset;
00133 int y_offset = input.fields[y_idx].offset;
00134 int z_offset = input.fields[z_idx].offset;
00135 uint8_t x_datatype = input.fields[x_idx].datatype;
00136 uint8_t y_datatype = input.fields[y_idx].datatype;
00137 uint8_t z_datatype = input.fields[z_idx].datatype;
00138
00139
00140 int cur_c = 0;
00141 for (size_t d = 0; d < input.fields.size (); ++d)
00142 {
00143 if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset)
00144 continue;
00145 output.channels[cur_c].name = input.fields[d].name;
00146 output.channels[cur_c].values.resize (output.points.size ());
00147 cur_c++;
00148 }
00149
00150
00151 for (size_t cp = 0; cp < output.points.size (); ++cp)
00152 {
00153
00154 output.points[cp].x = sensor_msgs::readPointCloud2BufferValue<float>(&input.data[cp * input.point_step + x_offset], x_datatype);
00155 output.points[cp].y = sensor_msgs::readPointCloud2BufferValue<float>(&input.data[cp * input.point_step + y_offset], y_datatype);
00156 output.points[cp].z = sensor_msgs::readPointCloud2BufferValue<float>(&input.data[cp * input.point_step + z_offset], z_datatype);
00157
00158 int cur_c = 0;
00159 for (size_t d = 0; d < input.fields.size (); ++d)
00160 {
00161 if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset)
00162 continue;
00163 output.channels[cur_c++].values[cp] = sensor_msgs::readPointCloud2BufferValue<float>(&input.data[cp * input.point_step + input.fields[d].offset], input.fields[d].datatype);
00164 }
00165 }
00166 return (true);
00167 }
00168 }
00169 #endif// SENSOR_MSGS_POINT_CLOUD_CONVERSION_H