hpp-rbprm  4.10.0
Implementation of RB-PRM planner using hpp.
stability.hh
Go to the documentation of this file.
1 //
2 // Copyright (c) 2014 CNRS
3 // Authors: Steve Tonneau (steve.tonneau@laas.fr)
4 //
5 // This file is part of hpp-rbprm.
6 // hpp-rbprm is free software: you can redistribute it
7 // and/or modify it under the terms of the GNU Lesser General Public
8 // License as published by the Free Software Foundation, either version
9 // 3 of the License, or (at your option) any later version.
10 //
11 // hpp-rbprm is distributed in the hope that it will be
12 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
13 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
14 // General Lesser Public License for more details. You should have
15 // received a copy of the GNU Lesser General Public License along with
16 // hpp-core If not, see
17 // <http://www.gnu.org/licenses/>.
18 
19 #ifndef HPP_RBPRM_STABILITY_HH
20 # define HPP_RBPRM_STABILITY_HH
21 
22 #include <hpp/pinocchio/device.hh>
23 #include <hpp/rbprm/rbprm-state.hh>
25 #include <hpp/centroidal-dynamics/centroidal_dynamics.hh>
26 
27 #include <map>
28 #include <memory>
29 
30 namespace hpp {
31 
32  namespace rbprm {
33  namespace stability{
34 
35 
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;
38 
46 
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);
48 
49 
55  std::pair<MatrixXX, VectorX> ComputeCentroidalCone(const RbPrmFullBodyPtr_t fullbody, State& state, const core::value_type friction = 0.5);
56 
57  centroidal_dynamics::Equilibrium initLibrary(const RbPrmFullBodyPtr_t fullbody);
58 
59  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)throw(std::runtime_error);
60 
61  } // namespace stability
62 } // namespace rbprm
63 } // namespace hpp
64 #endif // HPP_RBPRM_STABILITY_HH
rbprm-fullbody.hh
hpp::rbprm::stability::setupLibrary
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)
hpp::rbprm::Vector3
Eigen::Matrix< pinocchio::value_type, 3, 1 > Vector3
Definition: rbprm-limb.hh:50
rbprm-state.hh
hpp
Definition: algorithm.hh:27
hpp::rbprm::stability::VectorX
Eigen::Matrix< pinocchio::value_type, Eigen::Dynamic, 1 > VectorX
Definition: stability.hh:37
hpp::rbprm::stability::MatrixXX
Eigen::Matrix< pinocchio::value_type, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > MatrixXX
Definition: stability.hh:36
hpp::rbprm::stability::initLibrary
centroidal_dynamics::Equilibrium initLibrary(const RbPrmFullBodyPtr_t fullbody)
hpp::rbprm::stability::IsStable
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)
hpp::rbprm::State
Definition: rbprm-state.hh:40
hpp::rbprm::RbPrmFullBodyPtr_t
boost::shared_ptr< RbPrmFullBody > RbPrmFullBodyPtr_t
Definition: kinematics_constraints.hh:12
hpp::rbprm::stability::ComputeCentroidalCone
std::pair< MatrixXX, VectorX > ComputeCentroidalCone(const RbPrmFullBodyPtr_t fullbody, State &state, const core::value_type friction=0.5)