19 #ifndef HPP_RBPRM_LIMB_HH 20 #define HPP_RBPRM_LIMB_HH 22 #include <hpp/pinocchio/device.hh> 43 typedef std::map<std::string, const rbprm::RbPrmLimbPtr_t>
T_Limb;
45 typedef Eigen::Matrix<pinocchio::value_type, Eigen::Dynamic, Eigen::Dynamic>
47 typedef Eigen::Matrix<pinocchio::value_type, Eigen::Dynamic, 3>
MatrixX3;
48 typedef Eigen::Matrix<pinocchio::value_type, Eigen::Dynamic, 1>
VectorX;
49 typedef Eigen::Matrix<pinocchio::value_type, 3, 1>
Vector3;
99 static RbPrmLimbPtr_t create(
100 const pinocchio::JointPtr_t limb,
const std::string& effectorName,
101 const fcl::Vec3f& offset,
const fcl::Vec3f& limbOffset,
102 const fcl::Vec3f& normal,
const double x,
const double y,
105 bool disableEndEffectorCollision =
false,
bool grasps =
false,
106 const std::string& kinematicsConstraintsPath = std::string(),
107 const double kinematicConstraintsMinDistance = 0.);
109 static RbPrmLimbPtr_t create(
110 const pinocchio::DevicePtr_t device, std::ifstream& fileStream,
111 const bool loadValues =
true,
113 bool disableEndEffectorCollision =
false,
bool grasps =
false);
119 pinocchio::Transform3f octreeRoot()
const;
141 RbPrmLimb(
const pinocchio::JointPtr_t& limb,
const std::string& effectorName,
142 const fcl::Vec3f& offset,
const fcl::Vec3f& limbOffset,
143 const fcl::Vec3f& normal,
const double x,
const double y,
146 bool disableEndEffectorCollision =
false,
bool grasps =
false,
147 const std::string& kinematicsConstraintsPath = std::string(),
148 const double kinematicConstraintsMinDistance = 0.);
150 RbPrmLimb(
const pinocchio::DevicePtr_t device, std::ifstream& fileStream,
151 const bool loadValues,
153 bool disableEndEffectorCollision =
false,
bool grasps =
false);
157 void init(
const RbPrmLimbWkPtr_t& weakPtr);
160 RbPrmLimbWkPtr_t weakPtr_;
164 std::ofstream& dbFile);
169 #endif // HPP_RBPRM_LIMB_HH Eigen::Matrix< pinocchio::value_type, 3, 1 > Vector3
Definition: rbprm-limb.hh:49
sampling::heuristic evaluate_
Definition: rbprm-limb.hh:133
#define HPP_RBPRM_DLLAPI
Definition: config.hh:64
std::map< std::string, const rbprm::RbPrmLimbPtr_t > T_Limb
Definition: rbprm-limb.hh:43
Definition: sample-db.hh:90
ContactType
Definition: rbprm-limb.hh:30
const ContactType contactType_
Definition: rbprm-limb.hh:132
const fcl::Vec3f offset_
Definition: rbprm-limb.hh:126
Definition: algorithm.hh:26
Definition: rbprm-limb.hh:31
const double x_
Definition: rbprm-limb.hh:130
const pinocchio::JointPtr_t limb_
Definition: rbprm-limb.hh:122
Definition: rbprm-limb.hh:51
double(* heuristic)(const sampling::Sample &sample, const Eigen::Vector3d &direction, const Eigen::Vector3d &normal, const HeuristicParam ¶ms)
Definition: heuristic.hh:38
Eigen::Matrix< pinocchio::value_type, Eigen::Dynamic, 1 > VectorX
Definition: rbprm-limb.hh:48
shared_ptr< RbPrmLimb > RbPrmLimbPtr_t
Definition: rbprm-limb.hh:41
const bool disableEndEffectorCollision_
Definition: rbprm-limb.hh:135
Eigen::Matrix< pinocchio::value_type, Eigen::Dynamic, Eigen::Dynamic > MatrixXX
Definition: rbprm-limb.hh:46
fcl::Vec3f effectorReferencePosition_
Definition: rbprm-limb.hh:137
const fcl::Vec3f limbOffset_
Definition: rbprm-limb.hh:128
HPP_RBPRM_DLLAPI bool saveLimbInfoAndDatabase(const RbPrmLimbPtr_t limb, std::ofstream &dbFile)
const fcl::Vec3f normal_
Definition: rbprm-limb.hh:129
HPP_PREDEF_CLASS(RbPrmFullBody)
Eigen::Matrix< pinocchio::value_type, Eigen::Dynamic, 3 > MatrixX3
Definition: rbprm-limb.hh:47
boost::function< double(const SampleDB &sampleDB, const sampling::Sample &sample)> evaluate
Definition: sample-db.hh:78
std::pair< MatrixXX, MatrixXX > kinematicConstraints_
Definition: rbprm-limb.hh:138
sampling::SampleDB sampleContainer_
Definition: rbprm-limb.hh:134
Definition: rbprm-limb.hh:33
const double y_
Definition: rbprm-limb.hh:131
Definition: rbprm-limb.hh:32
T_Limb::const_iterator CIT_Limb
Definition: rbprm-limb.hh:44
const bool grasps_
Definition: rbprm-limb.hh:136
const fcl::Matrix3f effectorDefaultRotation_
Definition: rbprm-limb.hh:125
const pinocchio::Frame effector_
Definition: rbprm-limb.hh:123