19 #ifndef HPP_RBPRM_SAMPLE_HH 20 # define HPP_RBPRM_SAMPLE_HH 22 #include <Eigen/StdVector> 25 #include <hpp/pinocchio/device.hh> 44 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
53 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);
56 Sample(
const std::size_t
id,
const std::size_t length,
const std::size_t startRank,
const double staticValue,
57 const fcl::Vec3f& effectorPosition,
const fcl::Vec3f& effectorPositionInLimbFrame,
const pinocchio::ConfigurationIn_t configuration,
const Eigen::MatrixXd& jacobian,
58 const Eigen::Matrix <pinocchio::value_type, 6, 6>& jacobianProduct);
66 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);
67 Sample(
const Sample &clone);
92 typedef std::vector<Sample, Eigen::aligned_allocator<Sample> >
SampleVector_t;
100 SampleVector_t
GenerateSamples(
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));
105 void Load(
const Sample& sample, pinocchio::ConfigurationOut_t robot);
110 #endif // HPP_RBPRM_SAMPLE_HH #define HPP_RBPRM_DLLAPI
Definition: config.hh:64
std::size_t id_
id in sample container
Definition: sample.hh:81
fcl::Vec3f effectorPositionInLimbFrame_
Definition: sample.hh:76
Definition: algorithm.hh:27
HPP_PREDEF_CLASS(OctreeNode)
pinocchio::Configuration_t configuration_
Definition: sample.hh:73
void Load(const Sample &sample, pinocchio::ConfigurationOut_t robot)
double staticValue_
Definition: sample.hh:82
std::size_t startRank_
Definition: sample.hh:71
fcl::Vec3f effectorPosition_
Position relative to robot root (ie, robot base at 0 everywhere)
Definition: sample.hh:75
Eigen::Matrix< pinocchio::value_type, 6, 6 > jacobianProduct_
Product of the jacobian by its transpose.
Definition: sample.hh:79
Eigen::MatrixXd jacobian_
Definition: sample.hh:77
std::size_t length_
Definition: sample.hh:72
SampleVector_t GenerateSamples(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))
boost::shared_ptr< Sample > SamplePtr_t
Definition: sample.hh:37
~Sample()
Definition: sample.hh:68
std::vector< Sample, Eigen::aligned_allocator< Sample > > SampleVector_t
Definition: sample.hh:92