hpp-rbprm
4.15.1
Implementation of RB-PRM planner using hpp.
|
#include <hpp/rbprm/rbprm-limb.hh>
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, MatrixXX > | kinematicConstraints_ |
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... | |
hpp::rbprm::RbPrmLimb::~RbPrmLimb | ( | ) |
|
protected |
|
protected |
|
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.
limb | Joint instance that serves as a root for the limb |
effectorName | name of the joint to be considered as the effector of the limb |
offset | position of the effector in joint coordinates relatively to the effector joint |
unit | normal vector of the contact point, expressed in the effector joint coordinates |
x | half width of the default support polygon of the effector |
y | half height of the default support polygon of the effector |
nbSamples | number of samples to generate for the limb |
evaluate | heuristic method used to bias sample generation |
resolution,resolution | of 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. |
contactType | Whether 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. |
limb | Joint instance that serves as a root for the limb |
offset | position of the effector in joint coordinates relatively to the effector joint |
limbOffset | is the offset between the limb_ joint position and it's link |
unit | normal vector of the contact point, expressed in the effector joint coordinates |
x | half width of the default support polygon of the effector |
y | half height of the default support polygon of the effector |
nbSamples | number of samples to generate for the limb |
evaluate | heuristic method used to bias sample generation |
resolution,resolution | of 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. |
contactType | Whether the contact is a surface contact (orientation matters) or a punctual contact |
disableEndEffectorCollision | Whether the end effector bodies should be counted for collision detection |
|
static |
|
protected |
Initialization.
pinocchio::Transform3f hpp::rbprm::RbPrmLimb::octreeRoot | ( | ) | const |
const ContactType hpp::rbprm::RbPrmLimb::contactType_ |
const bool hpp::rbprm::RbPrmLimb::disableEndEffectorCollision_ |
const pinocchio::Frame hpp::rbprm::RbPrmLimb::effector_ |
const fcl::Matrix3f hpp::rbprm::RbPrmLimb::effectorDefaultRotation_ |
fcl::Vec3f hpp::rbprm::RbPrmLimb::effectorReferencePosition_ |
sampling::heuristic hpp::rbprm::RbPrmLimb::evaluate_ |
const bool hpp::rbprm::RbPrmLimb::grasps_ |
const pinocchio::JointPtr_t hpp::rbprm::RbPrmLimb::limb_ |
const fcl::Vec3f hpp::rbprm::RbPrmLimb::limbOffset_ |
const fcl::Vec3f hpp::rbprm::RbPrmLimb::normal_ |
const fcl::Vec3f hpp::rbprm::RbPrmLimb::offset_ |
sampling::SampleDB hpp::rbprm::RbPrmLimb::sampleContainer_ |
const double hpp::rbprm::RbPrmLimb::x_ |
const double hpp::rbprm::RbPrmLimb::y_ |