parser_base.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #ifndef PARSER_BASE_HPP_
19 #define PARSER_BASE_HPP_
20 
21 #include <stdint.h>
22 #include <fcl/BVH/BVH_model.h>
23 #include <fcl/math/vec_3f.h>
24 
26 
28 {
29  protected:
30  std::string file_path_;
31 
32  public:
37  ParserBase(const std::string& file_path)
38  : file_path_(file_path)
39  {
40 
41  }
42 
43  virtual ~ParserBase()
44  {
45 
46  }
47 
52  inline const std::string getFilePath() const
53  {
54  return this->file_path_;
55  }
56 
62  virtual int8_t read(std::vector<TriangleSupport>& tri_vec) = 0;
63 
64  template <typename T>
65  int8_t createBVH(fcl::BVHModel<T>& bvh);
66 
67  template <typename T>
68  int8_t createBVH(std::shared_ptr<fcl::BVHModel<T> > ptr_bvh);
69 };
70 
71 
78 template <typename T>
79 int8_t ParserBase::createBVH(fcl::BVHModel<T>& bvh)
80 {
81  int8_t success = -1;
82  std::vector<TriangleSupport> tri_vec;
83  if(0 == this->read(tri_vec))
84  {
85  bvh.beginModel();
86  for(TriangleSupport t : tri_vec)
87  {
88  bvh.addTriangle(t.a, t.b, t.c);
89  }
90 
91  bvh.endModel();
92  bvh.computeLocalAABB();
93  success = 0;
94  }
95 
96  return success;
97 }
98 
99 template <typename T>
100 int8_t ParserBase::createBVH(std::shared_ptr<fcl::BVHModel<T> > ptr_bvh)
101 {
102  int8_t success = -1;
103  std::vector<TriangleSupport> tri_vec;
104  if(0 == this->read(tri_vec))
105  {
106  ptr_bvh->beginModel();
107  for(TriangleSupport t : tri_vec)
108  {
109  ptr_bvh->addTriangle(t.a, t.b, t.c);
110  }
111 
112  ptr_bvh->endModel();
113  ptr_bvh->computeLocalAABB();
114  success = 0;
115  }
116 
117  return success;
118 }
119 
120 
121 #endif /* PARSER_BASE_HPP_ */
ParserBase(const std::string &file_path)
Definition: parser_base.hpp:37
virtual int8_t read(std::vector< TriangleSupport > &tri_vec)=0
int8_t createBVH(fcl::BVHModel< T > &bvh)
Definition: parser_base.hpp:79
std::string file_path_
Definition: parser_base.hpp:30
geometry_msgs::TransformStamped t
virtual ~ParserBase()
Definition: parser_base.hpp:43
const std::string getFilePath() const
Definition: parser_base.hpp:52


cob_obstacle_distance
Author(s): Marco Bezzon
autogenerated on Thu Apr 8 2021 02:39:47