parser_base.hpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 
00018 #ifndef PARSER_BASE_HPP_
00019 #define PARSER_BASE_HPP_
00020 
00021 #include <stdint.h>
00022 #include <fcl/BVH/BVH_model.h>
00023 #include <fcl/math/vec_3f.h>
00024 
00025 #include "cob_obstacle_distance/obstacle_distance_data_types.hpp"
00026 
00027 class ParserBase
00028 {
00029     protected:
00030         std::string file_path_;
00031 
00032     public:
00037         ParserBase(const std::string& file_path)
00038         : file_path_(file_path)
00039         {
00040 
00041         }
00042 
00043         virtual ~ParserBase()
00044         {
00045 
00046         }
00047 
00052         inline const std::string getFilePath() const
00053         {
00054             return this->file_path_;
00055         }
00056 
00062         virtual int8_t read(std::vector<TriangleSupport>& tri_vec) = 0;
00063 
00064         template <typename T>
00065         int8_t createBVH(fcl::BVHModel<T>& bvh);
00066 
00067         template <typename T>
00068         int8_t createBVH(boost::shared_ptr<fcl::BVHModel<T> > ptr_bvh);
00069 };
00070 
00071 
00078 template <typename T>
00079 int8_t ParserBase::createBVH(fcl::BVHModel<T>& bvh)
00080 {
00081     int8_t success = -1;
00082     std::vector<TriangleSupport> tri_vec;
00083     if(0 == this->read(tri_vec))
00084     {
00085         bvh.beginModel();
00086         for(TriangleSupport t :  tri_vec)
00087         {
00088             bvh.addTriangle(t.a, t.b, t.c);
00089         }
00090 
00091         bvh.endModel();
00092         bvh.computeLocalAABB();
00093         success = 0;
00094     }
00095 
00096     return success;
00097 }
00098 
00099 template <typename T>
00100 int8_t ParserBase::createBVH(boost::shared_ptr<fcl::BVHModel<T> > ptr_bvh)
00101 {
00102     int8_t success = -1;
00103     std::vector<TriangleSupport> tri_vec;
00104     if(0 == this->read(tri_vec))
00105     {
00106         ptr_bvh->beginModel();
00107         for(TriangleSupport t :  tri_vec)
00108         {
00109             ptr_bvh->addTriangle(t.a, t.b, t.c);
00110         }
00111 
00112         ptr_bvh->endModel();
00113         ptr_bvh->computeLocalAABB();
00114         success = 0;
00115     }
00116 
00117     return success;
00118 }
00119 
00120 
00121 #endif /* PARSER_BASE_HPP_ */


cob_obstacle_distance
Author(s): Marco Bezzon
autogenerated on Thu Jun 6 2019 21:19:14