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 <pcl/io/vtk_io.h>
00039 #include <fstream>
00040 #include <iostream>
00041 #include <pcl/io/io.h>
00042
00044 int
00045 pcl::io::saveVTKFile (const std::string &file_name,
00046 const pcl::PolygonMesh &triangles, unsigned precision)
00047 {
00048 if (triangles.cloud.data.empty ())
00049 {
00050 ROS_ERROR ("[pcl::io::saveVTKFile] Input point cloud has no data!");
00051 return (-1);
00052 }
00053
00054
00055 std::ofstream fs;
00056 fs.precision (precision);
00057 fs.open (file_name.c_str ());
00058
00059 int nr_points = triangles.cloud.width * triangles.cloud.height;
00060 int point_size = triangles.cloud.data.size () / nr_points;
00061
00062
00063 fs << "# vtk DataFile Version 3.0\nvtk output\nASCII\nDATASET POLYDATA\nPOINTS " << nr_points << " float" << std::endl;
00064
00065
00066 for (int i = 0; i < nr_points; ++i)
00067 {
00068 int xyz = 0;
00069 for (size_t d = 0; d < triangles.cloud.fields.size (); ++d)
00070 {
00071 int count = triangles.cloud.fields[d].count;
00072 if (count == 0)
00073 count = 1;
00074 int c = 0;
00075 if ((triangles.cloud.fields[d].datatype == sensor_msgs::PointField::FLOAT32) && (
00076 triangles.cloud.fields[d].name == "x" ||
00077 triangles.cloud.fields[d].name == "y" ||
00078 triangles.cloud.fields[d].name == "z"))
00079 {
00080 float value;
00081 memcpy (&value, &triangles.cloud.data[i * point_size + triangles.cloud.fields[d].offset + c * sizeof (float)], sizeof (float));
00082 fs << value;
00083 if (++xyz == 3)
00084 break;
00085 }
00086 fs << " ";
00087 }
00088 if (xyz != 3)
00089 {
00090 ROS_ERROR ("[pcl::io::saveVTKFile] Input point cloud has no XYZ data!");
00091 return (-2);
00092 }
00093 fs << std::endl;
00094 }
00095
00096
00097 fs << "\nVERTICES " << nr_points << " " << 2*nr_points << std::endl;
00098 for (int i = 0; i < nr_points; ++i)
00099 fs << "1 " << i << std::endl;
00100
00101
00102
00103 fs << "\nPOLYGONS " << triangles.polygons.size () << " " << (triangles.polygons[0].vertices.size () + 1) * triangles.polygons.size () << std::endl;
00104 for (size_t i = 0; i < triangles.polygons.size (); ++i)
00105 {
00106 fs << triangles.polygons[i].vertices.size () << " ";
00107 size_t j = 0;
00108 for (j = 0; j < triangles.polygons[i].vertices.size () - 1; ++j)
00109 fs << triangles.polygons[i].vertices[j] << " ";
00110 fs << triangles.polygons[i].vertices[j] << std::endl;
00111 }
00112
00113
00114 int field_index = getFieldIndex (triangles.cloud, "rgb");
00115 if (field_index != -1)
00116 {
00117 fs << "\nPOINT_DATA " << nr_points << "\nCOLOR_SCALARS scalars 3\n";
00118 for (int i = 0; i < nr_points; ++i)
00119 {
00120 int count = triangles.cloud.fields[field_index].count;
00121 if (count == 0)
00122 count = 1;
00123 int c = 0;
00124 if (triangles.cloud.fields[field_index].datatype == sensor_msgs::PointField::FLOAT32)
00125 {
00126 float value;
00127 memcpy (&value, &triangles.cloud.data[i * point_size + triangles.cloud.fields[field_index].offset + c * sizeof (float)], sizeof (float));
00128 int color = *reinterpret_cast<const int*>(&(value));
00129 int r = (0xff0000 & color) >> 16;
00130 int g = (0x00ff00 & color) >> 8;
00131 int b = 0x0000ff & color;
00132 fs << (float)r/255.0 << " " << (float)g/255.0 << " " << (float)b/255.0;
00133 }
00134 fs << std::endl;
00135 }
00136 }
00137
00138
00139 fs.close ();
00140 return (0);
00141 }
00142