hpp-rbprm  4.11.0
Implementation of RB-PRM planner using hpp.
hpp::rbprm::RbPrmLimb Class Reference

#include <hpp/rbprm/rbprm-limb.hh>

Collaboration diagram for hpp::rbprm::RbPrmLimb:

Public Member Functions

 ~RbPrmLimb ()
 
pinocchio::Transform3f octreeRoot () const
 

Static Public Member Functions

static RbPrmLimbPtr_t create (const pinocchio::JointPtr_t limb, const std::string &effectorName, const fcl::Vec3f &offset, const fcl::Vec3f &limbOffset, const fcl::Vec3f &normal, const double x, const double y, const std::size_t nbSamples, const sampling::heuristic evaluate=0, const double resolution=0.1, ContactType contactType=_6_DOF, bool disableEndEffectorCollision=false, bool grasps=false, const std::string &kinematicsConstraintsPath=std::string(), const double kinematicConstraintsMinDistance=0.)
 
static RbPrmLimbPtr_t create (const pinocchio::DevicePtr_t device, std::ifstream &fileStream, const bool loadValues=true, const hpp::rbprm::sampling::heuristic evaluate=0, bool disableEndEffectorCollision=false, bool grasps=false)
 

Public Attributes

const pinocchio::JointPtr_t limb_
 
const pinocchio::Frame effector_
 
const fcl::Matrix3f effectorDefaultRotation_
 
const fcl::Vec3f offset_
 
const fcl::Vec3f limbOffset_
 
const fcl::Vec3f normal_
 
const double x_
 
const double y_
 
const ContactType contactType_
 
sampling::heuristic evaluate_
 
sampling::SampleDB sampleContainer_
 
const bool disableEndEffectorCollision_
 
const bool grasps_
 
fcl::Vec3f effectorReferencePosition_
 
std::pair< MatrixXX, MatrixXXkinematicConstraints_
 

Protected Member Functions

 RbPrmLimb (const pinocchio::JointPtr_t &limb, const std::string &effectorName, const fcl::Vec3f &offset, const fcl::Vec3f &limbOffset, const fcl::Vec3f &normal, const double x, const double y, const std::size_t nbSamples, const sampling::heuristic evaluate, const double resolution, ContactType contactType, bool disableEndEffectorCollision=false, bool grasps=false, const std::string &kinematicsConstraintsPath=std::string(), const double kinematicConstraintsMinDistance=0.)
 
 RbPrmLimb (const pinocchio::DevicePtr_t device, std::ifstream &fileStream, const bool loadValues, const hpp::rbprm::sampling::heuristic evaluate, bool disableEndEffectorCollision=false, bool grasps=false)
 
void init (const RbPrmLimbWkPtr_t &weakPtr)
 Initialization. More...
 

Constructor & Destructor Documentation

◆ ~RbPrmLimb()

hpp::rbprm::RbPrmLimb::~RbPrmLimb ( )

◆ RbPrmLimb() [1/2]

hpp::rbprm::RbPrmLimb::RbPrmLimb ( const pinocchio::JointPtr_t &  limb,
const std::string &  effectorName,
const fcl::Vec3f &  offset,
const fcl::Vec3f &  limbOffset,
const fcl::Vec3f &  normal,
const double  x,
const double  y,
const std::size_t  nbSamples,
const sampling::heuristic  evaluate,
const double  resolution,
ContactType  contactType,
bool  disableEndEffectorCollision = false,
bool  grasps = false,
const std::string &  kinematicsConstraintsPath = std::string(),
const double  kinematicConstraintsMinDistance = 0. 
)
protected

◆ RbPrmLimb() [2/2]

hpp::rbprm::RbPrmLimb::RbPrmLimb ( const pinocchio::DevicePtr_t  device,
std::ifstream &  fileStream,
const bool  loadValues,
const hpp::rbprm::sampling::heuristic  evaluate,
bool  disableEndEffectorCollision = false,
bool  grasps = false 
)
protected

Member Function Documentation

◆ create() [1/2]

static RbPrmLimbPtr_t hpp::rbprm::RbPrmLimb::create ( const pinocchio::JointPtr_t  limb,
const std::string &  effectorName,
const fcl::Vec3f &  offset,
const fcl::Vec3f &  limbOffset,
const fcl::Vec3f &  normal,
const double  x,
const double  y,
const std::size_t  nbSamples,
const sampling::heuristic  evaluate = 0,
const double  resolution = 0.1,
ContactType  contactType = _6_DOF,
bool  disableEndEffectorCollision = false,
bool  grasps = false,
const std::string &  kinematicsConstraintsPath = std::string(),
const double  kinematicConstraintsMinDistance = 0. 
)
static

Creates a Limb a Fullbody instance Stores a sample container, used for proximity requests. The Effector is considered as the last joint of the depth first search on the kinematic subchain.

Parameters
limbJoint instance that serves as a root for the limb
effectorNamename of the joint to be considered as the effector of the limb
offsetposition of the effector in joint coordinates relatively to the effector joint
unitnormal vector of the contact point, expressed in the effector joint coordinates
xhalf width of the default support polygon of the effector
yhalf height of the default support polygon of the effector
nbSamplesnumber of samples to generate for the limb
evaluateheuristic method used to bias sample generation
resolution,resolutionof the octree voxels. The samples generated are stored in an octree data structure to perform efficient proximity requests. The resulution of the octree, in meters, specifies the size of the unit voxel of the octree. The larger they are, the more samples will be considered as candidates for contact. This can be problematic in terms of performance. The default value is 3 cm.
contactTypeWhether the contact is a surface contact (orientation matters) or a punctual contact Creates a Limb a Fullbody instance Stores a sample container, used for proximity requests.
limbJoint instance that serves as a root for the limb
offsetposition of the effector in joint coordinates relatively to the effector joint
limbOffsetis the offset between the limb_ joint position and it's link
unitnormal vector of the contact point, expressed in the effector joint coordinates
xhalf width of the default support polygon of the effector
yhalf height of the default support polygon of the effector
nbSamplesnumber of samples to generate for the limb
evaluateheuristic method used to bias sample generation
resolution,resolutionof the octree voxels. The samples generated are stored in an octree data structure to perform efficient proximity requests. The resulution of the octree, in meters, specifies the size of the unit voxel of the octree. The larger they are, the more samples will be considered as candidates for contact. This can be problematic in terms of performance. The default value is 3 cm.
contactTypeWhether the contact is a surface contact (orientation matters) or a punctual contact
disableEndEffectorCollisionWhether the end effector bodies should be counted for collision detection

◆ create() [2/2]

static RbPrmLimbPtr_t hpp::rbprm::RbPrmLimb::create ( const pinocchio::DevicePtr_t  device,
std::ifstream &  fileStream,
const bool  loadValues = true,
const hpp::rbprm::sampling::heuristic  evaluate = 0,
bool  disableEndEffectorCollision = false,
bool  grasps = false 
)
static

◆ init()

void hpp::rbprm::RbPrmLimb::init ( const RbPrmLimbWkPtr_t &  weakPtr)
protected

Initialization.

◆ octreeRoot()

pinocchio::Transform3f hpp::rbprm::RbPrmLimb::octreeRoot ( ) const

Member Data Documentation

◆ contactType_

const ContactType hpp::rbprm::RbPrmLimb::contactType_

◆ disableEndEffectorCollision_

const bool hpp::rbprm::RbPrmLimb::disableEndEffectorCollision_

◆ effector_

const pinocchio::Frame hpp::rbprm::RbPrmLimb::effector_

◆ effectorDefaultRotation_

const fcl::Matrix3f hpp::rbprm::RbPrmLimb::effectorDefaultRotation_

◆ effectorReferencePosition_

fcl::Vec3f hpp::rbprm::RbPrmLimb::effectorReferencePosition_

◆ evaluate_

sampling::heuristic hpp::rbprm::RbPrmLimb::evaluate_

◆ grasps_

const bool hpp::rbprm::RbPrmLimb::grasps_

◆ kinematicConstraints_

std::pair<MatrixXX, MatrixXX> hpp::rbprm::RbPrmLimb::kinematicConstraints_

◆ limb_

const pinocchio::JointPtr_t hpp::rbprm::RbPrmLimb::limb_

◆ limbOffset_

const fcl::Vec3f hpp::rbprm::RbPrmLimb::limbOffset_

◆ normal_

const fcl::Vec3f hpp::rbprm::RbPrmLimb::normal_

◆ offset_

const fcl::Vec3f hpp::rbprm::RbPrmLimb::offset_

◆ sampleContainer_

sampling::SampleDB hpp::rbprm::RbPrmLimb::sampleContainer_

◆ x_

const double hpp::rbprm::RbPrmLimb::x_

◆ y_

const double hpp::rbprm::RbPrmLimb::y_

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