BipedalLocomotion::Estimators::FloatingBaseEstimator::ModelComputations class

iDynTree based model-specific computations class This is class is used in a required configuration step for the estimator All the model related kinematics and dynamics computations specific to the floating base estimator are contained within this class.

Public functions

auto setKinDynObject(std::shared_ptr<iDynTree::KinDynComputations> kinDyn) -> bool
Set the shared kindyn object.
auto setBaseLinkAndIMU(const std::string& baseLinkFrame, const std::string& imuFrame) -> bool
Set base link name and name of the IMU rigidly attached to the IMU.
auto setFeetContactFrames(const std::string& lFootContactFrame, const std::string& rFootContactFrame) -> bool
Set the feet contact frames, expected to be in contact with the environment.
auto isModelInfoLoaded() -> bool
Check if model is configured with the required information.
auto getIMU_H_feet(Eigen::Ref<const Eigen::VectorXd> encoders, manif::SE3d& IMU_H_l_foot, manif::SE3d& IMU_H_r_foot) -> bool
Get relative pose between IMU and the feet.
auto getIMU_H_feet(const Eigen::Ref<const Eigen::VectorXd> encoders, manif::SE3d& IMU_H_l_foot, manif::SE3d& IMU_H_r_foot, Eigen::Ref<Eigen::MatrixXd> J_IMULF, Eigen::Ref<Eigen::MatrixXd> J_IMURF) -> bool
Get relative pose between IMU and the feet.
auto getBaseStateFromIMUState(const manif::SE3d& A_H_IMU, Eigen::Ref<const Eigen::Matrix<double, 6, 1>> v_IMU, manif::SE3d& A_H_B, Eigen::Ref<Eigen::Matrix<double, 6, 1>> v_B) -> bool
Get the base link pose and velocity from the estimated IMU pose and velocity.
auto nrJoints() const -> const int&
Getters.
auto baseLink() const -> const std::string&
auto baseLinkIdx() const -> const iDynTree::FrameIndex&
auto baseIMUIdx() const -> const iDynTree::FrameIndex&
auto baseLinkIMU() const -> const std::string&
auto leftFootContactFrame() const -> const std::string&
auto rightFootContactFrame() const -> const std::string&
auto base_H_IMU() const -> const manif::SE3d&
auto isKinDynValid() const -> const bool&
auto kinDyn() const -> std::shared_ptr<iDynTree::KinDynComputations>

Function documentation

bool BipedalLocomotion::Estimators::FloatingBaseEstimator::ModelComputations::setKinDynObject(std::shared_ptr<iDynTree::KinDynComputations> kinDyn)

Set the shared kindyn object.

Parameters
kinDyn in shared pointer of the common KinDynComputations resource
Returns True in case of success, false otherwise.

bool BipedalLocomotion::Estimators::FloatingBaseEstimator::ModelComputations::setBaseLinkAndIMU(const std::string& baseLinkFrame, const std::string& imuFrame)

Set base link name and name of the IMU rigidly attached to the IMU.

Parameters
baseLinkFrame in name of the base link frame
imuFrame in name of the IMU frame
Returns True in case of success, false otherwise.

bool BipedalLocomotion::Estimators::FloatingBaseEstimator::ModelComputations::setFeetContactFrames(const std::string& lFootContactFrame, const std::string& rFootContactFrame)

Set the feet contact frames, expected to be in contact with the environment.

Parameters
lFootContactFrame in left foot contact frame
rFootContactFrame in right foot contact frame
Returns True in case of success, false otherwise.

bool BipedalLocomotion::Estimators::FloatingBaseEstimator::ModelComputations::isModelInfoLoaded()

Check if model is configured with the required information.

Returns True in case of success, false otherwise.

bool BipedalLocomotion::Estimators::FloatingBaseEstimator::ModelComputations::getIMU_H_feet(Eigen::Ref<const Eigen::VectorXd> encoders, manif::SE3d& IMU_H_l_foot, manif::SE3d& IMU_H_r_foot)

Get relative pose between IMU and the feet.

Parameters
encoders in joint positions through encoder measurements
IMU_H_l_foot out pose of the left foot contact frame with respect to the IMU frame
IMU_H_r_foot out pose of the right foot contact frame with respect to the IMU frame
Returns True in case of success, false otherwise.

bool BipedalLocomotion::Estimators::FloatingBaseEstimator::ModelComputations::getIMU_H_feet(const Eigen::Ref<const Eigen::VectorXd> encoders, manif::SE3d& IMU_H_l_foot, manif::SE3d& IMU_H_r_foot, Eigen::Ref<Eigen::MatrixXd> J_IMULF, Eigen::Ref<Eigen::MatrixXd> J_IMURF)

Get relative pose between IMU and the feet.

Parameters
encoders in joint positions through encoder measurements
IMU_H_l_foot out pose of the left foot contact frame with respect to the IMU frame
IMU_H_r_foot out pose of the right foot contact frame with respect to the IMU frame
J_IMULF out Jacobian of left foot frame with respect to IMU frame in mixed-velocity trivialization
J_IMURF out Jacobian of right foot frame with respect to IMU frame in mixed-velocity trivialization
Returns True in case of success, false otherwise.

bool BipedalLocomotion::Estimators::FloatingBaseEstimator::ModelComputations::getBaseStateFromIMUState(const manif::SE3d& A_H_IMU, Eigen::Ref<const Eigen::Matrix<double, 6, 1>> v_IMU, manif::SE3d& A_H_B, Eigen::Ref<Eigen::Matrix<double, 6, 1>> v_B)

Get the base link pose and velocity from the estimated IMU pose and velocity.

Parameters
A_H_IMU in pose of the IMU in the world
v_IMU in mixed-trivialized velocity of the IMU in the world
A_H_B out pose of the base link in the world
v_B out mixed-trivialized velocity of the base link in the world
Returns True in case of success, false otherwise.