19 #ifndef HPP_RBPRM_FULLBODY_HH 20 #define HPP_RBPRM_FULLBODY_HH 22 #include <hpp/core/collision-validation.hh> 23 #include <hpp/core/problem-solver.hh> 24 #include <hpp/pinocchio/device.hh> 36 using core::size_type;
47 typedef hpp::core::Container<hpp::core::AffordanceObjects_t>
affMap_t;
48 typedef std::map<std::string, std::vector<bezier_Ptr> >
53 static RbPrmFullBodyPtr_t create(
const pinocchio::DevicePtr_t& device);
83 void AddLimb(
const std::string&
id,
const std::string& name,
84 const std::string& effectorName,
const fcl::Vec3f& offset,
85 const fcl::Vec3f& limbOffset,
const fcl::Vec3f& normal,
86 const double x,
const double y,
87 const core::ObjectStdVector_t& collisionObjects,
88 const std::size_t nbSamples,
91 const bool disableEffectorCollision =
false,
92 const bool grasp =
false,
93 const std::string& kinematicConstraintsPath = std::string(),
94 const double kinematicConstraintsMin = 0.);
111 void AddLimb(
const std::string& database,
const std::string&
id,
112 const core::ObjectStdVector_t& collisionObjects,
113 const std::string& heuristicName,
const bool loadValues,
114 const bool disableEffectorCollision =
false,
115 const bool grasp =
false);
126 void AddNonContactingLimb(
127 const std::string&
id,
const std::string& name,
128 const std::string& effectorName,
129 const hpp::core::ObjectStdVector_t& collisionObjects,
130 const std::size_t nbSamples);
141 typedef std::map<std::string, std::vector<std::string> >
T_LimbGroup;
146 bool onlyWithContact =
false);
150 return collisionValidation_;
152 const std::map<std::string, core::CollisionValidationPtr_t>&
154 return limbcollisionValidations_;
158 staticStability_ = staticStability;
164 void referenceConfig(pinocchio::Configuration_t referenceConfig);
166 void postureWeights(pinocchio::Configuration_t postureWeights);
168 return usePosturalTaskContactCreation_;
171 usePosturalTaskContactCreation_ = usePosturalTaskContactCreation;
173 bool addEffectorTrajectory(
const size_t pathId,
174 const std::string& effectorName,
176 bool addEffectorTrajectory(
const size_t pathId,
177 const std::string& effectorName,
178 const std::vector<bezier_Ptr>& trajectories);
179 bool getEffectorsTrajectories(
const size_t pathId,
181 bool getEffectorTrajectory(
const size_t pathId,
182 const std::string& effectorName,
183 std::vector<bezier_Ptr>& result);
184 bool toggleNonContactingLimb(std::string name);
187 core::CollisionValidationPtr_t collisionValidation_;
188 std::map<std::string, core::CollisionValidationPtr_t>
189 limbcollisionValidations_;
193 T_LimbGroup limbGroups_;
195 bool staticStability_;
197 pinocchio::Configuration_t reference_;
198 pinocchio::Configuration_t postureWeights_;
200 bool usePosturalTaskContactCreation_;
204 std::map<size_t, EffectorTrajectoriesMap_t>
205 effectorsTrajectoriesMaps_;
210 const std::string& name,
211 const hpp::core::ObjectStdVector_t& collisionObjects,
212 const bool disableEffectorCollision,
213 const bool nonContactingLimb =
false);
221 void init(
const RbPrmFullBodyWkPtr_t& weakPtr);
224 RbPrmFullBodyWkPtr_t weakPtr_;
230 #endif // HPP_RBPRM_DEVICE_HH std::map< std::string, std::vector< bezier_Ptr > > EffectorTrajectoriesMap_t
Definition: rbprm-fullbody.hh:49
hpp::core::Container< hpp::core::AffordanceObjects_t > affMap_t
Definition: rbprm-fullbody.hh:47
#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:26
Definition: rbprm-limb.hh:31
const rbprm::T_Limb & GetNonContactingLimbs()
Definition: rbprm-fullbody.hh:147
double(* heuristic)(const sampling::Sample &sample, const Eigen::Vector3d &direction, const Eigen::Vector3d &normal, const HeuristicParam ¶ms)
Definition: heuristic.hh:38
const core::CollisionValidationPtr_t & GetCollisionValidation()
Definition: rbprm-fullbody.hh:149
std::map< std::string, std::vector< std::string > > T_LimbGroup
Definition: rbprm-fullbody.hh:141
void staticStability(bool staticStability)
Definition: rbprm-fullbody.hh:157
shared_ptr< RbPrmLimb > RbPrmLimbPtr_t
Definition: rbprm-limb.hh:41
void usePosturalTaskContactCreation(bool usePosturalTaskContactCreation)
Definition: rbprm-fullbody.hh:170
HPP_PREDEF_CLASS(RbPrmFullBody)
bool staticStability() const
Definition: rbprm-fullbody.hh:160
double getFriction() const
Definition: rbprm-fullbody.hh:161
Definition: rbprm-fullbody.hh:51
pinocchio::Configuration_t postureWeights()
Definition: rbprm-fullbody.hh:165
void setFriction(double mu)
Definition: rbprm-fullbody.hh:162
const T_LimbGroup & GetGroups()
Definition: rbprm-fullbody.hh:148
Definition: heuristic.hh:47
const pinocchio::DevicePtr_t device_
Definition: rbprm-fullbody.hh:156
const rbprm::T_Limb & GetLimbs()
Definition: rbprm-fullbody.hh:144
pinocchio::Configuration_t referenceConfig()
Definition: rbprm-fullbody.hh:163
bool usePosturalTaskContactCreation()
Definition: rbprm-fullbody.hh:167
shared_ptr< bezier_t > bezier_Ptr
Definition: bezier-path.hh:32
shared_ptr< RbPrmFullBody > RbPrmFullBodyPtr_t
Definition: kinematics_constraints.hh:11
const std::map< std::string, core::CollisionValidationPtr_t > & GetLimbCollisionValidation()
Definition: rbprm-fullbody.hh:153