aig::BipedIG Class Reference

#include <aig/biped_ig.hpp>

Public Member Functions

 BipedIG ()
 
 BipedIG (const BipedIGSettings &settings)
 
void initialize (const BipedIGSettings &settings)
 
const BipedIGSettingsget_settings ()
 
const LegIGSettingsget_left_leg_settings ()
 
const LegIGSettingsget_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 ()
 

Detailed Description

Todo:
Describe BipedIG

Constructor & Destructor Documentation

◆ BipedIG() [1/2]

aig::BipedIG::BipedIG ( )

◆ BipedIG() [2/2]

aig::BipedIG::BipedIG ( const BipedIGSettings settings)

Member Function Documentation

◆ checkCompatibility()

void aig::BipedIG::checkCompatibility ( )

◆ computeDynamics()

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 
)

◆ computeNL() [1/2]

void aig::BipedIG::computeNL ( const double &  w)

In this function form, computeDynamics is suposed to have been called before.

◆ computeNL() [2/2]

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 
)

◆ correctCoMfromWaist() [1/2]

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 
)

◆ correctCoMfromWaist() [2/2]

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 
)

◆ get_com_from_waist()

Eigen::Vector3d& aig::BipedIG::get_com_from_waist ( )
inline

◆ get_data()

pinocchio::Data& aig::BipedIG::get_data ( )
inline

◆ get_left_leg_settings()

const LegIGSettings& aig::BipedIG::get_left_leg_settings ( )
inline

◆ get_model()

pinocchio::Model& aig::BipedIG::get_model ( )
inline

◆ get_right_leg_settings()

const LegIGSettings& aig::BipedIG::get_right_leg_settings ( )
inline

◆ get_settings()

const BipedIGSettings& aig::BipedIG::get_settings ( )
inline

◆ getACoM()

const Eigen::Vector3d& aig::BipedIG::getACoM ( )
inline

Get the CoM acceleration. Please call computeDynamics first.

◆ getAM()

const Eigen::Vector3d& aig::BipedIG::getAM ( )
inline

Get the angular momentum. Please call computeDynamics first.

◆ getAMVariation()

const Eigen::Vector3d& aig::BipedIG::getAMVariation ( )
inline

Get the Angular Momentum variation. Please call computeDynamics first. Deprecate it, AIG is not made for dynamics.

◆ getCoM()

const Eigen::Vector3d& aig::BipedIG::getCoM ( )
inline

Get the CoM position. Please call computeDynamics first.

◆ getCoP()

const Eigen::Vector2d& aig::BipedIG::getCoP ( )
inline

Get the CoP Position. Please call computeDynamics first.

◆ getNL()

const Eigen::Vector2d& aig::BipedIG::getNL ( )
inline

Get the nonlinear effect. Please call computeDynamics first.

◆ getQ0()

const Eigen::VectorXd& aig::BipedIG::getQ0 ( )
inline

◆ getVCoM()

const Eigen::Vector3d& aig::BipedIG::getVCoM ( )
inline

Get the CoM velocity. Please call computeDynamics first.

◆ initialize()

void aig::BipedIG::initialize ( const BipedIGSettings settings)

◆ set_com_from_waist() [1/2]

void aig::BipedIG::set_com_from_waist ( const Eigen::Vector3d &  com_from_waist)

◆ set_com_from_waist() [2/2]

void aig::BipedIG::set_com_from_waist ( const Eigen::VectorXd &  q)

◆ setQ0()

void aig::BipedIG::setQ0 ( const Eigen::VectorXd  q0)
inline

◆ solve() [1/12]

void aig::BipedIG::solve ( const Eigen::Isometry3d &  base,
const Eigen::Isometry3d &  leftFoot,
const Eigen::Isometry3d &  rightFoot,
const Eigen::VectorXd &  q0,
Eigen::VectorXd &  posture 
)

◆ solve() [2/12]

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 
)

◆ solve() [3/12]

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 
)

◆ solve() [4/12]

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 
)

◆ solve() [5/12]

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 
)

◆ solve() [6/12]

void aig::BipedIG::solve ( const pinocchio::SE3 &  base,
const pinocchio::SE3 &  leftFoot,
const pinocchio::SE3 &  rightFoot,
const Eigen::VectorXd &  q0,
Eigen::VectorXd &  posture 
)

◆ solve() [7/12]

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 
)

◆ solve() [8/12]

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 
)

◆ solve() [9/12]

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 
)

◆ solve() [10/12]

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 
)

◆ solve() [11/12]

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 
)

◆ solve() [12/12]

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 
)

The documentation for this class was generated from the following files: