19 #ifndef HPP_RBPRM_SAMPLEDB_HH 20 # define HPP_RBPRM_SAMPLEDB_HH 25 #include <hpp/fcl/octree.h> 26 #include <boost/function.hpp> 39 OctreeReport(
const Sample*,
const fcl::Contact,
const double,
const fcl::Vec3f& normal,
40 const fcl::Vec3f& v1,
const fcl::Vec3f& v2,
const fcl::Vec3f& v3);
66 typedef std::map<std::string, T_Double>
T_Values;
75 typedef boost::function <double (const SampleDB& sampleDB, const sampling::Sample& sample) >
evaluate;
89 SampleDB(std::ifstream& databaseStream,
bool loadValues =
true);
90 SampleDB(
const pinocchio::JointPtr_t limb,
const std::string& effector,
const std::size_t nbSamples,
91 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 =
"");
110 std::map<std::size_t, fcl::CollisionObject*>
boxes_;
130 const hpp::pinocchio::CollisionObjectPtr_t& o2,
146 const hpp::pinocchio::CollisionObjectPtr_t& o2,
147 const fcl::Vec3f& direction, T_OctreeReport& report,
const HeuristicParam & params,
const heuristic evaluate = 0);
152 #endif // HPP_RBPRM_SAMPLEDB_HH T_Sample samples_
Definition: sample-db.hh:100
#define HPP_RBPRM_DLLAPI
Definition: config.hh:64
T_ValueBound valueBounds_
Definition: sample-db.hh:105
fcl::CollisionObject treeObject_
fcl collision object used for collisions with environment
Definition: sample-db.hh:108
Definition: sample-db.hh:86
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:103
std::map< std::size_t, fcl::CollisionObject * > boxes_
Bounding boxes of areas of interest of the octree.
Definition: sample-db.hh:110
Definition: algorithm.hh:27
const Sample * sample_
Sample considered for contact generation.
Definition: sample-db.hh:42
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:76
std::map< long int, VoxelSampleId > T_VoxelSampleId
Definition: sample-db.hh:79
double(* heuristic)(const sampling::Sample &sample, const Eigen::Vector3d &direction, const Eigen::Vector3d &normal, const HeuristicParam ¶ms)
Definition: heuristic.hh:41
std::map< std::string, T_Double > T_Values
Definition: sample-db.hh:66
T_Values values_
Definition: sample-db.hh:104
fcl::Vec3f v1_
Definition: sample-db.hh:48
fcl::OcTree * octree_
Definition: sample-db.hh:102
fcl::Contact contact_
Contact information returned from fcl.
Definition: sample-db.hh:44
fcl::Vec3f v3_
Definition: sample-db.hh:48
HPP_RBPRM_DLLAPI bool saveLimbDatabase(const SampleDB &database, std::ofstream &dbFile)
T_VoxelSampleId samplesInVoxels_
Definition: sample-db.hh:106
std::multiset< OctreeReport, sample_compare > T_OctreeReport
Definition: sample-db.hh:61
Definition: sample-db.hh:55
sampling::SampleVector_t T_Sample
Definition: sample-db.hh:67
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)
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:48
fcl::Vec3f v2_
Definition: sample-db.hh:48
std::pair< std::size_t, std::size_t > VoxelSampleId
Definition: sample-db.hh:78
double resolution_
Definition: sample-db.hh:99
boost::function< double(const SampleDB &sampleDB, const sampling::Sample &sample) > evaluate
Definition: sample-db.hh:75
std::map< std::string, ValueBound > T_ValueBound
Definition: sample-db.hh:81
double value_
heuristic evaluation of the sample
Definition: sample-db.hh:46
std::vector< Sample, Eigen::aligned_allocator< Sample > > SampleVector_t
Definition: sample.hh:92
std::pair< double, double > ValueBound
Definition: sample-db.hh:80
std::vector< double > T_Double
Definition: sample-db.hh:65
boost::shared_ptr< const octomap::OcTree > octomapTree_
Definition: sample-db.hh:101