conversions.cpp
Go to the documentation of this file.
1 /*
2  * UOS-ROS packages - Robot Operating System code by the University of Osnabrück
3  * Copyright (C) 2013 University of Osnabrück
4  *
5  * This program is free software; you can redistribute it and/or
6  * modify it under the terms of the GNU General Public License
7  * as published by the Free Software Foundation; either version 2
8  * of the License, or (at your option) any later version.
9  *
10  * This program is distributed in the hope that it will be useful,
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program; if not, write to the Free Software
17  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301, USA.
18  *
19  * created on: 30.04.2014
20  *
21  * conversions.cpp
22  *
23  * Author: Sebastian Pütz <spuetz@uos.de>,
24  * Henning Deeken <hdeeken@uos.de>,
25  * Marcel Mrozinski <mmrozins@uos.de>,
26  * Tristan Igelbrink <tigelbri@uos.de>
27  *
28  */
29 
31 #include <omp.h>
32 #include <cmath>
33 
34 namespace mesh_msgs_conversions
35 {
36 
38  const lvr2::MeshBufferPtr& buffer,
39  mesh_msgs::MeshGeometry& mesh_geometry
40 ){
41  size_t n_vertices = buffer->numVertices();
42  size_t n_faces = buffer->numFaces();
43 
44  ROS_DEBUG_STREAM("Copy vertices from MeshBuffer to MeshGeometry.");
45 
46  // Copy vertices
47  mesh_geometry.vertices.resize(n_vertices);
48  auto buffer_vertices = buffer->getVertices();
49  for (unsigned int i = 0; i < n_vertices; i++)
50  {
51  mesh_geometry.vertices[i].x = buffer_vertices[i * 3];
52  mesh_geometry.vertices[i].y = buffer_vertices[i * 3 + 1];
53  mesh_geometry.vertices[i].z = buffer_vertices[i * 3 + 2];
54  }
55 
56  ROS_DEBUG_STREAM("Copy faces from MeshBuffer to MeshGeometry.");
57 
58  // Copy faces
59  auto buffer_faces = buffer->getFaceIndices();
60  mesh_geometry.faces.resize(n_faces);
61  for (unsigned int i = 0; i < n_faces; i++)
62  {
63  mesh_geometry.faces[i].vertex_indices[0] = buffer_faces[i * 3];
64  mesh_geometry.faces[i].vertex_indices[1] = buffer_faces[i * 3 + 1];
65  mesh_geometry.faces[i].vertex_indices[2] = buffer_faces[i * 3 + 2];
66  }
67 
68  // Copy vertex normals
69  auto buffer_vertexnormals = buffer->getVertexNormals();
70  if(buffer->hasVertexNormals())
71  {
72  ROS_DEBUG_STREAM("Copy normals from MeshBuffer to MeshGeometry.");
73 
74  mesh_geometry.vertex_normals.resize(n_vertices);
75  for (unsigned int i = 0; i < n_vertices; i++) {
76  mesh_geometry.vertex_normals[i].x = buffer_vertexnormals[i * 3];
77  mesh_geometry.vertex_normals[i].y = buffer_vertexnormals[i * 3 + 1];
78  mesh_geometry.vertex_normals[i].z = buffer_vertexnormals[i * 3 + 2];
79  }
80  }else{
81  ROS_DEBUG_STREAM("No vertex normals given!");
82  }
83 
84  ROS_DEBUG_STREAM("Successfully copied the MeshBuffer "
85  "geometry to the MeshGeometry message.");
86  return true;
87 }
88 
90  const lvr2::MeshBufferPtr& buffer,
91  mesh_msgs::MeshGeometry& mesh_geometry,
92  mesh_msgs::MeshMaterials& mesh_materials,
93  mesh_msgs::MeshVertexColors& mesh_vertex_colors,
94  boost::optional<std::vector<mesh_msgs::MeshTexture>&> texture_cache,
95  std::string mesh_uuid
96 )
97 {
98  size_t n_vertices = buffer->numVertices();
99  size_t n_faces = buffer->numFaces();
100 
101  // copy vertices, faces and normals
102  fromMeshBufferToMeshGeometryMessage(buffer, mesh_geometry);
103 
104  //size_t n_clusters = buffer->; TODO Clusters?
105  // Copy clusters
106  /*auto buffer_clusters = buffer->get;
107  mesh_materials.clusters.resize(n_clusters);
108  for (unsigned int i = 0; i < n_clusters; i++)
109  {
110  int n = buffer_clusters[i].size();
111  mesh_materials.clusters[i].face_indices.resize(n);
112  for (unsigned int j = 0; j < n; j++)
113  {
114  mesh_materials.clusters[i].face_indices[j] = buffer_clusters[i][j];
115  }
116  }
117  buffer_clusters.clear();
118  */
119 
120  size_t n_materials = buffer->getMaterials().size();
121  size_t n_textures = buffer->getTextures().size();
122 
123  // Copy materials
124  auto buffer_materials = buffer->getMaterials();
125  mesh_materials.materials.resize(n_materials);
126  for (unsigned int i = 0; i < n_materials; i++)
127  {
128  const lvr2::Material& m = buffer_materials[i];
129  if (m.m_color)
130  {
131  mesh_materials.materials[i].color.r = m.m_color.get()[0]/255.0;
132  mesh_materials.materials[i].color.g = m.m_color.get()[1]/255.0;
133  mesh_materials.materials[i].color.b = m.m_color.get()[2]/255.0;
134  mesh_materials.materials[i].color.a = 1.0;
135  }
136  else
137  {
138  mesh_materials.materials[i].color.r = 1.0;
139  mesh_materials.materials[i].color.g = 1.0;
140  mesh_materials.materials[i].color.b = 1.0;
141  mesh_materials.materials[i].color.a = 1.0;
142  }
143  if (m.m_texture)
144  {
145  mesh_materials.materials[i].has_texture = true;
146  mesh_materials.materials[i].texture_index = (int)m.m_texture.get().idx();
147  }
148  else
149  {
150  mesh_materials.materials[i].has_texture = false;
151  mesh_materials.materials[i].texture_index = 0;
152  }
153  }
154  buffer_materials.clear();
155 
156  // Copy cluster material indices TODO Cluster Materials?
157  /*
158  auto buffer_cluster_materials = buffer->getClusterMaterialIndices();
159  mesh_materials.materials.resize(n_clusters);
160  for (unsigned int i = 0; i < n_clusters; i++)
161  {
162  mesh_materials.cluster_materials[i] = buffer_cluster_materials[i];
163  }
164  buffer_cluster_materials.clear();
165  */
166 
167  // Copy vertex tex coords
168  auto buffer_texcoords = buffer->getTextureCoordinates();
169  {
170  mesh_materials.vertex_tex_coords.resize(n_vertices);
171 
172  for (unsigned int i = 0; i < n_vertices; i++)
173  {
174  mesh_materials.vertex_tex_coords[i].u = buffer_texcoords[i * 3];
175  mesh_materials.vertex_tex_coords[i].v = buffer_texcoords[i * 3 + 1];
176  }
177  }
178 
179  // Copy vertex colors
180  if (buffer->hasVertexColors())
181  {
182  size_t color_channels = 3;
183  auto buffer_vertex_colors = buffer->getVertexColors(color_channels);
184  mesh_vertex_colors.vertex_colors.resize(n_vertices);
185  for (size_t i = 0; i < n_vertices; i++)
186  {
187  mesh_vertex_colors.vertex_colors[i].r = buffer_vertex_colors[i * 3 + 0]/255.0;
188  mesh_vertex_colors.vertex_colors[i].g = buffer_vertex_colors[i * 3 + 1]/255.0;
189  mesh_vertex_colors.vertex_colors[i].b = buffer_vertex_colors[i * 3 + 2]/255.0;
190  mesh_vertex_colors.vertex_colors[i].a = 1.0;
191  }
192  }
193 
194  // If texture cache is available, cache textures in given vector
195  if (texture_cache)
196  {
197  auto buffer_textures = buffer->getTextures();
198  texture_cache.get().resize(n_textures);
199  for (unsigned int i = 0; i < n_textures; i++)
200  {
201  sensor_msgs::Image image;
203  image,
204  "rgb8",
205  buffer_textures[i].m_height,
206  buffer_textures[i].m_width,
207  buffer_textures[i].m_width * 3, // step size
208  buffer_textures[i].m_data
209  );
210  mesh_msgs::MeshTexture texture;
211  texture.uuid = mesh_uuid;
212  texture.texture_index = i;
213  texture.image = image;
214  texture_cache.get().at(i) = texture;
215  }
216  buffer_textures.clear();
217  }
218 
219  return true;
220 }
221 
223  const mesh_msgs::MeshGeometryConstPtr& mesh_geometry_ptr,
224  lvr2::MeshBuffer& buffer)
225 {
226  return fromMeshGeometryToMeshBuffer(*mesh_geometry_ptr, buffer);
227 }
228 
230  const mesh_msgs::MeshGeometryConstPtr& mesh_geometry_ptr,
231  lvr2::MeshBufferPtr& buffer_ptr)
232 {
233  if(!buffer_ptr) buffer_ptr = lvr2::MeshBufferPtr(new lvr2::MeshBuffer);
234  return fromMeshGeometryToMeshBuffer(*mesh_geometry_ptr, *buffer_ptr);
235 }
236 
238  const mesh_msgs::MeshGeometryPtr& mesh_geometry_ptr,
239  lvr2::MeshBufferPtr& buffer_ptr)
240 {
241  if(!buffer_ptr) buffer_ptr = lvr2::MeshBufferPtr(new lvr2::MeshBuffer);
242  return fromMeshGeometryToMeshBuffer(*mesh_geometry_ptr, *buffer_ptr);
243 }
244 
246  const mesh_msgs::MeshGeometryPtr& mesh_geometry_ptr,
247  lvr2::MeshBuffer& buffer)
248 {
249  return fromMeshGeometryToMeshBuffer(*mesh_geometry_ptr, buffer);
250 }
251 
253  const mesh_msgs::MeshGeometry& mesh_geometry,
254  lvr2::MeshBufferPtr& buffer_ptr)
255 {
256  if(!buffer_ptr) buffer_ptr = lvr2::MeshBufferPtr(new lvr2::MeshBuffer);
257  return fromMeshGeometryToMeshBuffer(mesh_geometry, *buffer_ptr);
258 }
259 
261  const mesh_msgs::MeshGeometry& mesh_geometry,
262  lvr2::MeshBuffer& buffer)
263 {
264 
265  const size_t numVertices = mesh_geometry.vertices.size();
266  lvr2::floatArr vertices( new float[ numVertices * 3 ] );
267  const auto& mg_vertices = mesh_geometry.vertices;
268  for(size_t i; i<numVertices; i++)
269  {
270  vertices[ i * 3 + 0 ] = static_cast<float>(mg_vertices[i].x);
271  vertices[ i * 3 + 1 ] = static_cast<float>(mg_vertices[i].y);
272  vertices[ i * 3 + 2 ] = static_cast<float>(mg_vertices[i].z);
273  }
274  buffer.setVertices(vertices, numVertices);
275 
276  const size_t numFaces = mesh_geometry.faces.size();
277  lvr2::indexArray faces( new unsigned int[ numVertices * 3 ] );
278  const auto& mg_faces = mesh_geometry.faces;
279  for(size_t i; i<numFaces; i++)
280  {
281  faces[ i * 3 + 0 ] = mg_faces[i].vertex_indices[0];
282  faces[ i * 3 + 1 ] = mg_faces[i].vertex_indices[1];
283  faces[ i * 3 + 2 ] = mg_faces[i].vertex_indices[2];
284  }
285  buffer.setFaceIndices(faces, numFaces);
286 
287  const size_t numNormals = mesh_geometry.vertex_normals.size();
288  lvr2::floatArr normals( new float[ numNormals * 3 ] );
289  const auto& mg_normals = mesh_geometry.vertex_normals;
290  for(size_t i; i<numNormals; i++)
291  {
292  normals[ i * 3 + 0 ] = static_cast<float>(mg_normals[i].x);
293  normals[ i * 3 + 1 ] = static_cast<float>(mg_normals[i].y);
294  normals[ i * 3 + 2 ] = static_cast<float>(mg_normals[i].z);
295  }
296  buffer.setVertexNormals(normals);
297 
298  return true;
299 }
300 
301 bool readMeshBuffer(lvr2::MeshBufferPtr& buffer_ptr, string path)
302 {
303  lvr2::ModelFactory io_factory;
304  lvr2::ModelPtr model = io_factory.readModel(path);
305 
306  if (!model)
307  {
308  return false;
309  }
310  else
311  {
312  buffer_ptr = model->m_mesh;
313  return true;
314  }
315 }
316 
317 bool writeMeshBuffer(lvr2::MeshBufferPtr& buffer, string path)
318 {
319  lvr2::ModelPtr model(new lvr2::Model(buffer));
320  lvr2::ModelFactory::saveModel(model, path);
321  return true;
322 }
323 
324 /*
325 void removeDuplicates(lvr2::MeshBuffer& buffer)
326 {
327  lvr2::floatArr old_vertexBuffer;
328  lvr2::uintArr old_indexBuffer;
329  std::vector<float> new_vertexBuffer;
330  std::vector<unsigned int> new_indexBuffer;
331 
332  size_t old_numVertices, old_numIndices;
333  size_t new_numVertices, new_numIndices;
334 
335  old_vertexBuffer = buffer.getVertexArray(old_numVertices);
336  old_indexBuffer = buffer.getFaceArray(old_numIndices);
337 
338  std::map<lvr::Vertex<float>, unsigned int> vertexMap;
339  size_t pos;
340  int index;
341 
342  for (int i = 0; i < old_numIndices; i++)
343  {
344  for (int j = 0; j < 3; j++)
345  {
346  index = old_indexBuffer[3 * i + j];
347 
348  lvr::Vertex<float> vertex =
349  lvr::Vertex<float>(old_vertexBuffer[3 * index],
350  old_vertexBuffer[3 * index + 1],
351  old_vertexBuffer[3 * index + 2]);
352 
353  if (vertexMap.find(vertex) != vertexMap.end())
354  {
355  pos = vertexMap[vertex];
356  }
357  else
358  {
359  pos = new_vertexBuffer.size() / 3;
360  new_vertexBuffer.push_back(vertex[0]);
361  new_vertexBuffer.push_back(vertex[1]);
362  new_vertexBuffer.push_back(vertex[2]);
363 
364  vertexMap.insert(pair<lvr::Vertex<float>, unsigned int>(vertex, pos));
365  }
366 
367  new_indexBuffer.push_back(pos);
368  }
369  }
370  buffer.setVertexArray(new_vertexBuffer);
371  buffer.setFaceArray(new_indexBuffer);
372 }
373 */
374 
375 static inline bool hasCloudChannel(const sensor_msgs::PointCloud2& cloud, const std::string& field_name)
376 {
377  // Get the index we need
378  for (size_t d = 0; d < cloud.fields.size(); ++d)
379  if (cloud.fields[d].name == field_name)
380  return true;
381  return false;
382 }
383 
384 bool fromPointCloud2ToPointBuffer(const sensor_msgs::PointCloud2& cloud, lvr2::PointBuffer& buffer)
385 {
386  size_t size = cloud.height * cloud.width;
387 
388  typedef sensor_msgs::PointCloud2ConstIterator<float> CloudIterFloat;
389  typedef sensor_msgs::PointCloud2ConstIterator<uint8_t> CloudIterUInt8;
390 
391  std::list<int> filter_nan;
392 
393  // copy point data
394  CloudIterFloat iter_x_filter(cloud, "x");
395  CloudIterFloat iter_y_filter(cloud, "y");
396  CloudIterFloat iter_z_filter(cloud, "z");
397 
398  // size without NaN values
399  size = 0;
400  for (int i = 0; iter_x_filter != iter_x_filter.end();
401  ++iter_x_filter, ++iter_y_filter, ++iter_z_filter, i++)
402  {
403  if( !std::isnan(*iter_x_filter) &&
404  !std::isnan(*iter_y_filter) &&
405  !std::isnan(*iter_z_filter))
406  {
407  size++;
408  }
409  else
410  {
411  filter_nan.push_back(i);
412  }
413  }
414 
415  filter_nan.sort();
416 
417  lvr2::floatArr pointData(new float[size * 3]);
418 
419  // copy point data
420  CloudIterFloat iter_x(cloud, "x");
421  CloudIterFloat iter_y(cloud, "y");
422  CloudIterFloat iter_z(cloud, "z");
423 
424 
425  std::list<int> tmp_filter = filter_nan;
426  int index, i;
427  for (i = 0, index = 0;
428  iter_x != iter_x.end();
429  ++iter_x, ++iter_y, ++iter_z,
430  index++)
431  {
432  // skip NaN point values
433  if (!tmp_filter.empty() && index == tmp_filter.front())
434  {
435  tmp_filter.pop_front();
436  continue;
437  }
438 
439  // copy point
440  pointData[i] = *iter_x;
441  pointData[i + 1] = *iter_y;
442  pointData[i + 2] = *iter_z;
443 
444  i += 3;
445 
446  }
447  buffer.setPointArray(pointData, size);
448 
449  // copy point normals if available
450  bool normalsAvailable =
451  hasCloudChannel(cloud, "normal_x")
452  && hasCloudChannel(cloud, "normal_y")
453  && hasCloudChannel(cloud, "normal_z");
454 
455  if (normalsAvailable)
456  {
457  CloudIterFloat iter_n_x(cloud, "normal_x");
458  CloudIterFloat iter_n_y(cloud, "normal_y");
459  CloudIterFloat iter_n_z(cloud, "normal_z");
460  lvr2::floatArr normalsData(new float[size * 3]);
461  tmp_filter = filter_nan;
462  int index, i;
463  for (i = 0, index = 0;
464  iter_n_x != iter_n_x.end();
465  ++iter_n_x, ++iter_n_y, ++iter_n_z,
466  index++)
467  {
468  // skip NaN point values
469  if (!tmp_filter.empty() && index == tmp_filter.front())
470  {
471  tmp_filter.pop_front();
472  continue;
473  }
474 
475  // copy normal
476  normalsData[i] = *iter_n_x;
477  normalsData[i + 1] = *iter_n_y;
478  normalsData[i + 2] = *iter_n_z;
479 
480  i += 3;
481  }
482  buffer.setNormalArray(normalsData, size);
483  }
484 
485  // copy color data if available
486  if (hasCloudChannel(cloud, "rgb"))
487  {
488  CloudIterUInt8 iter_rgb(cloud, "rgb");
489  lvr2::ucharArr colorData(new uint8_t[size * 3]);
490  tmp_filter = filter_nan;
491  int index, i;
492  for (i = 0, index = 0; iter_rgb != iter_rgb.end();
493  ++iter_rgb, index++)
494  {
495  // skip NaN point values
496  if (!tmp_filter.empty() && index == tmp_filter.front())
497  {
498  tmp_filter.pop_front();
499  continue;
500  }
501 
502  // copy color rgb
503  colorData[i] = iter_rgb[0];
504  colorData[i + 1] = iter_rgb[1];
505  colorData[i + 2] = iter_rgb[2];
506 
507  i += 3;
508  }
509  buffer.setColorArray(colorData, size);
510  }
511 
512  // copy intensity if available
513  if (hasCloudChannel(cloud, "intensities"))
514  {
515  CloudIterFloat iter_int(cloud, "intensities");
516  lvr2::floatArr intensityData(new float[size]);
517  tmp_filter = filter_nan;
518  int index, i;
519  for (i = 0, index = 0; iter_int != iter_int.end();
520  ++iter_int, index++)
521  {
522  // skip NaN point values
523  if (!tmp_filter.empty() && index == tmp_filter.front())
524  {
525  tmp_filter.pop_front();
526  continue;
527  }
528 
529  // copy intensity
530  intensityData[i] = *iter_int;
531  i++;
532  }
533  buffer.addFloatChannel(intensityData, "intensity", size, 1);
534  }
535  return true;
536 }
537 
539  const mesh_msgs::MeshGeometry& mesh_geometry,
540  const lvr2::MeshBufferPtr& buffer
541 )
542 {
543  // copy vertices
544  lvr2::floatArr vertices(new float[mesh_geometry.vertices.size() * 3]);
545  int i = 0;
546  for (auto vertex : mesh_geometry.vertices)
547  {
548  vertices[i] = static_cast<float>(vertex.x);
549  vertices[i+1] = static_cast<float>(vertex.y);
550  vertices[i+2] = static_cast<float>(vertex.z);
551  i += 3;
552  }
553  buffer->setVertices(vertices, mesh_geometry.vertices.size());
554 
555  // copy faces
556  lvr2::indexArray faces(new unsigned int[mesh_geometry.faces.size() * 3]);
557  i = 0;
558  for (auto face : mesh_geometry.faces)
559  {
560  faces[i] = face.vertex_indices[0];
561  faces[i+1] = face.vertex_indices[1];
562  faces[i+2] = face.vertex_indices[2];
563  i += 3;
564  }
565  buffer->setFaceIndices(faces, mesh_geometry.faces.size() * 3);
566 
567  if(mesh_geometry.vertex_normals.size() == mesh_geometry.vertices.size())
568  {
569  // copy normals
570  lvr2::floatArr normals(new float[mesh_geometry.vertex_normals.size() * 3]);
571  i = 0;
572  for (auto normal : mesh_geometry.vertex_normals)
573  {
574  normals[i] = static_cast<float>(normal.x);
575  normals[i+1] = static_cast<float>(normal.y);
576  normals[i+2] = static_cast<float>(normal.z);
577  i += 3;
578  }
579  buffer->setVertexNormals(normals);
580  }
581  else
582  {
583  ROS_ERROR_STREAM("Number of normals (" << mesh_geometry.vertex_normals.size()
584  << ") must be equal to number of vertices (" << mesh_geometry.vertices.size()
585  << "), ignore normals!");
586  }
587  return true;
588 }
589 
590 void PointBufferToPointCloud2(const lvr2::PointBufferPtr& buffer, std::string frame, sensor_msgs::PointCloud2Ptr& cloud)
591 {
592  // the offset will be updated by addPointField
593  cloud->header.stamp = ros::Time::now();
594  cloud->header.frame_id = frame;
595 
596  ros::Rate r(60);
597 
598  int type;
599  std::map<std::string, lvr2::Channel<float> > floatChannels;
600  type = buffer->getAllChannelsOfType<float>(floatChannels);
601  std::map<std::string, lvr2::Channel<unsigned char> > uCharChannels;
602  int ucharType = buffer->getAllChannelsOfType<unsigned char>(uCharChannels);
603 
604  size_t size = 0;
605  // xyz needs to be at the start.
606  int offset = 4 * sizeof(float);
607  // LVR mb needs a float64buffer especially for time information.
608  for(auto channelPair: floatChannels)
609  {
610  // http://pointclouds.org/documentation/tutorials/adding_custom_ptype.php
611  // For the padding reasons.
612  if(channelPair.first == "points")
613  {
614  size = channelPair.second.numElements();
615  int p_offset = 0;
616  p_offset = addPointField(*cloud, "x", 1, sensor_msgs::PointField::FLOAT32, p_offset);
617  p_offset = addPointField(*cloud, "y", 1, sensor_msgs::PointField::FLOAT32, p_offset);
618  p_offset = addPointField(*cloud, "z", 1, sensor_msgs::PointField::FLOAT32, p_offset);
619  p_offset += sizeof(float);
620  cloud->point_step = offset;
621  for(auto channelPair: uCharChannels)
622  {
623  if(channelPair.first == "colors")
624  {
625 
626  offset = addPointField(*cloud, "rgb", channelPair.second.width(), sensor_msgs::PointField::FLOAT32, offset);
627  cloud->point_step = offset;
628  }
629  }
630  }
631  else
632  {
633  // type in lvr2 starts at 0, in ros at 1
634  offset = addPointField(*cloud, channelPair.first, channelPair.second.width(), type + 1, offset);
635  //int padding = (sizeof(float) * 4) - ((channelPair.second.width() * sizeof(float)) % (4 * sizeof(float)));
636  //offset += padding;
637  cloud->point_step = offset;
638  }
639  }
640 
641 
642 
643 
644 // // Is this useful?!
645 // int padding = (sizeof(float) * 4) - ((channelPair.second.width() * sizeof(float)) % (4 * sizeof(float)));
646 // offset += padding;
647 // cloud->point_step = offset;
648 // }
649 
650  std::map<std::string, lvr2::Channel<int> > intChannels;
651  type = buffer->getAllChannelsOfType<int>(intChannels);
652  for(auto channelPair: intChannels)
653  {
654  // http://pointclouds.org/documentation/tutorials/adding_custom_ptype.php
655  // For the padding reasons.
656  // type in lvr2 starts at 0, in ros at 1
657  offset = addPointField(*cloud, channelPair.first, channelPair.second.width(), type + 1, offset);
658 // int padding = (sizeof(float) * 4) - ((channelPair.second.width() * sizeof(float)) % (4 * sizeof(float)));
659 // offset += padding;
660  cloud->point_step = offset;
661  }
662 
663  // reserve size
665  cloud->data.resize(size * cloud->point_step);
666 
667  cloud->height = 1;
668  cloud->width = size;
669 
670 
671  ROS_INFO("Starting conversion.");
672  for(auto field: cloud->fields)
673  {
674  // Points is a special case...
675  if(field.name == "x" || field.name == "y" || field.name == "z")
676  {
677  auto channel = floatChannels.at("points");
678  //auto iter_x = floatIters.at("x");
679  //auto iter_y = floatIters.at("y");
680  //auto iter_z = floatIters.at("z");
681  #pragma omp parallel for
682  for(size_t i = 0; i < size; ++i)
683  {
684  unsigned char* ptr = &(cloud->data[cloud->point_step * i]);
685  *(reinterpret_cast<float*>(ptr)) = channel[i][0];
686  *((reinterpret_cast<float*>(ptr)) + 1) = channel[i][1];
687  *((reinterpret_cast<float*>(ptr)) + 2) = channel[i][2];
688  //*iter_x = channel[i][0];
689  //*iter_y = channel[i][1];
690  //*iter_z = channel[i][2];
691  }
692 
693  }
694  else
695  {
696  if(field.datatype == sensor_msgs::PointField::FLOAT32)
697  {
698  std::string name = field.name;
699  if(name == "rgb")
700  {
701  name = "colors";
702  auto channel = uCharChannels.at(name);
703  //auto iter = uCharIters.at(field.name);
704 #pragma omp parallel for
705  for(size_t i = 0; i < size; ++i)
706  {
707  unsigned char* ptr = &(cloud->data[cloud->point_step * i]) + field.offset;
708  *(ptr + 2) = channel[i][0];
709  *(ptr + 1) = channel[i][1];
710  *(ptr + 0) = channel[i][2];
711  //for(size_t j = 0; j < field.count; ++j)
712  //{
713  // //iter[j] = channel[i][j];
714  // *(ptr + j) = channel[i][j];
715  //}
716  }
717 
718  continue;
719  }
720  // ELSE
721  auto channel = floatChannels.at(field.name);
722  //auto iter = floatIters.at(field.name);
723  #pragma omp parallel for
724  for(size_t i = 0; i < size; ++i)
725  {
726  unsigned char* ptr = &(cloud->data[cloud->point_step * i]) + field.offset;
727  for(size_t j = 0; j < field.count; ++j)
728  {
729  *((reinterpret_cast<float*>(ptr)) + j) = channel[i][j];
730  //iter[j] = channel[i][j];
731  }
732  }
733  }
734  else if (field.datatype == sensor_msgs::PointField::UINT8)
735  {
736  }
737  }
738  }
739  ROS_INFO("DONE");
740 }
741 
742 void PointCloud2ToPointBuffer(const sensor_msgs::PointCloud2Ptr& cloud, lvr2::PointBufferPtr& buffer)
743 {
744  buffer = lvr2::PointBufferPtr(new lvr2::PointBuffer());
745 
746  for(auto field : cloud->fields)
747  {
748  if(field.datatype == sensor_msgs::PointField::FLOAT32)
749  {
750  if(field.name == "x" || field.name == "y" || field.name == "z")
751  {
752  if(!buffer->hasFloatChannel("points"))
753  {
754  buffer->addEmptyChannel<float>("points", cloud->width * cloud->height, 3);
755  }
756  }
757  else
758  {
759  buffer->addEmptyChannel<float>(field.name, cloud->width * cloud->height, field.count);
760  }
761 
762  }
763  }
764 
765  for(auto field: cloud->fields)
766  {
767  // Points is a special case...
768  if(field.name == "x" || field.name == "y" || field.name == "z")
769  {
770  auto channel = buffer->getChannel<float>("points");
771  if(channel)
772  {
773  std::cout << "already init" << std::endl;
774  continue;
775  }
776 
777  lvr2::floatArr points(new float[cloud->width * cloud->height * 3]);
778  buffer->setPointArray(points, cloud->width * cloud->height);
779  channel = buffer->getChannel<float>("points");
780 
781  #pragma omp parallel for
782  for(size_t i = 0; i < (cloud->width * cloud->height); ++i)
783  {
784  unsigned char* ptr = &(cloud->data[cloud->point_step * i]);
785  (*channel)[i][0] = *(reinterpret_cast<float*>(ptr));
786  (*channel)[i][1] = *((reinterpret_cast<float*>(ptr)) + 1);
787  (*channel)[i][2] = *((reinterpret_cast<float*>(ptr)) + 2);
788  }
789 
790  }
791  else
792  {
793  if(field.datatype == sensor_msgs::PointField::FLOAT32)
794  {
795  auto channel = buffer->getChannel<float>(field.name);
796 
797  if(!channel)
798  {
799  ROS_INFO("Channel %s missing", field.name.c_str());
800  continue;
801  }
802 
803  #pragma omp parallel for
804  for(size_t i = 0; i < (cloud->width * cloud->height); ++i)
805  {
806  unsigned char* ptr = &(cloud->data[cloud->point_step * i]) + field.offset;
807  for(size_t j = 0; j < field.count; ++j)
808  {
809  (*channel)[i][j] = *((reinterpret_cast<float*>(ptr)) + j);
810  }
811  }
812  }
813  else if (field.datatype == sensor_msgs::PointField::UINT8)
814  {
815  auto channel = buffer->getChannel<unsigned char>(field.name);
816 
817  if(!channel)
818  {
819  ROS_INFO("Channel %s missing", field.name.c_str());
820  continue;
821  }
822 
823  #pragma omp parallel for
824  for(size_t i = 0; i < (cloud->width * cloud->height); ++i)
825  {
826  unsigned char* ptr = &(cloud->data[cloud->point_step * i]) + field.offset;
827  for(size_t j = 0; j < field.count; ++j)
828  {
829  (*channel)[i][j] = *(ptr + j);
830  }
831  }
832  }
833  }
834  }
835 }
836 
837 } // end namespace
lvr2::ModelFactory::saveModel
static void saveModel(ModelPtr m, std::string file)
mesh_msgs_conversions::fromMeshBufferToMeshMessages
bool fromMeshBufferToMeshMessages(const lvr2::MeshBufferPtr &buffer, mesh_msgs::MeshGeometry &mesh_geometry, mesh_msgs::MeshMaterials &mesh_materials, mesh_msgs::MeshVertexColors &mesh_vertex_colors, boost::optional< std::vector< mesh_msgs::MeshTexture > & > texture_cache, std::string mesh_uuid)
Convert lvr2::MeshBuffer to various messages for services.
Definition: conversions.cpp:89
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
lvr2::PointBuffer::setColorArray
void setColorArray(ucharArr colors, size_t n, size_t width=3)
lvr2::PointBufferPtr
std::shared_ptr< PointBuffer > PointBufferPtr
lvr2::MeshBuffer::setVertexNormals
void setVertexNormals(floatArr normals)
lvr2::BaseBuffer::addFloatChannel
void addFloatChannel(floatArr array, std::string name, size_t n, size_t width)
mesh_msgs_conversions::PointCloud2ToPointBuffer
void PointCloud2ToPointBuffer(const sensor_msgs::PointCloud2Ptr &cloud, lvr2::PointBufferPtr &buffer)
converts pointcloud2 to a newly created Pointerbuffer. Every pointfield is written into its own chann...
Definition: conversions.cpp:742
lvr2::PointBuffer
sensor_msgs::fillImage
static bool fillImage(Image &image, const std::string &encoding_arg, uint32_t rows_arg, uint32_t cols_arg, uint32_t step_arg, const void *data_arg)
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
lvr2::Model
conversions.h
mesh_msgs_conversions
Definition: conversions.h:73
sensor_msgs::PointCloud2ConstIterator
lvr2::PointBuffer::setNormalArray
void setNormalArray(floatArr normals, size_t n)
lvr2::MeshBuffer
mesh_msgs_conversions::PointBufferToPointCloud2
void PointBufferToPointCloud2(const lvr2::PointBufferPtr &buffer, std::string frame, sensor_msgs::PointCloud2Ptr &cloud)
converts lvr2::Pointbuffer to pointcloud2. Every channel is added as a pointfield.
Definition: conversions.cpp:590
mesh_msgs_conversions::fromMeshGeometryToMeshBuffer
bool fromMeshGeometryToMeshBuffer(const mesh_msgs::MeshGeometryConstPtr &mesh_geometry_ptr, lvr2::MeshBufferPtr &buffer_ptr)
Definition: conversions.cpp:229
lvr2::ModelFactory
mesh_msgs_conversions::hasCloudChannel
static bool hasCloudChannel(const sensor_msgs::PointCloud2 &cloud, const std::string &field_name)
Definition: conversions.cpp:375
boost::shared_array< float >
d
d
lvr2::MeshBuffer::setFaceIndices
void setFaceIndices(indexArray indices, size_t n)
mesh_msgs_conversions::fromPointCloud2ToPointBuffer
bool fromPointCloud2ToPointBuffer(const sensor_msgs::PointCloud2 &cloud, PointBuffer &buffer)
Definition: conversions.cpp:384
lvr2::PointBuffer::setPointArray
void setPointArray(floatArr points, size_t n)
mesh_msgs_conversions::fromMeshGeometryMessageToMeshBuffer
bool fromMeshGeometryMessageToMeshBuffer(const mesh_msgs::MeshGeometry &mesh_geometry, const lvr2::MeshBufferPtr &buffer)
Convert mesh_msgs::MeshGeometry to lvr2::MeshBuffer.
Definition: conversions.cpp:538
mesh_msgs_conversions::fromMeshBufferToMeshGeometryMessage
bool fromMeshBufferToMeshGeometryMessage(const lvr2::MeshBufferPtr &buffer, mesh_msgs::MeshGeometry &mesh_geometry)
Definition: conversions.cpp:37
lvr2::Material
mesh_msgs_conversions::writeMeshBuffer
bool writeMeshBuffer(lvr2::MeshBufferPtr &mesh, string path)
Writes a LVR-MeshBufferPointer to a file.
Definition: conversions.cpp:317
sensor_msgs::PointCloud2Modifier
lvr2::ModelPtr
std::shared_ptr< Model > ModelPtr
lvr2::MeshBufferPtr
std::shared_ptr< MeshBuffer > MeshBufferPtr
lvr2::ModelFactory::readModel
static ModelPtr readModel(std::string filename)
ros::Rate
lvr2::MeshBuffer::setVertices
void setVertices(floatArr vertices, size_t n)
ROS_INFO
#define ROS_INFO(...)
lvr2::Material::m_texture
boost::optional< TextureHandle > m_texture
lvr2::Material::m_color
boost::optional< Rgb8Color > m_color
ros::Time::now
static Time now()
mesh_msgs_conversions::readMeshBuffer
bool readMeshBuffer(lvr2::MeshBufferPtr &buffer, string path)
Creates a LVR-MeshBufferPointer from a file.
Definition: conversions.cpp:301


mesh_msgs_conversions
Author(s): Sebastian Pütz , Henning Deeken
autogenerated on Sun Jan 21 2024 04:06:17