hpp-rbprm  4.10.1
Implementation of RB-PRM planner using hpp.
rbprm-limb.hh
Go to the documentation of this file.
1 //
2 // Copyright (c) 2014 CNRS
3 // Authors: Steve Tonneau (steve.tonneau@laas.fr)
4 //
5 // This file is part of hpp-rbprm.
6 // hpp-rbprm is free software: you can redistribute it
7 // and/or modify it under the terms of the GNU Lesser General Public
8 // License as published by the Free Software Foundation, either version
9 // 3 of the License, or (at your option) any later version.
10 //
11 // hpp-rbprm is distributed in the hope that it will be
12 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
13 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
14 // General Lesser Public License for more details. You should have
15 // received a copy of the GNU Lesser General Public License along with
16 // hpp-core If not, see
17 // <http://www.gnu.org/licenses/>.
18 
19 #ifndef HPP_RBPRM_LIMB_HH
20 #define HPP_RBPRM_LIMB_HH
21 
22 #include <hpp/rbprm/config.hh>
25 #include <hpp/pinocchio/device.hh>
26 
27 namespace hpp {
28 namespace rbprm {
29 
31  _6_DOF = 0, // Position and orientation are considered (surface contact)
32  _3_DOF = 1, // Only 3D position is considered (punctual contact)
34 };
35 
36 HPP_PREDEF_CLASS(RbPrmLimb);
37 
41 class RbPrmLimb;
42 typedef boost::shared_ptr<RbPrmLimb> RbPrmLimbPtr_t;
43 typedef std::map<std::string, const rbprm::RbPrmLimbPtr_t> T_Limb;
44 typedef T_Limb::const_iterator CIT_Limb;
45 typedef Eigen::Matrix<pinocchio::value_type, Eigen::Dynamic, Eigen::Dynamic> MatrixXX;
46 typedef Eigen::Matrix<pinocchio::value_type, Eigen::Dynamic, 3> MatrixX3;
47 typedef Eigen::Matrix<pinocchio::value_type, Eigen::Dynamic, 1> VectorX;
48 typedef Eigen::Matrix<pinocchio::value_type, 3, 1> Vector3;
49 
51  public:
69  /*static RbPrmLimbPtr_t create (const pinocchio::JointPtr_t limb, const fcl::Vec3f &offset,
70  const fcl::Vec3f &normal,const double x, const double y,
71  const std::size_t nbSamples, const sampling::heuristic evaluate = 0,
72  const double resolution = 0.1, ContactType contactType = _6_DOF);*/
73 
91  static RbPrmLimbPtr_t create(const pinocchio::JointPtr_t limb, const std::string& effectorName,
92  const fcl::Vec3f& offset, const fcl::Vec3f& limbOffset, const fcl::Vec3f& normal,
93  const double x, const double y, const std::size_t nbSamples,
94  const sampling::heuristic evaluate = 0, const double resolution = 0.1,
95  ContactType contactType = _6_DOF, bool disableEndEffectorCollision = false,
96  bool grasps = false, const std::string& kinematicsConstraintsPath = std::string(),
97  const double kinematicConstraintsMinDistance = 0.);
98 
99  static RbPrmLimbPtr_t create(const pinocchio::DevicePtr_t device, std::ifstream& fileStream,
100  const bool loadValues = true, const hpp::rbprm::sampling::heuristic evaluate = 0,
101  bool disableEndEffectorCollision = false, bool grasps = false);
102 
103  public:
104  ~RbPrmLimb();
105 
106  public:
107  pinocchio::Transform3f octreeRoot() const;
108 
109  public:
110  const pinocchio::JointPtr_t limb_;
111  const pinocchio::Frame effector_;
112  const fcl::Matrix3f effectorDefaultRotation_; // effector transform in rest pose
113  const fcl::Vec3f offset_; // effector location
114  const fcl::Vec3f limbOffset_; // offset of between the limb_ joint position and it's link
115  const fcl::Vec3f normal_; // effector normal for surface
116  const double x_; // half width
117  const double y_; // half length of contact surface
122  const bool grasps_;
124  std::pair<MatrixXX, MatrixXX> kinematicConstraints_;
125 
126  protected:
127  RbPrmLimb(const pinocchio::JointPtr_t& limb, const std::string& effectorName, const fcl::Vec3f& offset,
128  const fcl::Vec3f& limbOffset, const fcl::Vec3f& normal, const double x, const double y,
129  const std::size_t nbSamples, const sampling::heuristic evaluate, const double resolution,
130  ContactType contactType, bool disableEndEffectorCollision = false, bool grasps = false,
131  const std::string& kinematicsConstraintsPath = std::string(),
132  const double kinematicConstraintsMinDistance = 0.);
133 
134  RbPrmLimb(const pinocchio::DevicePtr_t device, std::ifstream& fileStream, const bool loadValues,
135  const hpp::rbprm::sampling::heuristic evaluate, bool disableEndEffectorCollision = false,
136  bool grasps = false);
140  void init(const RbPrmLimbWkPtr_t& weakPtr);
141 
142  private:
143  RbPrmLimbWkPtr_t weakPtr_;
144 }; // class RbPrmLimb
145 
146 HPP_RBPRM_DLLAPI bool saveLimbInfoAndDatabase(const RbPrmLimbPtr_t limb, std::ofstream& dbFile);
147 
148 } // namespace rbprm
149 } // namespace hpp
150 
151 #endif // HPP_RBPRM_LIMB_HH
hpp::rbprm::RbPrmLimb::y_
const double y_
Definition: rbprm-limb.hh:117
hpp::rbprm::RbPrmLimbPtr_t
boost::shared_ptr< RbPrmLimb > RbPrmLimbPtr_t
Definition: rbprm-limb.hh:41
hpp::rbprm::RbPrmLimb::limb_
const pinocchio::JointPtr_t limb_
Definition: rbprm-limb.hh:110
hpp::rbprm::HPP_PREDEF_CLASS
HPP_PREDEF_CLASS(RbPrmFullBody)
hpp::rbprm::Vector3
Eigen::Matrix< pinocchio::value_type, 3, 1 > Vector3
Definition: rbprm-limb.hh:48
hpp::rbprm::RbPrmLimb::sampleContainer_
sampling::SampleDB sampleContainer_
Definition: rbprm-limb.hh:120
hpp::rbprm::RbPrmLimb::contactType_
const ContactType contactType_
Definition: rbprm-limb.hh:118
hpp::rbprm::MatrixX3
Eigen::Matrix< pinocchio::value_type, Eigen::Dynamic, 3 > MatrixX3
Definition: rbprm-limb.hh:46
hpp::rbprm::CIT_Limb
T_Limb::const_iterator CIT_Limb
Definition: rbprm-limb.hh:44
hpp::rbprm::RbPrmLimb::evaluate_
sampling::heuristic evaluate_
Definition: rbprm-limb.hh:119
hpp::rbprm::sampling::evaluate
boost::function< double(const SampleDB &sampleDB, const sampling::Sample &sample)> evaluate
Definition: sample-db.hh:70
hpp::rbprm::VectorX
Eigen::Matrix< pinocchio::value_type, Eigen::Dynamic, 1 > VectorX
Definition: rbprm-limb.hh:47
hpp::rbprm::_6_DOF
@ _6_DOF
Definition: rbprm-limb.hh:31
hpp::rbprm::RbPrmLimb::grasps_
const bool grasps_
Definition: rbprm-limb.hh:122
hpp::rbprm::T_Limb
std::map< std::string, const rbprm::RbPrmLimbPtr_t > T_Limb
Definition: rbprm-limb.hh:43
hpp
Definition: algorithm.hh:27
hpp::rbprm::RbPrmLimb::offset_
const fcl::Vec3f offset_
Definition: rbprm-limb.hh:113
hpp::rbprm::RbPrmLimb::effectorReferencePosition_
fcl::Vec3f effectorReferencePosition_
Definition: rbprm-limb.hh:123
hpp::rbprm::ContactType
ContactType
Definition: rbprm-limb.hh:30
hpp::rbprm::RbPrmLimb::normal_
const fcl::Vec3f normal_
Definition: rbprm-limb.hh:115
hpp::rbprm::sampling::heuristic
double(* heuristic)(const sampling::Sample &sample, const Eigen::Vector3d &direction, const Eigen::Vector3d &normal, const HeuristicParam &params)
Definition: heuristic.hh:39
hpp::rbprm::saveLimbInfoAndDatabase
HPP_RBPRM_DLLAPI bool saveLimbInfoAndDatabase(const RbPrmLimbPtr_t limb, std::ofstream &dbFile)
hpp::rbprm::RbPrmLimb::x_
const double x_
Definition: rbprm-limb.hh:116
sample-db.hh
hpp::rbprm::sampling::SampleDB
Definition: sample-db.hh:81
hpp::rbprm::RbPrmLimb::kinematicConstraints_
std::pair< MatrixXX, MatrixXX > kinematicConstraints_
Definition: rbprm-limb.hh:124
hpp::rbprm::RbPrmLimb::effector_
const pinocchio::Frame effector_
Definition: rbprm-limb.hh:111
hpp::rbprm::RbPrmLimb::disableEndEffectorCollision_
const bool disableEndEffectorCollision_
Definition: rbprm-limb.hh:121
hpp::rbprm::RbPrmLimb::effectorDefaultRotation_
const fcl::Matrix3f effectorDefaultRotation_
Definition: rbprm-limb.hh:112
hpp::rbprm::_3_DOF
@ _3_DOF
Definition: rbprm-limb.hh:32
hpp::rbprm::RbPrmLimb::limbOffset_
const fcl::Vec3f limbOffset_
Definition: rbprm-limb.hh:114
heuristic.hh
hpp::rbprm::RbPrmLimb
Definition: rbprm-limb.hh:50
config.hh
hpp::rbprm::_UNDEFINED
@ _UNDEFINED
Definition: rbprm-limb.hh:33
hpp::rbprm::MatrixXX
Eigen::Matrix< pinocchio::value_type, Eigen::Dynamic, Eigen::Dynamic > MatrixXX
Definition: rbprm-limb.hh:45
HPP_RBPRM_DLLAPI
#define HPP_RBPRM_DLLAPI
Definition: config.hh:64