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);
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