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;
76 double sizeFootx,
double sizeFooty,
double m,
double mu,
95 size_type numberOfContacts_;
Definition: rbprm-node.hh:22
RbprmNode(const ConfigurationPtr_t &configuration)
Definition: rbprm-node.hh:28
fcl::Vec3f getNormal()
Definition: rbprm-node.hh:36
Vector6 geth()
Definition: rbprm-node.hh:69
Matrix6X getIPhat()
Definition: rbprm-node.hh:57
void setG(Matrix6X G)
Definition: rbprm-node.hh:59
void normal(double x, double y, double z)
Definition: rbprm-node.hh:38
void collisionReport(RbprmValidationReportPtr_t report)
Definition: rbprm-node.hh:47
void normal(fcl::Vec3f n)
Definition: rbprm-node.hh:43
Matrix63 getH()
Definition: rbprm-node.hh:65
RbprmNode(const ConfigurationPtr_t &configuration, ConnectedComponentPtr_t connectedComponent)
Definition: rbprm-node.hh:32
Eigen::Quaterniond getQuaternion()
void setNumberOfContacts(size_type n)
Definition: rbprm-node.hh:71
void setH(Matrix63 H)
Definition: rbprm-node.hh:63
void seth(Vector6 h)
Definition: rbprm-node.hh:67
RbprmValidationReportPtr_t getReport()
Definition: rbprm-node.hh:45
void chooseBestContactSurface(ValidationReportPtr_t report, hpp::pinocchio::RbPrmDevicePtr_t device)
void fillNodeMatrices(ValidationReportPtr_t report, bool rectangularContact, double sizeFootx, double sizeFooty, double m, double mu, pinocchio::RbPrmDevicePtr_t device)
MatrixXX getV()
Definition: rbprm-node.hh:53
size_type getNumberOfContacts()
Definition: rbprm-node.hh:73
void setIPHat(Matrix6X m)
Definition: rbprm-node.hh:55
void setV(MatrixXX V)
Definition: rbprm-node.hh:51
Matrix6X getG()
Definition: rbprm-node.hh:61
centroidal_dynamics::MatrixXX MatrixXX
Definition: rbprm-node.hh:18
centroidal_dynamics::Matrix63 Matrix63
Definition: rbprm-node.hh:20
shared_ptr< RbprmValidationReport > RbprmValidationReportPtr_t
Definition: rbprm-validation-report.hh:29
centroidal_dynamics::Vector6 Vector6
Definition: rbprm-node.hh:21
RbprmNode * RbprmNodePtr_t
Definition: rbprm-node.hh:16
HPP_PREDEF_CLASS(RbprmNode)
centroidal_dynamics::Matrix6X Matrix6X
Definition: rbprm-node.hh:19
shared_ptr< RbPrmDevice > RbPrmDevicePtr_t
Definition: dynamic-validation.hh:27
Definition: algorithm.hh:26