hpp-rbprm  4.11.0
Implementation of RB-PRM planner using hpp.
sample-db.hh
Go to the documentation of this file.
1 //
2 // Copyright (c) 2014 CNRS
3 // Authors: Steve Tonneau (steve.tonneau@laas.fr)
4 //
5 // This file is part of hpp-rbprm.
6 // hpp-rbprm is free software: you can redistribute it
7 // and/or modify it under the terms of the GNU Lesser General Public
8 // License as published by the Free Software Foundation, either version
9 // 3 of the License, or (at your option) any later version.
10 //
11 // hpp-rbprm is distributed in the hope that it will be
12 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
13 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
14 // General Lesser Public License for more details. You should have
15 // received a copy of the GNU Lesser General Public License along with
16 // hpp-core If not, see
17 // <http://www.gnu.org/licenses/>.
18 
19 #ifndef HPP_RBPRM_SAMPLEDB_HH
20 #define HPP_RBPRM_SAMPLEDB_HH
21 
22 #include <hpp/rbprm/config.hh>
25 #include <hpp/fcl/octree.h>
26 #include <boost/function.hpp>
27 #include <vector>
28 #include <map>
29 
30 namespace hpp {
31 
32 namespace rbprm {
33 namespace sampling {
34 
37 struct OctreeReport {
38  OctreeReport(const Sample*, const fcl::Contact, const double, const fcl::Vec3f& normal, const fcl::Vec3f& v1,
39  const fcl::Vec3f& v2, const fcl::Vec3f& v3); // vertices of triangle collided
41  const Sample* sample_;
43  fcl::Contact contact_;
45  double value_;
47  fcl::Vec3f normal_, v1_, v2_, v3_;
48 };
49 
54  bool operator()(const OctreeReport& lhs, const OctreeReport& rhs) const { return lhs.value_ > rhs.value_; }
55 };
56 
57 typedef std::multiset<OctreeReport, sample_compare> T_OctreeReport;
58 
60 
61 typedef std::vector<double> T_Double;
62 typedef std::map<std::string, T_Double> T_Values;
64 
69 // typedef double (*evaluate) (const SampleDB& sampleDB, const sampling::Sample& sample);
70 typedef boost::function<double(const SampleDB& sampleDB, const sampling::Sample& sample)> evaluate;
71 typedef std::map<std::string, evaluate> T_evaluate;
72 // first sample index, number of samples
73 typedef std::pair<std::size_t, std::size_t> VoxelSampleId;
74 typedef std::map<long int, VoxelSampleId> T_VoxelSampleId;
75 typedef std::pair<double, double> ValueBound;
76 typedef std::map<std::string, ValueBound> T_ValueBound;
77 
82  public:
83  SampleDB(std::ifstream& databaseStream, bool loadValues = true);
84  SampleDB(const pinocchio::JointPtr_t limb, const std::string& effector, const std::size_t nbSamples,
85  const fcl::Vec3f& offset = fcl::Vec3f(0, 0, 0), const fcl::Vec3f& limbOffset = fcl::Vec3f(0, 0, 0),
86  const double resolution = 0.1, const T_evaluate& data = T_evaluate(), const std::string& staticValue = "");
87  ~SampleDB();
88  /*
89  private:
90  SampleDB(const SampleDB&);
91  const SampleDB& operator=(const SampleDB&);
92  */
93  public:
94  double resolution_;
95  T_Sample samples_;
96  boost::shared_ptr<const octomap::OcTree> octomapTree_;
97  fcl::OcTree* octree_; // deleted with geometry_
98  boost::shared_ptr<fcl::CollisionGeometry> geometry_;
99  T_Values values_;
100  T_ValueBound valueBounds_;
101  T_VoxelSampleId samplesInVoxels_;
103  fcl::CollisionObject treeObject_;
105  std::map<std::size_t, fcl::CollisionObject*> boxes_;
106 
107 }; // class SampleDB
108 
109 HPP_RBPRM_DLLAPI SampleDB& addValue(SampleDB& database, const std::string& valueName, const evaluate eval,
110  bool isStaticValue = true, bool sortSamples = true);
111 HPP_RBPRM_DLLAPI bool saveLimbDatabase(const SampleDB& database, std::ofstream& dbFile);
112 
124 HPP_RBPRM_DLLAPI T_OctreeReport GetCandidates(const SampleDB& sc, const fcl::Transform3f& treeTrf,
125  const hpp::pinocchio::CollisionObjectPtr_t& o2,
126  const fcl::Vec3f& direction, const HeuristicParam& params,
127  const heuristic evaluate = 0);
128 
141 HPP_RBPRM_DLLAPI bool GetCandidates(const SampleDB& sc, const fcl::Transform3f& treeTrf,
142  const hpp::pinocchio::CollisionObjectPtr_t& o2, const fcl::Vec3f& direction,
143  T_OctreeReport& report, const HeuristicParam& params,
144  const heuristic evaluate = 0);
145 
146 } // namespace sampling
147 } // namespace rbprm
148 } // namespace hpp
149 #endif // HPP_RBPRM_SAMPLEDB_HH
T_Sample samples_
Definition: sample-db.hh:95
#define HPP_RBPRM_DLLAPI
Definition: config.hh:64
T_ValueBound valueBounds_
Definition: sample-db.hh:100
bool operator()(const OctreeReport &lhs, const OctreeReport &rhs) const
Definition: sample-db.hh:54
fcl::CollisionObject treeObject_
fcl collision object used for collisions with environment
Definition: sample-db.hh:103
Definition: sample.hh:40
Definition: sample-db.hh:81
OctreeReport(const Sample *, const fcl::Contact, const double, const fcl::Vec3f &normal, const fcl::Vec3f &v1, const fcl::Vec3f &v2, const fcl::Vec3f &v3)
boost::shared_ptr< fcl::CollisionGeometry > geometry_
Definition: sample-db.hh:98
std::map< std::size_t, fcl::CollisionObject * > boxes_
Bounding boxes of areas of interest of the octree.
Definition: sample-db.hh:105
Definition: algorithm.hh:27
const Sample * sample_
Sample considered for contact generation.
Definition: sample-db.hh:41
HPP_PREDEF_CLASS(OctreeNode)
Defines a parameters set for the ZMP-based heuristic.
Definition: heuristic-tools.hh:13
std::map< std::string, evaluate > T_evaluate
Definition: sample-db.hh:71
std::map< long int, VoxelSampleId > T_VoxelSampleId
Definition: sample-db.hh:74
double(* heuristic)(const sampling::Sample &sample, const Eigen::Vector3d &direction, const Eigen::Vector3d &normal, const HeuristicParam &params)
Definition: heuristic.hh:39
std::map< std::string, T_Double > T_Values
Definition: sample-db.hh:62
T_Values values_
Definition: sample-db.hh:99
fcl::Vec3f v1_
Definition: sample-db.hh:47
fcl::OcTree * octree_
Definition: sample-db.hh:97
fcl::Contact contact_
Contact information returned from fcl.
Definition: sample-db.hh:43
fcl::Vec3f v3_
Definition: sample-db.hh:47
HPP_RBPRM_DLLAPI bool saveLimbDatabase(const SampleDB &database, std::ofstream &dbFile)
T_VoxelSampleId samplesInVoxels_
Definition: sample-db.hh:101
std::multiset< OctreeReport, sample_compare > T_OctreeReport
Definition: sample-db.hh:57
Definition: sample-db.hh:53
sampling::SampleVector_t T_Sample
Definition: sample-db.hh:63
HPP_RBPRM_DLLAPI T_OctreeReport GetCandidates(const SampleDB &sc, const fcl::Transform3f &treeTrf, const hpp::pinocchio::CollisionObjectPtr_t &o2, const fcl::Vec3f &direction, const HeuristicParam &params, const heuristic evaluate=0)
boost::function< double(const SampleDB &sampleDB, const sampling::Sample &sample)> evaluate
Definition: sample-db.hh:70
Definition: sample-db.hh:37
HPP_RBPRM_DLLAPI SampleDB & addValue(SampleDB &database, const std::string &valueName, const evaluate eval, bool isStaticValue=true, bool sortSamples=true)
fcl::Vec3f normal_
normal vector of the surface in contact
Definition: sample-db.hh:47
fcl::Vec3f v2_
Definition: sample-db.hh:47
std::pair< std::size_t, std::size_t > VoxelSampleId
Definition: sample-db.hh:73
double resolution_
Definition: sample-db.hh:94
std::map< std::string, ValueBound > T_ValueBound
Definition: sample-db.hh:76
double value_
heuristic evaluation of the sample
Definition: sample-db.hh:45
std::vector< Sample, Eigen::aligned_allocator< Sample > > SampleVector_t
Definition: sample.hh:93
std::pair< double, double > ValueBound
Definition: sample-db.hh:75
std::vector< double > T_Double
Definition: sample-db.hh:61
boost::shared_ptr< const octomap::OcTree > octomapTree_
Definition: sample-db.hh:96