#include <aig/biped_ig.hpp>
Public Member Functions | |
BipedIG () | |
BipedIG (const BipedIGSettings &settings) | |
void | initialize (const BipedIGSettings &settings) |
const BipedIGSettings & | get_settings () |
const LegIGSettings & | get_left_leg_settings () |
const LegIGSettings & | get_right_leg_settings () |
const Eigen::VectorXd & | getQ0 () |
void | setQ0 (const Eigen::VectorXd q0) |
const Eigen::Vector3d & | getAMVariation () |
Get the Angular Momentum variation. Please call computeDynamics first. Deprecate it, AIG is not made for dynamics. More... | |
const Eigen::Vector3d & | getCoM () |
Get the CoM position. Please call computeDynamics first. More... | |
const Eigen::Vector3d & | getVCoM () |
Get the CoM velocity. Please call computeDynamics first. More... | |
const Eigen::Vector3d & | getACoM () |
Get the CoM acceleration. Please call computeDynamics first. More... | |
const Eigen::Vector3d & | getAM () |
Get the angular momentum. Please call computeDynamics first. More... | |
const Eigen::Vector2d & | getCoP () |
Get the CoP Position. Please call computeDynamics first. More... | |
const Eigen::Vector2d & | getNL () |
Get the nonlinear effect. Please call computeDynamics first. More... | |
void | checkCompatibility () |
void | solve (const Eigen::Vector3d &com, const pinocchio::SE3 &leftFoot, const pinocchio::SE3 &rightFoot, const Eigen::VectorXd &q0, Eigen::VectorXd &posture, const double &tolerance=1e-10, const int &max_iterations=0) |
void | solve (const Eigen::Vector3d &com, const Eigen::Isometry3d &leftFeet, const Eigen::Isometry3d &rightFeet, const Eigen::VectorXd &q0, Eigen::VectorXd &posture, const double &tolerance=1e-10, const int &max_iterations=0) |
void | solve (const Eigen::Vector3d &com, const Eigen::Matrix3d &baseRotation, const pinocchio::SE3 &leftFoot, const pinocchio::SE3 &rightFoot, const Eigen::VectorXd &q0, Eigen::VectorXd &posture, const double &tolerance=1e-10, const int &max_iterations=0) |
void | solve (const Eigen::Vector3d &com, const Eigen::Matrix3d &baseRotation, const Eigen::Isometry3d &leftFoot, const Eigen::Isometry3d &rightFoot, const Eigen::VectorXd &q0, Eigen::VectorXd &posture, const double &tolerance=1e-10, const int &max_iterations=0) |
void | solve (const pinocchio::SE3 &base, const pinocchio::SE3 &leftFoot, const pinocchio::SE3 &rightFoot, const Eigen::VectorXd &q0, Eigen::VectorXd &posture) |
void | solve (const Eigen::Isometry3d &base, const Eigen::Isometry3d &leftFoot, const Eigen::Isometry3d &rightFoot, const Eigen::VectorXd &q0, Eigen::VectorXd &posture) |
void | solve (const std::array< Eigen::Vector3d, 3 > &coms, const std::array< pinocchio::SE3, 3 > &leftFeet, const std::array< pinocchio::SE3, 3 > &rightFeet, const Eigen::VectorXd &q0, Eigen::VectorXd &posture, Eigen::VectorXd &velocity, Eigen::VectorXd &acceleration, const double &dt, const double &tolerance=1e-10, const int &max_iterations=0) |
void | solve (const std::array< Eigen::Vector3d, 3 > &coms, const std::array< Eigen::Isometry3d, 3 > &leftFeet, const std::array< Eigen::Isometry3d, 3 > &rightFeet, const Eigen::VectorXd &q0, Eigen::VectorXd &posture, Eigen::VectorXd &velocity, Eigen::VectorXd &acceleration, const double &dt, const double &tolerance=1e-10, const int &max_iterations=0) |
void | solve (const std::array< Eigen::Vector3d, 3 > &coms, const std::array< Eigen::Matrix3d, 3 > &baseRotations, const std::array< pinocchio::SE3, 3 > &leftFeet, const std::array< pinocchio::SE3, 3 > &rightFeet, const Eigen::VectorXd &q0, Eigen::VectorXd &posture, Eigen::VectorXd &velocity, Eigen::VectorXd &acceleration, const double &dt, const double &tolerance=1e-10, const int &max_iterations=0) |
void | solve (const std::array< Eigen::Vector3d, 3 > &coms, const std::array< Eigen::Matrix3d, 3 > &baseRotations, const std::array< Eigen::Isometry3d, 3 > &leftFeet, const std::array< Eigen::Isometry3d, 3 > &rightFeet, const Eigen::VectorXd &q0, Eigen::VectorXd &posture, Eigen::VectorXd &velocity, Eigen::VectorXd &acceleration, const double &dt, const double &tolerance=1e-10, const int &max_iterations=0) |
void | solve (const std::array< pinocchio::SE3, 3 > &bases, const std::array< pinocchio::SE3, 3 > &leftFeet, const std::array< pinocchio::SE3, 3 > &rightFeet, const Eigen::VectorXd &q0, Eigen::VectorXd &posture, Eigen::VectorXd &velocity, Eigen::VectorXd &acceleration, const double &dt) |
void | solve (const std::array< Eigen::Isometry3d, 3 > &bases, const std::array< Eigen::Isometry3d, 3 > &leftFeet, const std::array< Eigen::Isometry3d, 3 > &rightFeet, const Eigen::VectorXd &q0, Eigen::VectorXd &posture, Eigen::VectorXd &velocity, Eigen::VectorXd &acceleration, const double &dt) |
void | set_com_from_waist (const Eigen::Vector3d &com_from_waist) |
void | set_com_from_waist (const Eigen::VectorXd &q) |
void | correctCoMfromWaist (const Eigen::Vector3d &com, const pinocchio::SE3 &leftFoot, const pinocchio::SE3 &rightFoot, const Eigen::VectorXd &q0, const double &tolerance=1e-10, const int &max_iterations=20) |
void | correctCoMfromWaist (const Eigen::Vector3d &com, const Eigen::Isometry3d &leftFoot, const Eigen::Isometry3d &rightFoot, const Eigen::VectorXd &q0, const double &tolerance=1e-10, const int &max_iterations=20) |
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) |
pinocchio::Model & | get_model () |
pinocchio::Data & | get_data () |
Eigen::Vector3d & | get_com_from_waist () |
aig::BipedIG::BipedIG | ( | ) |
aig::BipedIG::BipedIG | ( | const BipedIGSettings & | settings | ) |
void aig::BipedIG::checkCompatibility | ( | ) |
void aig::BipedIG::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 aig::BipedIG::computeNL | ( | const double & | w | ) |
In this function form, computeDynamics is suposed to have been called before.
void aig::BipedIG::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 aig::BipedIG::correctCoMfromWaist | ( | const Eigen::Vector3d & | com, |
const Eigen::Isometry3d & | leftFoot, | ||
const Eigen::Isometry3d & | rightFoot, | ||
const Eigen::VectorXd & | q0, | ||
const double & | tolerance = 1e-10 , |
||
const int & | max_iterations = 20 |
||
) |
void aig::BipedIG::correctCoMfromWaist | ( | const Eigen::Vector3d & | com, |
const pinocchio::SE3 & | leftFoot, | ||
const pinocchio::SE3 & | rightFoot, | ||
const Eigen::VectorXd & | q0, | ||
const double & | tolerance = 1e-10 , |
||
const int & | max_iterations = 20 |
||
) |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
|
inline |
Get the CoM acceleration. Please call computeDynamics first.
|
inline |
Get the angular momentum. Please call computeDynamics first.
|
inline |
Get the Angular Momentum variation. Please call computeDynamics first. Deprecate it, AIG is not made for dynamics.
|
inline |
Get the CoM position. Please call computeDynamics first.
|
inline |
Get the CoP Position. Please call computeDynamics first.
|
inline |
Get the nonlinear effect. Please call computeDynamics first.
|
inline |
|
inline |
Get the CoM velocity. Please call computeDynamics first.
void aig::BipedIG::initialize | ( | const BipedIGSettings & | settings | ) |
void aig::BipedIG::set_com_from_waist | ( | const Eigen::Vector3d & | com_from_waist | ) |
void aig::BipedIG::set_com_from_waist | ( | const Eigen::VectorXd & | q | ) |
|
inline |
void aig::BipedIG::solve | ( | const Eigen::Isometry3d & | base, |
const Eigen::Isometry3d & | leftFoot, | ||
const Eigen::Isometry3d & | rightFoot, | ||
const Eigen::VectorXd & | q0, | ||
Eigen::VectorXd & | posture | ||
) |
void aig::BipedIG::solve | ( | const Eigen::Vector3d & | com, |
const Eigen::Isometry3d & | leftFeet, | ||
const Eigen::Isometry3d & | rightFeet, | ||
const Eigen::VectorXd & | q0, | ||
Eigen::VectorXd & | posture, | ||
const double & | tolerance = 1e-10 , |
||
const int & | max_iterations = 0 |
||
) |
void aig::BipedIG::solve | ( | const Eigen::Vector3d & | com, |
const Eigen::Matrix3d & | baseRotation, | ||
const Eigen::Isometry3d & | leftFoot, | ||
const Eigen::Isometry3d & | rightFoot, | ||
const Eigen::VectorXd & | q0, | ||
Eigen::VectorXd & | posture, | ||
const double & | tolerance = 1e-10 , |
||
const int & | max_iterations = 0 |
||
) |
void aig::BipedIG::solve | ( | const Eigen::Vector3d & | com, |
const Eigen::Matrix3d & | baseRotation, | ||
const pinocchio::SE3 & | leftFoot, | ||
const pinocchio::SE3 & | rightFoot, | ||
const Eigen::VectorXd & | q0, | ||
Eigen::VectorXd & | posture, | ||
const double & | tolerance = 1e-10 , |
||
const int & | max_iterations = 0 |
||
) |
void aig::BipedIG::solve | ( | const Eigen::Vector3d & | com, |
const pinocchio::SE3 & | leftFoot, | ||
const pinocchio::SE3 & | rightFoot, | ||
const Eigen::VectorXd & | q0, | ||
Eigen::VectorXd & | posture, | ||
const double & | tolerance = 1e-10 , |
||
const int & | max_iterations = 0 |
||
) |
void aig::BipedIG::solve | ( | const pinocchio::SE3 & | base, |
const pinocchio::SE3 & | leftFoot, | ||
const pinocchio::SE3 & | rightFoot, | ||
const Eigen::VectorXd & | q0, | ||
Eigen::VectorXd & | posture | ||
) |
void aig::BipedIG::solve | ( | const std::array< Eigen::Isometry3d, 3 > & | bases, |
const std::array< Eigen::Isometry3d, 3 > & | leftFeet, | ||
const std::array< Eigen::Isometry3d, 3 > & | rightFeet, | ||
const Eigen::VectorXd & | q0, | ||
Eigen::VectorXd & | posture, | ||
Eigen::VectorXd & | velocity, | ||
Eigen::VectorXd & | acceleration, | ||
const double & | dt | ||
) |
void aig::BipedIG::solve | ( | const std::array< Eigen::Vector3d, 3 > & | coms, |
const std::array< Eigen::Isometry3d, 3 > & | leftFeet, | ||
const std::array< Eigen::Isometry3d, 3 > & | rightFeet, | ||
const Eigen::VectorXd & | q0, | ||
Eigen::VectorXd & | posture, | ||
Eigen::VectorXd & | velocity, | ||
Eigen::VectorXd & | acceleration, | ||
const double & | dt, | ||
const double & | tolerance = 1e-10 , |
||
const int & | max_iterations = 0 |
||
) |
void aig::BipedIG::solve | ( | const std::array< Eigen::Vector3d, 3 > & | coms, |
const std::array< Eigen::Matrix3d, 3 > & | baseRotations, | ||
const std::array< Eigen::Isometry3d, 3 > & | leftFeet, | ||
const std::array< Eigen::Isometry3d, 3 > & | rightFeet, | ||
const Eigen::VectorXd & | q0, | ||
Eigen::VectorXd & | posture, | ||
Eigen::VectorXd & | velocity, | ||
Eigen::VectorXd & | acceleration, | ||
const double & | dt, | ||
const double & | tolerance = 1e-10 , |
||
const int & | max_iterations = 0 |
||
) |
void aig::BipedIG::solve | ( | const std::array< Eigen::Vector3d, 3 > & | coms, |
const std::array< Eigen::Matrix3d, 3 > & | baseRotations, | ||
const std::array< pinocchio::SE3, 3 > & | leftFeet, | ||
const std::array< pinocchio::SE3, 3 > & | rightFeet, | ||
const Eigen::VectorXd & | q0, | ||
Eigen::VectorXd & | posture, | ||
Eigen::VectorXd & | velocity, | ||
Eigen::VectorXd & | acceleration, | ||
const double & | dt, | ||
const double & | tolerance = 1e-10 , |
||
const int & | max_iterations = 0 |
||
) |
void aig::BipedIG::solve | ( | const std::array< Eigen::Vector3d, 3 > & | coms, |
const std::array< pinocchio::SE3, 3 > & | leftFeet, | ||
const std::array< pinocchio::SE3, 3 > & | rightFeet, | ||
const Eigen::VectorXd & | q0, | ||
Eigen::VectorXd & | posture, | ||
Eigen::VectorXd & | velocity, | ||
Eigen::VectorXd & | acceleration, | ||
const double & | dt, | ||
const double & | tolerance = 1e-10 , |
||
const int & | max_iterations = 0 |
||
) |
void aig::BipedIG::solve | ( | const std::array< pinocchio::SE3, 3 > & | bases, |
const std::array< pinocchio::SE3, 3 > & | leftFeet, | ||
const std::array< pinocchio::SE3, 3 > & | rightFeet, | ||
const Eigen::VectorXd & | q0, | ||
Eigen::VectorXd & | posture, | ||
Eigen::VectorXd & | velocity, | ||
Eigen::VectorXd & | acceleration, | ||
const double & | dt | ||
) |