mesh_operations.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #ifndef GEOMETRIC_SHAPES_MESH_OPERATIONS_
38 #define GEOMETRIC_SHAPES_MESH_OPERATIONS_
39 
42 #include <vector>
43 
44 // forward declaration of aiScene (caller needs to include assimp if aiScene is used)
45 class aiScene;
46 
47 namespace shapes
48 {
53 Mesh* createMeshFromVertices(const EigenSTL::vector_Vector3d& vertices, const std::vector<unsigned int>& triangles);
54 
60 
62 Mesh* createMeshFromResource(const std::string& resource);
63 
65 Mesh* createMeshFromResource(const std::string& resource, const Eigen::Vector3d& scale);
66 
68 Mesh* createMeshFromBinary(const char* buffer, std::size_t size, const std::string& assimp_hint = std::string());
69 
71 Mesh* createMeshFromBinary(const char* buffer, std::size_t size, const Eigen::Vector3d& scale,
72  const std::string& assimp_hint = std::string());
73 
75 Mesh* createMeshFromAsset(const aiScene* scene, const Eigen::Vector3d& scale,
76  const std::string& assimp_hint = std::string());
77 
79 Mesh* createMeshFromAsset(const aiScene* scene, const std::string& assimp_hint = std::string());
80 
82 Mesh* createMeshFromShape(const Shape* shape);
83 
85 Mesh* createMeshFromShape(const Box& box);
86 
88 Mesh* createMeshFromShape(const Sphere& sphere);
89 
91 Mesh* createMeshFromShape(const Cylinder& cylinder);
92 
94 Mesh* createMeshFromShape(const Cone& cone);
95 
97 void writeSTLBinary(const Mesh* mesh, std::vector<char>& buffer);
98 } // namespace shapes
99 
100 #endif
shapes
Definition of various shapes. No properties such as position are included. These are simply the descr...
Definition: mesh_operations.h:47
shapes::Cylinder
Definition of a cylinder Length is along z axis. Origin is at center of mass.
Definition: shapes.h:127
shapes::Shape
A basic definition of a shape. Shapes are considered centered at origin.
Definition: shapes.h:77
shapes::Mesh
Definition of a triangle mesh By convention the "center" of the shape is at the origin....
Definition: shapes.h:281
shapes::Box
Definition of a box Aligned with the XYZ axes.
Definition: shapes.h:226
shapes::Sphere
Definition of a sphere.
Definition: shapes.h:106
shapes::createMeshFromVertices
Mesh * createMeshFromVertices(const EigenSTL::vector_Vector3d &vertices, const std::vector< unsigned int > &triangles)
Load a mesh from a set of vertices.
Definition: mesh_operations.cpp:140
EigenSTL::vector_Vector3d
std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > vector_Vector3d
eigen_stl_containers.h
shapes::createMeshFromResource
Mesh * createMeshFromResource(const std::string &resource)
Load a mesh from a resource that contains a mesh that can be loaded by assimp.
Definition: mesh_operations.cpp:234
shapes::writeSTLBinary
void writeSTLBinary(const Mesh *mesh, std::vector< char > &buffer)
Write the mesh to a buffer in STL format.
Definition: mesh_operations.cpp:672
shapes::createMeshFromBinary
Mesh * createMeshFromBinary(const char *buffer, std::size_t size, const std::string &assimp_hint=std::string())
Load a mesh from a binary stream that contains a mesh that can be loaded by assimp.
Definition: mesh_operations.cpp:240
shapes.h
shapes::Cone
Definition of a cone Tip is on positive z axis. Center of base is on negative z axis....
Definition: shapes.h:178
shapes::createMeshFromAsset
Mesh * createMeshFromAsset(const aiScene *scene, const Eigen::Vector3d &scale, const std::string &assimp_hint=std::string())
Load a mesh from an assimp datastructure.
Definition: mesh_operations.cpp:366
shapes::createMeshFromShape
Mesh * createMeshFromShape(const Shape *shape)
Construct a mesh from a primitive shape that is NOT already a mesh. This call allocates a new object.
Definition: mesh_operations.cpp:390


geometric_shapes
Author(s): Ioan Sucan , Gil Jones
autogenerated on Sun Oct 1 2023 02:40:16