hpp-rbprm
4.10.0
Implementation of RB-PRM planner using hpp.
|
Go to the documentation of this file.
19 #ifndef HPP_RBPRM_STABILITY_HH
20 # define HPP_RBPRM_STABILITY_HH
22 #include <hpp/pinocchio/device.hh>
25 #include <hpp/centroidal-dynamics/centroidal_dynamics.hh>
36 typedef Eigen::Matrix <pinocchio::value_type, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor>
MatrixXX;
37 typedef Eigen::Matrix <pinocchio::value_type, Eigen::Dynamic, 1>
VectorX;
47 double IsStable(
const RbPrmFullBodyPtr_t fullbody,
State& state, fcl::Vec3f acc = fcl::Vec3f(0,0,0), fcl::Vec3f com = fcl::Vec3f(0,0,0),
const centroidal_dynamics::EquilibriumAlgorithm = centroidal_dynamics::EQUILIBRIUM_ALGORITHM_DLP);
64 #endif // HPP_RBPRM_STABILITY_HH
centroidal_dynamics::Vector3 setupLibrary(const RbPrmFullBodyPtr_t fullbody, State &state, centroidal_dynamics::Equilibrium &sEq, centroidal_dynamics::EquilibriumAlgorithm &alg, core::value_type friction=0.6, const double feetX=0, const double feetY=0)
Eigen::Matrix< pinocchio::value_type, 3, 1 > Vector3
Definition: rbprm-limb.hh:50
Definition: algorithm.hh:27
Eigen::Matrix< pinocchio::value_type, Eigen::Dynamic, 1 > VectorX
Definition: stability.hh:37
Eigen::Matrix< pinocchio::value_type, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > MatrixXX
Definition: stability.hh:36
centroidal_dynamics::Equilibrium initLibrary(const RbPrmFullBodyPtr_t fullbody)
double IsStable(const RbPrmFullBodyPtr_t fullbody, State &state, fcl::Vec3f acc=fcl::Vec3f(0, 0, 0), fcl::Vec3f com=fcl::Vec3f(0, 0, 0), const centroidal_dynamics::EquilibriumAlgorithm=centroidal_dynamics::EQUILIBRIUM_ALGORITHM_DLP)
Definition: rbprm-state.hh:40
boost::shared_ptr< RbPrmFullBody > RbPrmFullBodyPtr_t
Definition: kinematics_constraints.hh:12
std::pair< MatrixXX, VectorX > ComputeCentroidalCone(const RbPrmFullBodyPtr_t fullbody, State &state, const core::value_type friction=0.5)