26 #ifndef TESSERACT_GEOMETRY_CONVEX_MESH_H
27 #define TESSERACT_GEOMETRY_CONVEX_MESH_H
31 #include <boost/serialization/export.hpp>
32 #include <Eigen/Geometry>
49 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
52 using Ptr = std::shared_ptr<ConvexMesh>;
53 using ConstPtr = std::shared_ptr<const ConvexMesh>;
77 ConvexMesh(std::shared_ptr<const tesseract_common::VectorVector3d> vertices,
78 std::shared_ptr<const Eigen::VectorXi> faces,
79 std::shared_ptr<const tesseract_common::Resource> resource =
nullptr,
80 const Eigen::Vector3d& scale = Eigen::Vector3d(1, 1, 1),
81 std::shared_ptr<const tesseract_common::VectorVector3d> normals =
nullptr,
82 std::shared_ptr<const tesseract_common::VectorVector4d> vertex_colors =
nullptr,
83 std::shared_ptr<MeshMaterial> mesh_material =
nullptr,
84 std::shared_ptr<
const std::vector<std::shared_ptr<MeshTexture>>> mesh_textures =
nullptr);
103 ConvexMesh(std::shared_ptr<const tesseract_common::VectorVector3d> vertices,
104 std::shared_ptr<const Eigen::VectorXi> faces,
106 std::shared_ptr<const tesseract_common::Resource> resource =
nullptr,
107 const Eigen::Vector3d& scale = Eigen::Vector3d(1, 1, 1),
108 std::shared_ptr<const tesseract_common::VectorVector3d> normals =
nullptr,
109 std::shared_ptr<const tesseract_common::VectorVector4d> vertex_colors =
nullptr,
110 std::shared_ptr<MeshMaterial> mesh_material =
nullptr,
111 std::shared_ptr<
const std::vector<std::shared_ptr<MeshTexture>>> mesh_textures =
nullptr);
140 template <
class Archive>
141 void serialize(Archive& ar,
const unsigned int version);