hpp-rbprm  4.13.0
Implementation of RB-PRM planner using hpp.
hpp::rbprm::sampling::SampleDB Class Reference

#include <hpp/rbprm/sampling/sample-db.hh>

Public Member Functions

 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="")
 
 ~SampleDB ()
 

Public Attributes

double resolution_
 
T_Sample samples_
 
hpp::fcl::shared_ptr< const octomap::OcTree > octomapTree_
 
fcl::OcTree * octree_
 
hpp::fcl::shared_ptr< fcl::CollisionGeometry > geometry_
 
T_Values values_
 
T_ValueBound valueBounds_
 
T_VoxelSampleId samplesInVoxels_
 
fcl::CollisionObject treeObject_
 fcl collision object used for collisions with environment More...
 
std::map< std::size_t, fcl::CollisionObject * > boxes_
 Bounding boxes of areas of interest of the octree. More...
 

Detailed Description

Sample configuration for a robot limb, stored in an octree and used for proximity requests for contact creation. assumes that joints are compact, ie they all are consecutive in configuration.

Constructor & Destructor Documentation

◆ SampleDB() [1/2]

hpp::rbprm::sampling::SampleDB::SampleDB ( std::ifstream &  databaseStream,
bool  loadValues = true 
)

◆ SampleDB() [2/2]

hpp::rbprm::sampling::SampleDB::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 = "" 
)

◆ ~SampleDB()

hpp::rbprm::sampling::SampleDB::~SampleDB ( )

Member Data Documentation

◆ boxes_

std::map<std::size_t, fcl::CollisionObject*> hpp::rbprm::sampling::SampleDB::boxes_

Bounding boxes of areas of interest of the octree.

◆ geometry_

hpp::fcl::shared_ptr<fcl::CollisionGeometry> hpp::rbprm::sampling::SampleDB::geometry_

◆ octomapTree_

hpp::fcl::shared_ptr<const octomap::OcTree> hpp::rbprm::sampling::SampleDB::octomapTree_

◆ octree_

fcl::OcTree* hpp::rbprm::sampling::SampleDB::octree_

◆ resolution_

double hpp::rbprm::sampling::SampleDB::resolution_

◆ samples_

T_Sample hpp::rbprm::sampling::SampleDB::samples_

◆ samplesInVoxels_

T_VoxelSampleId hpp::rbprm::sampling::SampleDB::samplesInVoxels_

◆ treeObject_

fcl::CollisionObject hpp::rbprm::sampling::SampleDB::treeObject_

fcl collision object used for collisions with environment

◆ valueBounds_

T_ValueBound hpp::rbprm::sampling::SampleDB::valueBounds_

◆ values_

T_Values hpp::rbprm::sampling::SampleDB::values_

The documentation for this class was generated from the following file: