hpp-rbprm
4.10.0
Implementation of RB-PRM planner using hpp.
|
Go to the documentation of this file. 1 #ifndef HPP_RBPRM_NODE_HH
2 #define HPP_RBPRM_NODE_HH
4 #include <hpp/core/node.hh>
6 #include <hpp/centroidal-dynamics/centroidal_dynamics.hh>
30 RbprmNode (
const ConfigurationPtr_t& configuration):
37 ConnectedComponentPtr_t connectedComponent):
38 Node(configuration,connectedComponent)
45 void normal(
double x,
double y,
double z){
55 return collisionReport_;
59 collisionReport_ = report;
89 void fillNodeMatrices(ValidationReportPtr_t report,
bool rectangularContact,
double sizeFootx,
double sizeFooty,
double m,
double mu,
pinocchio::RbPrmDevicePtr_t device);
94 Eigen::Quaterniond getQuaternion();
106 size_type numberOfContacts_;
115 #endif // HPP_RBPRM_NODE_HH
void setV(MatrixXX V)
Definition: rbprm-node.hh:65
void setH(Matrix63 H)
Definition: rbprm-node.hh:77
centroidal_dynamics::Matrix6X Matrix6X
Definition: rbprm-node.hh:20
void normal(fcl::Vec3f n)
Definition: rbprm-node.hh:50
void seth(Vector6 h)
Definition: rbprm-node.hh:81
Definition: rbprm-node.hh:23
centroidal_dynamics::MatrixXX MatrixXX
Definition: rbprm-node.hh:19
MatrixXX getV()
Definition: rbprm-node.hh:67
fcl::Vec3f getNormal()
Definition: rbprm-node.hh:41
RbprmNode(const ConfigurationPtr_t &configuration)
Definition: rbprm-node.hh:30
centroidal_dynamics::Matrix63 Matrix63
Definition: rbprm-node.hh:21
RbprmNode(const ConfigurationPtr_t &configuration, ConnectedComponentPtr_t connectedComponent)
Definition: rbprm-node.hh:36
Matrix6X getG()
Definition: rbprm-node.hh:75
Definition: algorithm.hh:27
RbprmNode * RbprmNodePtr_t
Definition: rbprm-node.hh:17
void collisionReport(RbprmValidationReportPtr_t report)
Definition: rbprm-node.hh:58
HPP_PREDEF_CLASS(RbprmNode)
Matrix63 getH()
Definition: rbprm-node.hh:79
boost::shared_ptr< RbPrmDevice > RbPrmDevicePtr_t
Definition: dynamic-validation.hh:27
void setNumberOfContacts(size_type n)
Definition: rbprm-node.hh:85
centroidal_dynamics::Vector6 Vector6
Definition: rbprm-node.hh:22
RbprmValidationReportPtr_t getReport()
Definition: rbprm-node.hh:54
void normal(double x, double y, double z)
Definition: rbprm-node.hh:45
Vector6 geth()
Definition: rbprm-node.hh:83
boost::shared_ptr< RbprmValidationReport > RbprmValidationReportPtr_t
Definition: rbprm-validation-report.hh:29
void setG(Matrix6X G)
Definition: rbprm-node.hh:73
Matrix6X getIPhat()
Definition: rbprm-node.hh:71
size_type getNumberOfContacts()
Definition: rbprm-node.hh:87
void setIPHat(Matrix6X m)
Definition: rbprm-node.hh:69