1 #ifndef HPP_HEURISTIC_TOOLS_HH
2 #define HPP_HEURISTIC_TOOLS_HH
4 #include <hpp/core/path.hh>
5 #include <hpp/pinocchio/device.hh>
14 std::map<std::string, fcl::Vec3f>
33 const fcl::Vec3f& comPos,
const fcl::Vec3f& comSp,
34 const fcl::Vec3f& comAcc,
const std::string& sln,
35 const fcl::Transform3f& tf);
47 fcl::Vec3f
transform(
const fcl::Vec3f& p,
const fcl::Vec3f& tr,
48 const fcl::Matrix3f& ro);
55 Vec2D(
double xx,
double yy) :
x(xx),
y(yy) {}
68 bool contains(
const std::vector<T>& vect,
const T& val) {
70 for (
unsigned int i = 0; !found && (i < vect.size()); ++i) {
71 if (vect[i] == val) found =
true;
84 Plane(
double aa,
double bb,
double cc,
double dd)
85 :
a(aa),
b(bb),
c(cc),
d(dd) {}
104 const std::map<std::string, fcl::Vec3f>& contactPositions);
124 double groundThreshold);
Point center(CIT_Point pointsBegin, CIT_Point pointsEnd)
center compute the center using average method
bool operator==(const Vec2D &v1, const Vec2D &v2)
std::ostream & operator<<(std::ostream &out, const Vec2D &v)
std::vector< Vec2D > convexHull(std::vector< Vec2D > set)
double computeAngle(const Vec2D ¢er, const Vec2D &end1, const Vec2D &end2)
bool contains(const std::vector< T > &vect, const T &val)
Function to verify the existence of an element in a std::vector.
Definition: heuristic-tools.hh:68
bool operator!=(const Vec2D &v1, const Vec2D &v2)
Vec2D weightedCentroidConvex2D(const std::vector< Vec2D > &convexPolygon)
std::vector< Vec2D > computeSupportPolygon(const std::map< std::string, fcl::Vec3f > &contactPositions)
fcl::Vec3f transform(const fcl::Vec3f &p, const fcl::Vec3f &tr, const fcl::Matrix3f &ro)
void removeNonGroundContacts(std::map< std::string, fcl::Vec3f > &contacts, double groundThreshold)
Definition: algorithm.hh:26
Defines a parameters set for the ZMP-based heuristic.
Definition: heuristic-tools.hh:13
fcl::Transform3f tfWorldRoot_
Definition: heuristic-tools.hh:21
fcl::Vec3f comSpeed_
Definition: heuristic-tools.hh:18
HeuristicParam(const std::map< std::string, fcl::Vec3f > &cp, const fcl::Vec3f &comPos, const fcl::Vec3f &comSp, const fcl::Vec3f &comAcc, const std::string &sln, const fcl::Transform3f &tf)
core::PathConstPtr_t comPath_
Definition: heuristic-tools.hh:24
std::string sampleLimbName_
Definition: heuristic-tools.hh:20
fcl::Vec3f comPosition_
Definition: heuristic-tools.hh:17
std::map< std::string, fcl::Vec3f > contactPositions_
Definition: heuristic-tools.hh:15
double currentPathId_
Definition: heuristic-tools.hh:25
fcl::Vec3f limbReferenceOffset_
Definition: heuristic-tools.hh:28
fcl::Vec3f comAcceleration_
Definition: heuristic-tools.hh:19
HeuristicParam()
Definition: heuristic-tools.hh:31
HeuristicParam(const HeuristicParam &zhp)
HeuristicParam & operator=(const HeuristicParam &zhp)
Definition: heuristic-tools.hh:78
Plane()
Definition: heuristic-tools.hh:83
Plane & operator=(const Plane &pe)
double c
Definition: heuristic-tools.hh:81
double b
Definition: heuristic-tools.hh:80
double d
Definition: heuristic-tools.hh:82
Plane(const Plane &pe)
Definition: heuristic-tools.hh:86
Plane(double aa, double bb, double cc, double dd)
Definition: heuristic-tools.hh:84
double a
Definition: heuristic-tools.hh:79
Data structure to store 2-dimensional informations (2D vectors)
Definition: heuristic-tools.hh:51
double operator[](int idx) const
double & operator[](int idx)
Vec2D & operator=(const Vec2D &c)
double y
Definition: heuristic-tools.hh:53
double x
Definition: heuristic-tools.hh:52
static double euclideanDist(const Vec2D &v1, const Vec2D &v2)
Vec2D(double xx, double yy)
Definition: heuristic-tools.hh:55
Vec2D()
Definition: heuristic-tools.hh:54
Vec2D(const Vec2D &c2D)
Definition: heuristic-tools.hh:56