|
RBDyn 1.9.3
|
#include <RBDyn/RBDyn/Momentum.h>
Public Member Functions | |
| CentroidalMomentumMatrix () | |
| CentroidalMomentumMatrix (const MultiBody &mb) | |
| CentroidalMomentumMatrix (const MultiBody &mb, std::vector< double > weight) | |
| void | computeMatrix (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com) |
| void | computeMatrixDot (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com, const Eigen::Vector3d &comDot) |
| void | computeMatrixAndMatrixDot (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com, const Eigen::Vector3d &comDot) |
| const Eigen::MatrixXd & | matrix () const |
| const Eigen::MatrixXd & | matrixDot () const |
| sva::ForceVecd | momentum (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com) const |
| sva::ForceVecd | normalMomentumDot (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com, const Eigen::Vector3d &comDot) |
| sva::ForceVecd | normalMomentumDot (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com, const Eigen::Vector3d &comDot, const std::vector< sva::MotionVecd > &normalAccB) const |
| void | sComputeMatrix (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com) |
| void | sComputeMatrixDot (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com, const Eigen::Vector3d &comDot) |
| void | sComputeMatrixAndMatrixDot (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com, const Eigen::Vector3d &comDot) |
| sva::ForceVecd | sMomentum (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com) const |
| sva::ForceVecd | sNormalMomentumDot (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com, const Eigen::Vector3d &comDot) |
| sva::ForceVecd | sNormalMomentumDot (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &com, const Eigen::Vector3d &comDot, const std::vector< sva::MotionVecd > &normalAccB) const |
Compute the Centroidal momentum matrix (Jacobian) as describe in [Orin and Gosawami 2008].
| rbd::CentroidalMomentumMatrix::CentroidalMomentumMatrix | ( | ) |
| rbd::CentroidalMomentumMatrix::CentroidalMomentumMatrix | ( | const MultiBody & | mb | ) |
| mb | MultiBody used has model. |
| rbd::CentroidalMomentumMatrix::CentroidalMomentumMatrix | ( | const MultiBody & | mb, |
| std::vector< double > | weight | ||
| ) |
| mb | MultiBody used has model. |
| weight | Per body weight. |
| void rbd::CentroidalMomentumMatrix::computeMatrix | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | com | ||
| ) |
Compute the centroidal momentum matrix.
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, motionSubspace. |
| com | CoM position. |
| void rbd::CentroidalMomentumMatrix::computeMatrixAndMatrixDot | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | com, | ||
| const Eigen::Vector3d & | comDot | ||
| ) |
Compute the centroidal momentum matrix and his time derivative.
| void rbd::CentroidalMomentumMatrix::computeMatrixDot | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | com, | ||
| const Eigen::Vector3d & | comDot | ||
| ) |
Compute the time derivative of centroidal momentum matrix.
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, bodyVelW, bodyVelB, motionSubspace. |
| com | CoM position. |
| comDot | CoM velocity. |
| const Eigen::MatrixXd & rbd::CentroidalMomentumMatrix::matrix | ( | ) | const |
| const Eigen::MatrixXd & rbd::CentroidalMomentumMatrix::matrixDot | ( | ) | const |
| sva::ForceVecd rbd::CentroidalMomentumMatrix::momentum | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | com | ||
| ) | const |
Compute the centroidal momentum (with weight) (J·alpha).
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, bodyVelB. |
| com | CoM position. |
| sva::ForceVecd rbd::CentroidalMomentumMatrix::normalMomentumDot | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | com, | ||
| const Eigen::Vector3d & | comDot | ||
| ) |
Compute the normal componant of the time derivative of centroidal momentum (with weight) (JDot·alpha).
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, bodyVelB, jointVelocity, parentToSon. |
| com | CoM position. |
| comDot | CoM velocity. |
| sva::ForceVecd rbd::CentroidalMomentumMatrix::normalMomentumDot | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | com, | ||
| const Eigen::Vector3d & | comDot, | ||
| const std::vector< sva::MotionVecd > & | normalAccB | ||
| ) | const |
Compute the normal componant of the time derivative of centroidal momentum (with weight) (JDot·alpha).
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, bodyVelB. |
| com | CoM position. |
| comDot | CoM velocity. |
| normalAccB | Normal bodies acceleration in body frame. |
| void rbd::CentroidalMomentumMatrix::sComputeMatrix | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | com | ||
| ) |
| void rbd::CentroidalMomentumMatrix::sComputeMatrixAndMatrixDot | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | com, | ||
| const Eigen::Vector3d & | comDot | ||
| ) |
safe version of
| std::domain_error | If mb don't match mbc. |
| void rbd::CentroidalMomentumMatrix::sComputeMatrixDot | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | com, | ||
| const Eigen::Vector3d & | comDot | ||
| ) |
| sva::ForceVecd rbd::CentroidalMomentumMatrix::sMomentum | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | com | ||
| ) | const |
| sva::ForceVecd rbd::CentroidalMomentumMatrix::sNormalMomentumDot | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | com, | ||
| const Eigen::Vector3d & | comDot | ||
| ) |
| sva::ForceVecd rbd::CentroidalMomentumMatrix::sNormalMomentumDot | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | com, | ||
| const Eigen::Vector3d & | comDot, | ||
| const std::vector< sva::MotionVecd > & | normalAccB | ||
| ) | const |
safe version of
| std::domain_error | If mb don't match mbc or normalAccB. |