class
LinearizedFrictionConeLinearizedFrictionCone computes the polyhedral approximation of the friction cone.
A point contact remains fixed with respect the environment if the contact force lies in a cone described by
where is the contact force, is the vector normal to the contact surface. is the tangential force to the contact surface and is the friction parameter. The LinearizedFrictionCone aims to compute the polyhedral approximation of by spitting the base of the cone into slices.
Public functions
-
auto initialize(std::weak_ptr<const ParametersHandler::
IParametersHandler> handler) -> bool - Initialize the continuous algebraic riccati equation solver.
- auto getA() const -> Eigen::Ref<const Eigen::MatrixXd>
- Get the matrix A.
- auto getB() const -> Eigen::Ref<const Eigen::VectorXd>
- Get the vector B.
Function documentation
bool BipedalLocomotion:: Math:: LinearizedFrictionCone:: initialize(std::weak_ptr<const ParametersHandler:: IParametersHandler> handler)
Initialize the continuous algebraic riccati equation solver.
Parameters | |
---|---|
handler | pointer to the parameter handler. |
Returns | true in case of success/false otherwise. |
Eigen::Ref<const Eigen::MatrixXd> BipedalLocomotion:: Math:: LinearizedFrictionCone:: getA() const
Get the matrix A.
Returns | the matrix A. |
---|
Eigen::Ref<const Eigen::VectorXd> BipedalLocomotion:: Math:: LinearizedFrictionCone:: getB() const
Get the vector B.
Returns | the matrix B.. |
---|