Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
polygon_mesh.h
Go to the documentation of this file.
1
26#ifndef TESSERACT_GEOMETRY_POLYGON_MESH_H
27#define TESSERACT_GEOMETRY_POLYGON_MESH_H
28
31#include <boost/serialization/access.hpp>
32#include <boost/serialization/export.hpp>
33#include <Eigen/Geometry>
34#include <memory>
36
42
43namespace tesseract_geometry
44{
45class PolygonMesh : public Geometry
46{
47public:
48 // LCOV_EXCL_START
49 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
50 // LCOV_EXCL_STOP
51
52 using Ptr = std::shared_ptr<PolygonMesh>;
53 using ConstPtr = std::shared_ptr<const PolygonMesh>;
54
70 PolygonMesh(std::shared_ptr<const tesseract_common::VectorVector3d> vertices,
71 std::shared_ptr<const Eigen::VectorXi> faces,
73 const Eigen::Vector3d& scale = Eigen::Vector3d(1, 1, 1), // NOLINT
74 std::shared_ptr<const tesseract_common::VectorVector3d> normals = nullptr,
75 std::shared_ptr<const tesseract_common::VectorVector4d> vertex_colors = nullptr,
76 MeshMaterial::Ptr mesh_material = nullptr,
77 std::shared_ptr<const std::vector<MeshTexture::Ptr>> mesh_textures = nullptr,
79 : Geometry(type)
80 , vertices_(std::move(vertices))
81 , faces_(std::move(faces))
82 , vertex_count_(static_cast<int>(vertices_->size()))
83 , resource_(std::move(resource))
84 , scale_(scale)
85 , normals_(std::move(normals))
86 , vertex_colors_(std::move(vertex_colors))
87 , mesh_material_(std::move(mesh_material))
88 , mesh_textures_(std::move(mesh_textures))
89 {
90 for (int i = 0; i < faces_->size(); ++i)
91 {
93 int num_verts = (*faces_)(i); // NOLINT
94 i += num_verts;
95 }
96 }
97
115 PolygonMesh(std::shared_ptr<const tesseract_common::VectorVector3d> vertices,
116 std::shared_ptr<const Eigen::VectorXi> faces,
117 int face_count,
119 const Eigen::Vector3d& scale = Eigen::Vector3d(1, 1, 1), // NOLINT
120 std::shared_ptr<const tesseract_common::VectorVector3d> normals = nullptr,
121 std::shared_ptr<const tesseract_common::VectorVector4d> vertex_colors = nullptr,
122 MeshMaterial::Ptr mesh_material = nullptr,
123 std::shared_ptr<const std::vector<MeshTexture::Ptr>> mesh_textures = nullptr,
125 : Geometry(type)
126 , vertices_(std::move(vertices))
127 , faces_(std::move(faces))
128 , vertex_count_(static_cast<int>(vertices_->size()))
129 , face_count_(face_count)
130 , resource_(std::move(resource))
131 , scale_(scale)
132 , normals_(std::move(normals))
133 , vertex_colors_(std::move(vertex_colors))
134 , mesh_material_(std::move(mesh_material))
135 , mesh_textures_(std::move(mesh_textures))
136 {
137 }
138
139 PolygonMesh() = default;
140 ~PolygonMesh() override = default;
141
146 const std::shared_ptr<const tesseract_common::VectorVector3d>& getVertices() const { return vertices_; }
147
152 const std::shared_ptr<const Eigen::VectorXi>& getFaces() const { return faces_; }
153
158 int getVertexCount() const { return vertex_count_; }
159
164 int getFaceCount() const { return face_count_; }
165
174
179 const Eigen::Vector3d& getScale() const { return scale_; }
180
188 const std::shared_ptr<const tesseract_common::VectorVector3d>& getNormals() const { return normals_; }
189
197 const std::shared_ptr<const tesseract_common::VectorVector4d>& getVertexColors() const { return vertex_colors_; }
198
208
219 const std::shared_ptr<const std::vector<MeshTexture::Ptr>>& getTextures() const { return mesh_textures_; }
220
221 Geometry::Ptr clone() const override
222 {
223 return std::make_shared<PolygonMesh>(vertices_, faces_, face_count_, resource_, scale_);
224 }
225 bool operator==(const PolygonMesh& rhs) const;
226 bool operator!=(const PolygonMesh& rhs) const;
227
228private:
229 std::shared_ptr<const tesseract_common::VectorVector3d> vertices_;
230 std::shared_ptr<const Eigen::VectorXi> faces_;
231
233 int face_count_{ 0 };
235 Eigen::Vector3d scale_;
236 std::shared_ptr<const tesseract_common::VectorVector3d> normals_;
237 std::shared_ptr<const tesseract_common::VectorVector4d> vertex_colors_;
239 std::shared_ptr<const std::vector<MeshTexture::Ptr>> mesh_textures_;
240
242 template <class Archive>
243 void serialize(Archive& ar, const unsigned int version); // NOLINT
244};
245
246} // namespace tesseract_geometry
247
248BOOST_CLASS_EXPORT_KEY2(tesseract_geometry::PolygonMesh, "PolygonMesh")
249#endif // POLYGON_MESH_H
std::shared_ptr< const Resource > ConstPtr
Definition: resource_locator.h:102
Definition: geometry.h:60
std::shared_ptr< Geometry > Ptr
Definition: geometry.h:62
std::shared_ptr< const MeshMaterial > ConstPtr
Definition: mesh_material.h:64
std::shared_ptr< MeshMaterial > Ptr
Definition: mesh_material.h:63
Definition: polygon_mesh.h:46
MeshMaterial::Ptr mesh_material_
Definition: polygon_mesh.h:238
const std::shared_ptr< const Eigen::VectorXi > & getFaces() const
Get Polygon mesh faces.
Definition: polygon_mesh.h:152
int getFaceCount() const
Get face count.
Definition: polygon_mesh.h:164
std::shared_ptr< const tesseract_common::VectorVector4d > vertex_colors_
Definition: polygon_mesh.h:237
std::shared_ptr< PolygonMesh > Ptr
Definition: polygon_mesh.h:52
std::shared_ptr< const Eigen::VectorXi > faces_
Definition: polygon_mesh.h:230
int getVertexCount() const
Get vertex count.
Definition: polygon_mesh.h:158
PolygonMesh(std::shared_ptr< const tesseract_common::VectorVector3d > vertices, std::shared_ptr< const Eigen::VectorXi > faces, tesseract_common::Resource::ConstPtr resource=nullptr, const Eigen::Vector3d &scale=Eigen::Vector3d(1, 1, 1), std::shared_ptr< const tesseract_common::VectorVector3d > normals=nullptr, std::shared_ptr< const tesseract_common::VectorVector4d > vertex_colors=nullptr, MeshMaterial::Ptr mesh_material=nullptr, std::shared_ptr< const std::vector< MeshTexture::Ptr > > mesh_textures=nullptr, GeometryType type=GeometryType::CONVEX_MESH)
Polygon Mesh geometry.
Definition: polygon_mesh.h:70
tesseract_common::Resource::ConstPtr resource_
Definition: polygon_mesh.h:234
tesseract_common::Resource::ConstPtr getResource() const
Get the path to file used to generate the mesh.
Definition: polygon_mesh.h:173
const std::shared_ptr< const tesseract_common::VectorVector3d > & getVertices() const
Get Polygon mesh vertices.
Definition: polygon_mesh.h:146
const Eigen::Vector3d & getScale() const
Get the scale applied to file used to generate the mesh.
Definition: polygon_mesh.h:179
const std::shared_ptr< const std::vector< MeshTexture::Ptr > > & getTextures() const
Get textures extracted from the mesh file.
Definition: polygon_mesh.h:219
bool operator==(const PolygonMesh &rhs) const
Definition: polygon_mesh.cpp:43
void serialize(Archive &ar, const unsigned int version)
Definition: polygon_mesh.cpp:56
~PolygonMesh() override=default
std::shared_ptr< const PolygonMesh > ConstPtr
Definition: polygon_mesh.h:53
const std::shared_ptr< const tesseract_common::VectorVector4d > & getVertexColors() const
Get the vertex colors.
Definition: polygon_mesh.h:197
Eigen::Vector3d scale_
Definition: polygon_mesh.h:235
Geometry::Ptr clone() const override
Create a copy of this shape.
Definition: polygon_mesh.h:221
friend class boost::serialization::access
Definition: polygon_mesh.h:241
std::shared_ptr< const tesseract_common::VectorVector3d > normals_
Definition: polygon_mesh.h:236
std::shared_ptr< const tesseract_common::VectorVector3d > vertices_
Definition: polygon_mesh.h:229
MeshMaterial::ConstPtr getMaterial() const
Get material data extracted from the mesh file.
Definition: polygon_mesh.h:207
bool operator!=(const PolygonMesh &rhs) const
Definition: polygon_mesh.cpp:53
PolygonMesh(std::shared_ptr< const tesseract_common::VectorVector3d > vertices, std::shared_ptr< const Eigen::VectorXi > faces, int face_count, tesseract_common::Resource::ConstPtr resource=nullptr, const Eigen::Vector3d &scale=Eigen::Vector3d(1, 1, 1), std::shared_ptr< const tesseract_common::VectorVector3d > normals=nullptr, std::shared_ptr< const tesseract_common::VectorVector4d > vertex_colors=nullptr, MeshMaterial::Ptr mesh_material=nullptr, std::shared_ptr< const std::vector< MeshTexture::Ptr > > mesh_textures=nullptr, GeometryType type=GeometryType::CONVEX_MESH)
Polygon Mesh geometry.
Definition: polygon_mesh.h:115
int face_count_
Definition: polygon_mesh.h:233
int vertex_count_
Definition: polygon_mesh.h:232
const std::shared_ptr< const tesseract_common::VectorVector3d > & getNormals() const
Get the vertex normal vectors.
Definition: polygon_mesh.h:188
std::shared_ptr< const std::vector< MeshTexture::Ptr > > mesh_textures_
Definition: polygon_mesh.h:239
double scale
Definition: collision_margin_data_unit.cpp:133
Common Tesseract Macros.
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
Definition: macros.h:71
Tesseract Mesh Material read from a mesh file.
Definition: create_convex_hull.cpp:36
Definition: geometry.h:39
GeometryType
Definition: geometry.h:41
@ CONVEX_MESH
Definition: geometry.h:50
Locate and retrieve resource data.
Resource::Ptr resource
Definition: resource_locator_unit.cpp:59
Common Tesseract Types.
mCollisionCheckConfig contact_request type
Definition: tesseract_environment_collision.cpp:103
Tesseract Geometries.
std::shared_ptr< const Eigen::VectorXi > faces
Definition: tesseract_geometry_unit.cpp:16