19 #ifndef HPP_RBPRM_SAMPLEDB_HH
20 #define HPP_RBPRM_SAMPLEDB_HH
22 #include <hpp/fcl/octree.h>
24 #include <boost/function.hpp>
40 const fcl::Vec3f& normal,
const fcl::Vec3f& v1,
42 const fcl::Vec3f& v3);
67 typedef std::map<std::string, T_Double>
T_Values;
76 typedef boost::function<double(
const SampleDB& sampleDB,
92 SampleDB(std::ifstream& databaseStream,
bool loadValues =
true);
93 SampleDB(
const pinocchio::JointPtr_t limb,
const std::string& effector,
94 const std::size_t nbSamples,
95 const fcl::Vec3f& offset = fcl::Vec3f(0, 0, 0),
96 const fcl::Vec3f& limbOffset = fcl::Vec3f(0, 0, 0),
98 const std::string& staticValue =
"");
117 std::map<std::size_t, fcl::CollisionObject*>
boxes_;
122 const std::string& valueName,
124 bool isStaticValue =
true,
125 bool sortSamples =
true);
127 std::ofstream& dbFile);
140 const SampleDB& sc,
const fcl::Transform3f& treeTrf,
141 const hpp::pinocchio::CollisionObjectPtr_t& o2,
const fcl::Vec3f& direction,
156 const SampleDB& sc,
const fcl::Transform3f& treeTrf,
157 const hpp::pinocchio::CollisionObjectPtr_t& o2,
const fcl::Vec3f& direction,
Definition: sample-db.hh:90
fcl::CollisionObject treeObject_
fcl collision object used for collisions with environment
Definition: sample-db.hh:115
T_VoxelSampleId samplesInVoxels_
Definition: sample-db.hh:113
SampleDB(std::ifstream &databaseStream, bool loadValues=true)
SampleDB(const pinocchio::JointPtr_t limb, const std::string &effector, const std::size_t nbSamples, const fcl::Vec3f &offset=fcl::Vec3f(0, 0, 0), const fcl::Vec3f &limbOffset=fcl::Vec3f(0, 0, 0), const double resolution=0.1, const T_evaluate &data=T_evaluate(), const std::string &staticValue="")
std::map< std::size_t, fcl::CollisionObject * > boxes_
Bounding boxes of areas of interest of the octree.
Definition: sample-db.hh:117
hpp::fcl::shared_ptr< const octomap::OcTree > octomapTree_
Definition: sample-db.hh:108
T_ValueBound valueBounds_
Definition: sample-db.hh:112
double resolution_
Definition: sample-db.hh:106
hpp::fcl::shared_ptr< fcl::CollisionGeometry > geometry_
Definition: sample-db.hh:110
fcl::OcTree * octree_
Definition: sample-db.hh:109
T_Values values_
Definition: sample-db.hh:111
T_Sample samples_
Definition: sample-db.hh:107
#define HPP_RBPRM_DLLAPI
Definition: config.hh:64
double(* heuristic)(const sampling::Sample &sample, const Eigen::Vector3d &direction, const Eigen::Vector3d &normal, const HeuristicParam ¶ms)
Definition: heuristic.hh:38
std::map< std::string, ValueBound > T_ValueBound
Definition: sample-db.hh:84
std::map< std::string, evaluate > T_evaluate
Definition: sample-db.hh:79
std::vector< double > T_Double
Definition: sample-db.hh:66
HPP_RBPRM_DLLAPI SampleDB & addValue(SampleDB &database, const std::string &valueName, const evaluate eval, bool isStaticValue=true, bool sortSamples=true)
std::vector< Sample, Eigen::aligned_allocator< Sample > > SampleVector_t
Definition: sample.hh:100
std::multiset< OctreeReport, sample_compare > T_OctreeReport
Definition: sample-db.hh:62
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 ¶ms, const heuristic evaluate=0)
std::pair< std::size_t, std::size_t > VoxelSampleId
Definition: sample-db.hh:81
std::pair< double, double > ValueBound
Definition: sample-db.hh:83
boost::function< double(const SampleDB &sampleDB, const sampling::Sample &sample)> evaluate
Definition: sample-db.hh:78
HPP_RBPRM_DLLAPI bool saveLimbDatabase(const SampleDB &database, std::ofstream &dbFile)
std::map< std::string, T_Double > T_Values
Definition: sample-db.hh:67
sampling::SampleVector_t T_Sample
Definition: sample-db.hh:68
HPP_PREDEF_CLASS(OctreeNode)
std::map< long int, VoxelSampleId > T_VoxelSampleId
Definition: sample-db.hh:82
Definition: algorithm.hh:26
Defines a parameters set for the ZMP-based heuristic.
Definition: heuristic-tools.hh:13
Definition: sample-db.hh:38
double value_
heuristic evaluation of the sample
Definition: sample-db.hh:48
fcl::Vec3f v2_
Definition: sample-db.hh:50
fcl::Vec3f normal_
normal vector of the surface in contact
Definition: sample-db.hh:50
fcl::Contact contact_
Contact information returned from fcl.
Definition: sample-db.hh:46
OctreeReport(const Sample *, const fcl::Contact, const double, const fcl::Vec3f &normal, const fcl::Vec3f &v1, const fcl::Vec3f &v2, const fcl::Vec3f &v3)
const Sample * sample_
Sample considered for contact generation.
Definition: sample-db.hh:44
fcl::Vec3f v3_
Definition: sample-db.hh:50
fcl::Vec3f v1_
Definition: sample-db.hh:50
Definition: sample-db.hh:56
bool operator()(const OctreeReport &lhs, const OctreeReport &rhs) const
Definition: sample-db.hh:57