diff --git a/mesh_msgs_conversions/src/conversions.cpp b/mesh_msgs_conversions/src/conversions.cpp index 16a9e65..4830dd3 100644 --- a/mesh_msgs_conversions/src/conversions.cpp +++ b/mesh_msgs_conversions/src/conversions.cpp @@ -239,11 +239,10 @@ bool fromMeshGeometryToMeshBuffer( const mesh_msgs::msg::MeshGeometry& mesh_geometry, lvr2::MeshBuffer& buffer) { - const size_t numVertices = mesh_geometry.vertices.size(); lvr2::floatArr vertices( new float[ numVertices * 3 ] ); const auto& mg_vertices = mesh_geometry.vertices; - for(size_t i; i(mg_vertices[i].x); vertices[ i * 3 + 1 ] = static_cast(mg_vertices[i].y); @@ -254,7 +253,7 @@ bool fromMeshGeometryToMeshBuffer( const size_t numFaces = mesh_geometry.faces.size(); lvr2::indexArray faces( new unsigned int[ numVertices * 3 ] ); const auto& mg_faces = mesh_geometry.faces; - for(size_t i; i(mg_normals[i].x); normals[ i * 3 + 1 ] = static_cast(mg_normals[i].y); @@ -276,7 +275,7 @@ bool fromMeshGeometryToMeshBuffer( return true; } -bool readMeshBuffer(lvr2::MeshBufferPtr& buffer_ptr, string path) +bool readMeshBuffer(lvr2::MeshBufferPtr& buffer_ptr, std::string path) { lvr2::ModelFactory io_factory; lvr2::ModelPtr model = io_factory.readModel(path); @@ -292,7 +291,7 @@ bool readMeshBuffer(lvr2::MeshBufferPtr& buffer_ptr, string path) } } -bool writeMeshBuffer(lvr2::MeshBufferPtr& buffer, string path) +bool writeMeshBuffer(lvr2::MeshBufferPtr& buffer, std::string path) { lvr2::ModelPtr model(new lvr2::Model(buffer)); lvr2::ModelFactory::saveModel(model, path);