17 #ifndef HPP_RBPRM_SHOOTER_HH
18 # define HPP_RBPRM_SHOOTER_HH
23 # include <hpp/core/problem-solver.hh>
24 # include <hpp/pinocchio/joint.hh>
26 # include <hpp/core/configuration-shooter.hh>
38 typedef boost::shared_ptr <RbPrmShooter>
40 typedef hpp::core::Container <hpp::core::AffordanceObjects_t>
affMap_t;
66 const core::ObjectStdVector_t &geometries,
68 const std::vector<std::string>& filter = std::vector<std::string>(),
69 const std::map<std::string, std::vector<std::string> >& affFilters = std::map<std::string, std::vector<std::string> >(),
70 const std::size_t shootLimit = 10000,
71 const std::size_t displacementLimit = 100);
79 void BoundSO3(
const std::vector<double>& limitszyx);
81 void sampleExtraDOF(
bool sampleExtraDOF);
98 const core::ObjectStdVector_t &geometries,
100 const std::vector<std::string>& filter,
101 const std::map<std::string, std::vector<std::string> >& affFilters,
102 const std::size_t shootLimit = 10000,
103 const std::size_t displacementLimit = 100);
107 virtual void impl_shoot (core::Configuration_t& q)
const;
110 void InitWeightedTriangles (
const core::ObjectStdVector_t &geometries);
113 void randConfigAtPos(
const pinocchio::RbPrmDevicePtr_t robot,
const std::vector<double>& eulerSo3, core::Configuration_t& config,
const fcl::Vec3f p)
const;
117 std::vector<double> weights_;
118 std::vector<T_TriangleNormal> triangles_;
121 core::configurationShooter::UniformPtr_t uniformShooter_;
122 double ratioWeighted_;
123 RbPrmShooterWkPtr_t weak_;
125 std::vector<double> eulerSo3_;
130 #endif // HPP_RBPRM_SHOOTER_HH