#include <dynacom/dyna_com.hpp>
|
| DynaCoM () |
|
| DynaCoM (const DynaCoMSettings settings) |
|
void | initialize (const DynaCoMSettings settings) |
|
void | computeDynamics (const Eigen::VectorXd &posture, const Eigen::VectorXd &velocity, const Eigen::VectorXd &acceleration, const Eigen::Matrix< double, 6, 1 > &externalWrench=Eigen::Matrix< double, 6, 1 >::Zero(), bool flatHorizontalGround=true) |
|
void | computeNL (const double &w, const Eigen::VectorXd &posture, const Eigen::VectorXd &velocity, const Eigen::VectorXd &acceleration, const Eigen::Matrix< double, 6, 1 > &externalWrench=Eigen::Matrix< double, 6, 1 >::Zero(), bool flatHorizontalGround=true) |
|
void | computeNL (const double &w) |
|
void | addContact6d (const std::shared_ptr< Contact6D > &contact, const std::string &name, const bool active=true) |
|
void | removeContact6d (const std::string &name) |
|
void | activateContact6d (const std::string &name) |
|
void | deactivateContact6d (const std::string &name) |
|
void | distributeForce (const Eigen::Vector3d &groundCoMForce, const Eigen::Vector3d &groundCoMTorque, const Eigen::Vector3d &CoM) |
|
const Eigen::Vector3d & | getAMVariation () |
| Please call computeDynamics first. More...
|
|
const Eigen::Vector3d & | getCoM () |
|
const Eigen::Vector3d & | getVCoM () |
|
const Eigen::Vector3d & | getACoM () |
|
const Eigen::Vector3d & | getAM () |
|
const Eigen::Vector2d & | getCoP () |
|
const Eigen::Vector2d & | getNL () |
|
const Eigen::Vector3d & | getGroundCoMForce () |
|
const Eigen::Vector3d & | getGroundCoMTorque () |
|
const std::vector< std::string > & | getActiveContacts () |
|
const std::shared_ptr< Contact6D > & | getContact (std::string name) |
|
const DynaCoMSettings & | getSettings () |
|
const pinocchio::Model & | getModel () |
|
const pinocchio::Data & | getData () |
|
const Eigen::MatrixXd | uni_A () |
|
const Eigen::VectorXd | uni_b () |
|
const Eigen::MatrixXd | fri_A () |
|
const Eigen::VectorXd | fri_b () |
|
const Eigen::VectorXd | reg_A () |
|
const Eigen::VectorXd | reg_b () |
|
const Eigen::Matrix< double, 6, -1 > | NE_A () |
|
const Eigen::Matrix< double, 6, 1 > & | NE_b () |
|
const Eigen::VectorXd & | allForces () |
|
◆ DynaCoM() [1/2]
dynacom::DynaCoM::DynaCoM |
( |
| ) |
|
◆ DynaCoM() [2/2]
◆ activateContact6d()
void dynacom::DynaCoM::activateContact6d |
( |
const std::string & |
name | ) |
|
◆ addContact6d()
void dynacom::DynaCoM::addContact6d |
( |
const std::shared_ptr< Contact6D > & |
contact, |
|
|
const std::string & |
name, |
|
|
const bool |
active = true |
|
) |
| |
◆ allForces()
const Eigen::VectorXd& dynacom::DynaCoM::allForces |
( |
| ) |
|
|
inline |
◆ computeDynamics()
void dynacom::DynaCoM::computeDynamics |
( |
const Eigen::VectorXd & |
posture, |
|
|
const Eigen::VectorXd & |
velocity, |
|
|
const Eigen::VectorXd & |
acceleration, |
|
|
const Eigen::Matrix< double, 6, 1 > & |
externalWrench = Eigen::Matrix<double, 6, 1>::Zero() , |
|
|
bool |
flatHorizontalGround = true |
|
) |
| |
The external wrench is supposed to be expressed in the frame of the Center of mass.
The option flatHorizontalGround assumes that supporting contacts where previously defined.
TODO: In the case when flatHorizontalGround = True, still, we could remove the assumption of horizontal ground by including the lateral force produced by the lateral components of the groundNormalReaction.
For this we should know what is the direction normal to the ground. Then, we could change the flag name by bool flatGround
. The normal direction can be obtained from the feet frames (both are the same in a flatGround)
◆ computeNL() [1/2]
void dynacom::DynaCoM::computeNL |
( |
const double & |
w | ) |
|
In this function form, computeDynamics is supposed to have been called before.
◆ computeNL() [2/2]
void dynacom::DynaCoM::computeNL |
( |
const double & |
w, |
|
|
const Eigen::VectorXd & |
posture, |
|
|
const Eigen::VectorXd & |
velocity, |
|
|
const Eigen::VectorXd & |
acceleration, |
|
|
const Eigen::Matrix< double, 6, 1 > & |
externalWrench = Eigen::Matrix<double, 6, 1>::Zero() , |
|
|
bool |
flatHorizontalGround = true |
|
) |
| |
◆ deactivateContact6d()
void dynacom::DynaCoM::deactivateContact6d |
( |
const std::string & |
name | ) |
|
◆ distributeForce()
void dynacom::DynaCoM::distributeForce |
( |
const Eigen::Vector3d & |
groundCoMForce, |
|
|
const Eigen::Vector3d & |
groundCoMTorque, |
|
|
const Eigen::Vector3d & |
CoM |
|
) |
| |
Make sure that the data of the dynaCoM class has been updated to the correct robot posture before executing this distribution.
//@TODO: if the list of active contacts is empty, no force or torque can be applied. Manage such case. We change the arguments? we throw error? Check.
◆ fri_A()
const Eigen::MatrixXd dynacom::DynaCoM::fri_A |
( |
| ) |
|
|
inline |
◆ fri_b()
const Eigen::VectorXd dynacom::DynaCoM::fri_b |
( |
| ) |
|
|
inline |
◆ getACoM()
const Eigen::Vector3d& dynacom::DynaCoM::getACoM |
( |
| ) |
|
|
inline |
◆ getActiveContacts()
const std::vector<std::string>& dynacom::DynaCoM::getActiveContacts |
( |
| ) |
|
|
inline |
◆ getAM()
const Eigen::Vector3d& dynacom::DynaCoM::getAM |
( |
| ) |
|
|
inline |
◆ getAMVariation()
const Eigen::Vector3d& dynacom::DynaCoM::getAMVariation |
( |
| ) |
|
|
inline |
Please call computeDynamics first.
◆ getCoM()
const Eigen::Vector3d& dynacom::DynaCoM::getCoM |
( |
| ) |
|
|
inline |
◆ getContact()
const std::shared_ptr<Contact6D>& dynacom::DynaCoM::getContact |
( |
std::string |
name | ) |
|
|
inline |
◆ getCoP()
const Eigen::Vector2d& dynacom::DynaCoM::getCoP |
( |
| ) |
|
|
inline |
◆ getData()
const pinocchio::Data& dynacom::DynaCoM::getData |
( |
| ) |
|
|
inline |
◆ getGroundCoMForce()
const Eigen::Vector3d& dynacom::DynaCoM::getGroundCoMForce |
( |
| ) |
|
|
inline |
◆ getGroundCoMTorque()
const Eigen::Vector3d& dynacom::DynaCoM::getGroundCoMTorque |
( |
| ) |
|
|
inline |
◆ getModel()
const pinocchio::Model& dynacom::DynaCoM::getModel |
( |
| ) |
|
|
inline |
◆ getNL()
const Eigen::Vector2d& dynacom::DynaCoM::getNL |
( |
| ) |
|
|
inline |
◆ getSettings()
◆ getVCoM()
const Eigen::Vector3d& dynacom::DynaCoM::getVCoM |
( |
| ) |
|
|
inline |
◆ initialize()
◆ NE_A()
const Eigen::Matrix<double, 6, -1> dynacom::DynaCoM::NE_A |
( |
| ) |
|
|
inline |
◆ NE_b()
const Eigen::Matrix<double, 6, 1>& dynacom::DynaCoM::NE_b |
( |
| ) |
|
|
inline |
◆ reg_A()
const Eigen::VectorXd dynacom::DynaCoM::reg_A |
( |
| ) |
|
|
inline |
◆ reg_b()
const Eigen::VectorXd dynacom::DynaCoM::reg_b |
( |
| ) |
|
|
inline |
◆ removeContact6d()
void dynacom::DynaCoM::removeContact6d |
( |
const std::string & |
name | ) |
|
◆ uni_A()
const Eigen::MatrixXd dynacom::DynaCoM::uni_A |
( |
| ) |
|
|
inline |
◆ uni_b()
const Eigen::VectorXd dynacom::DynaCoM::uni_b |
( |
| ) |
|
|
inline |
The documentation for this class was generated from the following files: