19 #ifndef HPP_RBPRM_FULLBODY_HH 20 #define HPP_RBPRM_FULLBODY_HH 24 #include <hpp/pinocchio/device.hh> 26 #include <hpp/core/collision-validation.hh> 27 #include <hpp/core/problem-solver.hh> 36 using core::size_type;
47 typedef hpp::core::Container<hpp::core::AffordanceObjects_t>
affMap_t;
52 static RbPrmFullBodyPtr_t create(
const pinocchio::DevicePtr_t& device);
78 void AddLimb(
const std::string&
id,
const std::string& name,
const std::string& effectorName,
79 const fcl::Vec3f& offset,
const fcl::Vec3f& limbOffset,
const fcl::Vec3f& normal,
const double x,
80 const double y,
const core::ObjectStdVector_t& collisionObjects,
const std::size_t nbSamples,
81 const std::string&
heuristic =
"static",
const double resolution = 0.03,
82 ContactType contactType =
_6_DOF,
const bool disableEffectorCollision =
false,
const bool grasp =
false,
83 const std::string& kinematicConstraintsPath = std::string(),
const double kinematicConstraintsMin = 0.);
97 void AddLimb(
const std::string& database,
const std::string&
id,
const core::ObjectStdVector_t& collisionObjects,
98 const std::string& heuristicName,
const bool loadValues,
const bool disableEffectorCollision =
false,
99 const bool grasp =
false);
109 void AddNonContactingLimb(
const std::string&
id,
const std::string& name,
const std::string& effectorName,
110 const hpp::core::ObjectStdVector_t& collisionObjects,
const std::size_t nbSamples);
120 typedef std::map<std::string, std::vector<std::string> >
T_LimbGroup;
129 return limbcollisionValidations_;
137 void referenceConfig(pinocchio::Configuration_t referenceConfig);
139 void postureWeights(pinocchio::Configuration_t postureWeights);
142 usePosturalTaskContactCreation_ = usePosturalTaskContactCreation;
144 bool addEffectorTrajectory(
const size_t pathId,
const std::string& effectorName,
const bezier_Ptr& trajectory);
145 bool addEffectorTrajectory(
const size_t pathId,
const std::string& effectorName,
146 const std::vector<bezier_Ptr>& trajectories);
147 bool getEffectorsTrajectories(
const size_t pathId, EffectorTrajectoriesMap_t& result);
148 bool getEffectorTrajectory(
const size_t pathId,
const std::string& effectorName, std::vector<bezier_Ptr>& result);
149 bool toggleNonContactingLimb(std::string name);
152 core::CollisionValidationPtr_t collisionValidation_;
153 std::map<std::string, core::CollisionValidationPtr_t> limbcollisionValidations_;
156 T_LimbGroup limbGroups_;
158 bool staticStability_;
160 pinocchio::Configuration_t reference_;
161 pinocchio::Configuration_t postureWeights_;
162 bool usePosturalTaskContactCreation_;
164 std::map<size_t, EffectorTrajectoriesMap_t>
165 effectorsTrajectoriesMaps_;
169 const hpp::core::ObjectStdVector_t& collisionObjects,
const bool disableEffectorCollision,
170 const bool nonContactingLimb =
false);
178 void init(
const RbPrmFullBodyWkPtr_t& weakPtr);
181 RbPrmFullBodyWkPtr_t weakPtr_;
187 #endif // HPP_RBPRM_DEVICE_HH std::map< std::string, std::vector< bezier_Ptr > > EffectorTrajectoriesMap_t
Definition: rbprm-fullbody.hh:48
hpp::core::Container< hpp::core::AffordanceObjects_t > affMap_t
Definition: rbprm-fullbody.hh:47
std::shared_ptr< RbPrmFullBody > RbPrmFullBodyPtr_t
Definition: kinematics_constraints.hh:12
#define HPP_RBPRM_DLLAPI
Definition: config.hh:64
std::map< std::string, const rbprm::RbPrmLimbPtr_t > T_Limb
Definition: rbprm-limb.hh:43
ContactType
Definition: rbprm-limb.hh:30
Definition: algorithm.hh:27
Definition: rbprm-limb.hh:31
const rbprm::T_Limb & GetNonContactingLimbs()
Definition: rbprm-fullbody.hh:125
double(* heuristic)(const sampling::Sample &sample, const Eigen::Vector3d &direction, const Eigen::Vector3d &normal, const HeuristicParam ¶ms)
Definition: heuristic.hh:39
const core::CollisionValidationPtr_t & GetCollisionValidation()
Definition: rbprm-fullbody.hh:127
std::map< std::string, std::vector< std::string > > T_LimbGroup
Definition: rbprm-fullbody.hh:120
void staticStability(bool staticStability)
Definition: rbprm-fullbody.hh:132
void usePosturalTaskContactCreation(bool usePosturalTaskContactCreation)
Definition: rbprm-fullbody.hh:141
HPP_PREDEF_CLASS(RbPrmFullBody)
bool staticStability() const
Definition: rbprm-fullbody.hh:133
double getFriction() const
Definition: rbprm-fullbody.hh:134
Definition: rbprm-fullbody.hh:50
pinocchio::Configuration_t postureWeights()
Definition: rbprm-fullbody.hh:138
void setFriction(double mu)
Definition: rbprm-fullbody.hh:135
const T_LimbGroup & GetGroups()
Definition: rbprm-fullbody.hh:126
Definition: heuristic.hh:45
const pinocchio::DevicePtr_t device_
Definition: rbprm-fullbody.hh:131
const rbprm::T_Limb & GetLimbs()
Definition: rbprm-fullbody.hh:123
pinocchio::Configuration_t referenceConfig()
Definition: rbprm-fullbody.hh:136
bool usePosturalTaskContactCreation()
Definition: rbprm-fullbody.hh:140
std::shared_ptr< bezier_t > bezier_Ptr
Definition: bezier-path.hh:31
const std::map< std::string, core::CollisionValidationPtr_t > & GetLimbCollisionValidation()
Definition: rbprm-fullbody.hh:128
std::shared_ptr< RbPrmLimb > RbPrmLimbPtr_t
Definition: rbprm-limb.hh:41