17 #ifndef HPP_RBPRM_SHOOTER_HH
18 #define HPP_RBPRM_SHOOTER_HH
20 #include <hpp/core/problem-solver.hh>
21 #include <hpp/pinocchio/joint.hh>
26 #include <hpp/core/configuration-shooter.hh>
37 typedef hpp::core::Container<hpp::core::AffordanceObjects_t>
affMap_t;
68 const core::ObjectStdVector_t& geometries,
const affMap_t& affordances,
69 const std::vector<std::string>& filter = std::vector<std::string>(),
70 const std::map<std::string, std::vector<std::string> >& affFilters =
71 std::map<std::string, std::vector<std::string> >(),
72 const std::size_t shootLimit = 10000,
73 const std::size_t displacementLimit = 100);
82 void BoundSO3(
const std::vector<double>& limitszyx);
100 const core::ObjectStdVector_t& geometries,
const affMap_t& affordances,
101 const std::vector<std::string>& filter,
102 const std::map<std::string, std::vector<std::string> >& affFilters,
103 const std::size_t shootLimit = 10000,
104 const std::size_t displacementLimit = 100);
111 void InitWeightedTriangles(
const core::ObjectStdVector_t& geometries);
115 const std::vector<double>& eulerSo3,
116 core::Configuration_t& config,
const fcl::Vec3f p)
const;
119 std::vector<double> weights_;
120 std::vector<T_TriangleNormal> triangles_;
123 core::configurationShooter::UniformPtr_t uniformShooter_;
124 double ratioWeighted_;
125 RbPrmShooterWkPtr_t weak_;
127 std::vector<double> eulerSo3_;
Definition: rbprm-shooter.hh:42
const std::vector< std::string > filter_
Definition: rbprm-shooter.hh:94
virtual void impl_shoot(core::Configuration_t &q) const
std::pair< fcl::Vec3f, TrianglePoints > T_TriangleNormal
Definition: rbprm-shooter.hh:89
RbPrmShooter(const pinocchio::RbPrmDevicePtr_t &robot, const core::ObjectStdVector_t &geometries, const affMap_t &affordances, const std::vector< std::string > &filter, const std::map< std::string, std::vector< std::string > > &affFilters, const std::size_t shootLimit=10000, const std::size_t displacementLimit=100)
Note that translation joints have to be bounded.
void BoundSO3(const std::vector< double > &limitszyx)
const std::size_t displacementLimit_
Definition: rbprm-shooter.hh:93
void sampleExtraDOF(bool sampleExtraDOF)
const std::size_t shootLimit_
Definition: rbprm-shooter.hh:92
static HPP_RBPRM_DLLAPI RbPrmShooterPtr_t create(const pinocchio::RbPrmDevicePtr_t &robot, const core::ObjectStdVector_t &geometries, const affMap_t &affordances, const std::vector< std::string > &filter=std::vector< std::string >(), const std::map< std::string, std::vector< std::string > > &affFilters=std::map< std::string, std::vector< std::string > >(), const std::size_t shootLimit=10000, const std::size_t displacementLimit=100)
void ratioWeighted(double ratio)
Definition: rbprm-shooter.hh:86
void init(const RbPrmShooterPtr_t &self)
#define HPP_RBPRM_DLLAPI
Definition: config.hh:64
shared_ptr< RbPrmDevice > RbPrmDevicePtr_t
Definition: dynamic-validation.hh:27
hpp::core::Container< hpp::core::AffordanceObjects_t > affMap_t
Definition: rbprm-fullbody.hh:47
HPP_PREDEF_CLASS(RbPrmFullBody)
shared_ptr< RbPrmValidation > RbPrmValidationPtr_t
Definition: rbprm-validation.hh:34
shared_ptr< RbPrmShooter > RbPrmShooterPtr_t
Definition: rbprm-shooter.hh:36
Definition: algorithm.hh:26
Definition: rbprm-shooter.hh:32
fcl::Vec3f p1
Definition: rbprm-shooter.hh:33
fcl::Vec3f p2
Definition: rbprm-shooter.hh:33
fcl::Vec3f p3
Definition: rbprm-shooter.hh:33