19 #ifndef HPP_RBPRM_SAMPLE_HH
20 #define HPP_RBPRM_SAMPLE_HH
22 #include <Eigen/StdVector>
24 #include <hpp/pinocchio/device.hh>
42 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
51 Sample(
const pinocchio::JointPtr_t limb,
const pinocchio::Frame effector,
52 const fcl::Vec3f& offset = fcl::Vec3f(0, 0, 0),
53 const fcl::Vec3f& limbOffset = fcl::Vec3f(0, 0, 0),
54 const std::size_t
id = 0);
56 Sample(
const std::size_t
id,
const std::size_t length,
57 const std::size_t startRank,
const double staticValue,
58 const fcl::Vec3f& effectorPosition,
59 const fcl::Vec3f& effectorPositionInLimbFrame,
60 const pinocchio::ConfigurationIn_t configuration,
61 const Eigen::MatrixXd& jacobian,
62 const Eigen::Matrix<pinocchio::value_type, 6, 6>& jacobianProduct);
70 Sample(
const pinocchio::JointPtr_t limb,
const pinocchio::Frame effector,
71 pinocchio::ConfigurationIn_t configuration,
72 const fcl::Vec3f& offset = fcl::Vec3f(0, 0, 0),
73 const fcl::Vec3f& limbOffset = fcl::Vec3f(0, 0, 0),
74 const std::size_t
id = 0);
109 const pinocchio::JointPtr_t limb,
const std::string& effector,
110 const std::size_t nbSamples,
const fcl::Vec3f& offset = fcl::Vec3f(0, 0, 0),
111 const fcl::Vec3f& limbOffset = fcl::Vec3f(0, 0, 0));
116 void Load(
const Sample& sample, pinocchio::ConfigurationOut_t robot);
121 #endif // HPP_RBPRM_SAMPLE_HH