1 |
|
|
#ifndef HPP_RBPRM_NODE_HH |
2 |
|
|
#define HPP_RBPRM_NODE_HH |
3 |
|
|
|
4 |
|
|
#include <hpp/centroidal-dynamics/centroidal_dynamics.hh> |
5 |
|
|
#include <hpp/core/node.hh> |
6 |
|
|
#include <hpp/rbprm/rbprm-validation-report.hh> |
7 |
|
|
|
8 |
|
|
namespace hpp { |
9 |
|
|
namespace pinocchio { |
10 |
|
|
class RbPrmDevice; // fwd declaration of rbprmDevice class |
11 |
|
|
typedef shared_ptr<RbPrmDevice> RbPrmDevicePtr_t; |
12 |
|
|
} // namespace pinocchio |
13 |
|
|
namespace core { |
14 |
|
|
|
15 |
|
|
HPP_PREDEF_CLASS(RbprmNode); |
16 |
|
|
typedef RbprmNode* RbprmNodePtr_t; |
17 |
|
|
|
18 |
|
|
typedef centroidal_dynamics::MatrixXX MatrixXX; |
19 |
|
|
typedef centroidal_dynamics::Matrix6X Matrix6X; |
20 |
|
|
typedef centroidal_dynamics::Matrix63 Matrix63; |
21 |
|
|
typedef centroidal_dynamics::Vector6 Vector6; |
22 |
|
|
class HPP_CORE_DLLAPI RbprmNode : public Node { |
23 |
|
|
public: |
24 |
|
|
/// Constructor |
25 |
|
|
/// \param configuration configuration stored in the new node |
26 |
|
|
/// \note A new connected component is created. For consistency, the |
27 |
|
|
/// new node is not registered in the connected component. |
28 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗
|
13519 |
RbprmNode(const ConfigurationPtr_t& configuration) : Node(configuration) {} |
29 |
|
|
/// Constructor |
30 |
|
|
/// \param configuration configuration stored in the new node |
31 |
|
|
/// \param connectedComponent connected component the node belongs to. |
32 |
|
|
RbprmNode(const ConfigurationPtr_t& configuration, |
33 |
|
|
ConnectedComponentPtr_t connectedComponent) |
34 |
|
|
: Node(configuration, connectedComponent) {} |
35 |
|
|
|
36 |
|
|
fcl::Vec3f getNormal() { return normal_; } |
37 |
|
|
|
38 |
|
|
void normal(double x, double y, double z) { |
39 |
|
|
fcl::Vec3f n(x, y, z); |
40 |
|
|
normal_ = n; |
41 |
|
|
} |
42 |
|
|
|
43 |
|
|
void normal(fcl::Vec3f n) { normal_ = n; } |
44 |
|
|
|
45 |
|
|
RbprmValidationReportPtr_t getReport() { return collisionReport_; } |
46 |
|
|
|
47 |
|
13520 |
void collisionReport(RbprmValidationReportPtr_t report) { |
48 |
|
13520 |
collisionReport_ = report; |
49 |
|
13520 |
} |
50 |
|
|
|
51 |
|
13520 |
void setV(MatrixXX V) { V_ = V; } |
52 |
|
|
|
53 |
|
|
MatrixXX getV() { return V_; } |
54 |
|
|
|
55 |
|
13520 |
void setIPHat(Matrix6X m) { IP_hat_ = m; } |
56 |
|
|
|
57 |
|
|
Matrix6X getIPhat() { return IP_hat_; } |
58 |
|
|
|
59 |
|
13520 |
void setG(Matrix6X G) { G_ = G; } |
60 |
|
|
|
61 |
|
13954 |
Matrix6X getG() { return G_; } |
62 |
|
|
|
63 |
|
13520 |
void setH(Matrix63 H) { H_ = H; } |
64 |
|
|
|
65 |
|
13971 |
Matrix63 getH() { return H_; } |
66 |
|
|
|
67 |
|
13520 |
void seth(Vector6 h) { h_ = h; } |
68 |
|
|
|
69 |
|
13971 |
Vector6 geth() { return h_; } |
70 |
|
|
|
71 |
|
13520 |
void setNumberOfContacts(size_type n) { numberOfContacts_ = n; } |
72 |
|
|
|
73 |
|
|
size_type getNumberOfContacts() { return numberOfContacts_; } |
74 |
|
|
|
75 |
|
|
void fillNodeMatrices(ValidationReportPtr_t report, bool rectangularContact, |
76 |
|
|
double sizeFootx, double sizeFooty, double m, double mu, |
77 |
|
|
pinocchio::RbPrmDevicePtr_t device); |
78 |
|
|
|
79 |
|
|
void chooseBestContactSurface(ValidationReportPtr_t report, |
80 |
|
|
hpp::pinocchio::RbPrmDevicePtr_t device); |
81 |
|
|
|
82 |
|
|
Eigen::Quaterniond getQuaternion(); |
83 |
|
|
|
84 |
|
|
private: |
85 |
|
|
fcl::Vec3f normal_; |
86 |
|
|
RbprmValidationReportPtr_t collisionReport_; |
87 |
|
|
// const polytope::ProjectedCone* giwc_; // useless now ? |
88 |
|
|
// polytope::T_rotation_t rotContact_; |
89 |
|
|
// polytope::vector_t posContact_; |
90 |
|
|
MatrixXX V_; |
91 |
|
|
Matrix6X IP_hat_; |
92 |
|
|
Matrix6X G_; // not initialized yet |
93 |
|
|
Matrix63 H_; |
94 |
|
|
Vector6 h_; |
95 |
|
|
size_type numberOfContacts_; |
96 |
|
|
|
97 |
|
|
}; // class |
98 |
|
|
|
99 |
|
|
} // namespace core |
100 |
|
|
} // namespace hpp |
101 |
|
|
|
102 |
|
|
#endif // HPP_RBPRM_NODE_HH |