hpp-rbprm  4.14.0
Implementation of RB-PRM planner using hpp.
hpp::rbprm::sampling::Sample Class Reference

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

Public Member Functions

 Sample (const pinocchio::JointPtr_t limb, const pinocchio::Frame effector, const fcl::Vec3f &offset=fcl::Vec3f(0, 0, 0), const fcl::Vec3f &limbOffset=fcl::Vec3f(0, 0, 0), const std::size_t id=0)
 
 Sample (const std::size_t id, const std::size_t length, const std::size_t startRank, const double staticValue, const fcl::Vec3f &effectorPosition, const fcl::Vec3f &effectorPositionInLimbFrame, const pinocchio::ConfigurationIn_t configuration, const Eigen::MatrixXd &jacobian, const Eigen::Matrix< pinocchio::value_type, 6, 6 > &jacobianProduct)
 
 Sample (const pinocchio::JointPtr_t limb, const pinocchio::Frame effector, pinocchio::ConfigurationIn_t configuration, const fcl::Vec3f &offset=fcl::Vec3f(0, 0, 0), const fcl::Vec3f &limbOffset=fcl::Vec3f(0, 0, 0), const std::size_t id=0)
 
 Sample (const Sample &clone)
 
 ~Sample ()
 

Public Attributes

std::size_t startRank_
 
std::size_t length_
 
pinocchio::Configuration_t configuration_
 
fcl::Vec3f effectorPosition_
 Position relative to robot root (ie, robot base at 0 everywhere) More...
 
fcl::Vec3f effectorPositionInLimbFrame_
 
Eigen::MatrixXd jacobian_
 
Eigen::Matrix< pinocchio::value_type, 6, 6 > jacobianProduct_
 Product of the jacobian by its transpose. More...
 
std::size_t id_
 id in sample container More...
 
double staticValue_
 

Constructor & Destructor Documentation

◆ Sample() [1/4]

hpp::rbprm::sampling::Sample::Sample ( const pinocchio::JointPtr_t  limb,
const pinocchio::Frame  effector,
const fcl::Vec3f &  offset = fcl::Vec3f(0, 0, 0),
const fcl::Vec3f &  limbOffset = fcl::Vec3f(0, 0, 0),
const std::size_t  id = 0 
)

Creates a sample configuration, given the current configuration of a limb. the current Configuration_t of the limb will be used to compute the sample.

Parameters
limbroot of the considered limb
effectorjoint to be considered as the effector of the limb
offsetlocation of the contact point of the effector, relatively to the effector joint
idoptional identifier for the sample

◆ Sample() [2/4]

hpp::rbprm::sampling::Sample::Sample ( const std::size_t  id,
const std::size_t  length,
const std::size_t  startRank,
const double  staticValue,
const fcl::Vec3f &  effectorPosition,
const fcl::Vec3f &  effectorPositionInLimbFrame,
const pinocchio::ConfigurationIn_t  configuration,
const Eigen::MatrixXd &  jacobian,
const Eigen::Matrix< pinocchio::value_type, 6, 6 > &  jacobianProduct 
)

◆ Sample() [3/4]

hpp::rbprm::sampling::Sample::Sample ( const pinocchio::JointPtr_t  limb,
const pinocchio::Frame  effector,
pinocchio::ConfigurationIn_t  configuration,
const fcl::Vec3f &  offset = fcl::Vec3f(0, 0, 0),
const fcl::Vec3f &  limbOffset = fcl::Vec3f(0, 0, 0),
const std::size_t  id = 0 
)

Creates sample configuration for a limb, extracted from a complete robot configuration, passed as a parameter

Parameters
limbroot of the considered limb
theconfiguration from which the limb sample will be extracted
effectorjoint to be considered as the effector of the limb
offsetlocation of the contact point of the effector, relatively to the effector joint
idoptional identifier for the sample

◆ Sample() [4/4]

hpp::rbprm::sampling::Sample::Sample ( const Sample clone)

◆ ~Sample()

hpp::rbprm::sampling::Sample::~Sample ( )
inline

Member Data Documentation

◆ configuration_

pinocchio::Configuration_t hpp::rbprm::sampling::Sample::configuration_

◆ effectorPosition_

fcl::Vec3f hpp::rbprm::sampling::Sample::effectorPosition_

Position relative to robot root (ie, robot base at 0 everywhere)

◆ effectorPositionInLimbFrame_

fcl::Vec3f hpp::rbprm::sampling::Sample::effectorPositionInLimbFrame_

◆ id_

std::size_t hpp::rbprm::sampling::Sample::id_

id in sample container

◆ jacobian_

Eigen::MatrixXd hpp::rbprm::sampling::Sample::jacobian_

◆ jacobianProduct_

Eigen::Matrix<pinocchio::value_type, 6, 6> hpp::rbprm::sampling::Sample::jacobianProduct_

Product of the jacobian by its transpose.

◆ length_

std::size_t hpp::rbprm::sampling::Sample::length_

◆ startRank_

std::size_t hpp::rbprm::sampling::Sample::startRank_

◆ staticValue_

double hpp::rbprm::sampling::Sample::staticValue_

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