hpp-rbprm
4.10.1
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>
28 RbprmNode(
const ConfigurationPtr_t& configuration) : Node(configuration) {}
32 RbprmNode(
const ConfigurationPtr_t& configuration, ConnectedComponentPtr_t connectedComponent)
33 : Node(configuration, connectedComponent) {}
37 void normal(
double x,
double y,
double z) {
38 fcl::Vec3f n(x, y, z);
42 void normal(fcl::Vec3f n) { normal_ = n; }
72 void fillNodeMatrices(ValidationReportPtr_t report,
bool rectangularContact,
double sizeFootx,
double sizeFooty,
77 Eigen::Quaterniond getQuaternion();
90 size_type numberOfContacts_;
97 #endif // HPP_RBPRM_NODE_HH
void setV(MatrixXX V)
Definition: rbprm-node.hh:48
void setH(Matrix63 H)
Definition: rbprm-node.hh:60
centroidal_dynamics::Matrix6X Matrix6X
Definition: rbprm-node.hh:19
void normal(fcl::Vec3f n)
Definition: rbprm-node.hh:42
void seth(Vector6 h)
Definition: rbprm-node.hh:64
Definition: rbprm-node.hh:22
centroidal_dynamics::MatrixXX MatrixXX
Definition: rbprm-node.hh:18
MatrixXX getV()
Definition: rbprm-node.hh:50
fcl::Vec3f getNormal()
Definition: rbprm-node.hh:35
RbprmNode(const ConfigurationPtr_t &configuration)
Definition: rbprm-node.hh:28
centroidal_dynamics::Matrix63 Matrix63
Definition: rbprm-node.hh:20
RbprmNode(const ConfigurationPtr_t &configuration, ConnectedComponentPtr_t connectedComponent)
Definition: rbprm-node.hh:32
Matrix6X getG()
Definition: rbprm-node.hh:58
Definition: algorithm.hh:27
RbprmNode * RbprmNodePtr_t
Definition: rbprm-node.hh:16
void collisionReport(RbprmValidationReportPtr_t report)
Definition: rbprm-node.hh:46
HPP_PREDEF_CLASS(RbprmNode)
Matrix63 getH()
Definition: rbprm-node.hh:62
boost::shared_ptr< RbPrmDevice > RbPrmDevicePtr_t
Definition: dynamic-validation.hh:27
void setNumberOfContacts(size_type n)
Definition: rbprm-node.hh:68
centroidal_dynamics::Vector6 Vector6
Definition: rbprm-node.hh:21
RbprmValidationReportPtr_t getReport()
Definition: rbprm-node.hh:44
void normal(double x, double y, double z)
Definition: rbprm-node.hh:37
Vector6 geth()
Definition: rbprm-node.hh:66
boost::shared_ptr< RbprmValidationReport > RbprmValidationReportPtr_t
Definition: rbprm-validation-report.hh:29
void setG(Matrix6X G)
Definition: rbprm-node.hh:56
Matrix6X getIPhat()
Definition: rbprm-node.hh:54
size_type getNumberOfContacts()
Definition: rbprm-node.hh:70
void setIPHat(Matrix6X m)
Definition: rbprm-node.hh:52