18 #ifndef PARSER_BASE_HPP_ 19 #define PARSER_BASE_HPP_ 22 #include <fcl/BVH/BVH_model.h> 23 #include <fcl/math/vec_3f.h> 38 : file_path_(file_path)
62 virtual int8_t
read(std::vector<TriangleSupport>& tri_vec) = 0;
68 int8_t
createBVH(std::shared_ptr<fcl::BVHModel<T> > ptr_bvh);
82 std::vector<TriangleSupport> tri_vec;
83 if(0 == this->
read(tri_vec))
88 bvh.addTriangle(
t.a,
t.b,
t.c);
92 bvh.computeLocalAABB();
103 std::vector<TriangleSupport> tri_vec;
104 if(0 == this->
read(tri_vec))
106 ptr_bvh->beginModel();
109 ptr_bvh->addTriangle(
t.a,
t.b,
t.c);
113 ptr_bvh->computeLocalAABB();
ParserBase(const std::string &file_path)
virtual int8_t read(std::vector< TriangleSupport > &tri_vec)=0
int8_t createBVH(fcl::BVHModel< T > &bvh)
geometry_msgs::TransformStamped t
const std::string getFilePath() const