1 #ifndef HPP_RBPRM_NODE_HH 2 #define HPP_RBPRM_NODE_HH 4 #include <hpp/centroidal-dynamics/centroidal_dynamics.hh> 5 #include <hpp/core/node.hh> 28 RbprmNode(
const ConfigurationPtr_t& configuration) : Node(configuration) {}
33 ConnectedComponentPtr_t connectedComponent)
34 : Node(configuration, connectedComponent) {}
38 void normal(
double x,
double y,
double z) {
39 fcl::Vec3f n(x, y, z);
43 void normal(fcl::Vec3f n) { normal_ = n; }
48 collisionReport_ = report;
51 void setV(MatrixXX V) { V_ = V; }
53 MatrixXX
getV() {
return V_; }
59 void setG(Matrix6X G) { G_ = G; }
61 Matrix6X
getG() {
return G_; }
63 void setH(Matrix63 H) { H_ = H; }
65 Matrix63
getH() {
return H_; }
67 void seth(Vector6 h) { h_ = h; }
69 Vector6
geth() {
return h_; }
75 void fillNodeMatrices(ValidationReportPtr_t report,
bool rectangularContact,
76 double sizeFootx,
double sizeFooty,
double m,
double mu,
79 void chooseBestContactSurface(ValidationReportPtr_t report,
82 Eigen::Quaterniond getQuaternion();
95 size_type numberOfContacts_;
102 #endif // HPP_RBPRM_NODE_HH Vector6 geth()
Definition: rbprm-node.hh:69
void collisionReport(RbprmValidationReportPtr_t report)
Definition: rbprm-node.hh:47
void setG(Matrix6X G)
Definition: rbprm-node.hh:59
fcl::Vec3f getNormal()
Definition: rbprm-node.hh:36
Definition: algorithm.hh:26
Matrix63 getH()
Definition: rbprm-node.hh:65
RbprmNode * RbprmNodePtr_t
Definition: rbprm-node.hh:16
void setV(MatrixXX V)
Definition: rbprm-node.hh:51
void setH(Matrix63 H)
Definition: rbprm-node.hh:63
RbprmValidationReportPtr_t getReport()
Definition: rbprm-node.hh:45
Matrix6X getG()
Definition: rbprm-node.hh:61
Definition: rbprm-node.hh:22
centroidal_dynamics::MatrixXX MatrixXX
Definition: rbprm-node.hh:18
MatrixXX getV()
Definition: rbprm-node.hh:53
size_type getNumberOfContacts()
Definition: rbprm-node.hh:73
centroidal_dynamics::Matrix63 Matrix63
Definition: rbprm-node.hh:20
void setNumberOfContacts(size_type n)
Definition: rbprm-node.hh:71
shared_ptr< RbPrmDevice > RbPrmDevicePtr_t
Definition: dynamic-validation.hh:27
HPP_PREDEF_CLASS(RbPrmDevice)
void normal(double x, double y, double z)
Definition: rbprm-node.hh:38
Matrix6X getIPhat()
Definition: rbprm-node.hh:57
void setIPHat(Matrix6X m)
Definition: rbprm-node.hh:55
RbprmNode(const ConfigurationPtr_t &configuration)
Definition: rbprm-node.hh:28
shared_ptr< RbprmValidationReport > RbprmValidationReportPtr_t
Definition: rbprm-validation-report.hh:29
centroidal_dynamics::Matrix6X Matrix6X
Definition: rbprm-node.hh:19
RbprmNode(const ConfigurationPtr_t &configuration, ConnectedComponentPtr_t connectedComponent)
Definition: rbprm-node.hh:32
void normal(fcl::Vec3f n)
Definition: rbprm-node.hh:43
centroidal_dynamics::Vector6 Vector6
Definition: rbprm-node.hh:21
void seth(Vector6 h)
Definition: rbprm-node.hh:67