#include <RBDyn/RBDyn/Momentum.h>
|
| | 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].
◆ CentroidalMomentumMatrix() [1/3]
| rbd::CentroidalMomentumMatrix::CentroidalMomentumMatrix |
( |
| ) |
|
◆ CentroidalMomentumMatrix() [2/3]
| rbd::CentroidalMomentumMatrix::CentroidalMomentumMatrix |
( |
const MultiBody & |
mb | ) |
|
◆ CentroidalMomentumMatrix() [3/3]
| rbd::CentroidalMomentumMatrix::CentroidalMomentumMatrix |
( |
const MultiBody & |
mb, |
|
|
std::vector< double > |
weight |
|
) |
| |
- Parameters
-
| mb | MultiBody used has model. |
| weight | Per body weight. |
◆ computeMatrix()
| void rbd::CentroidalMomentumMatrix::computeMatrix |
( |
const MultiBody & |
mb, |
|
|
const MultiBodyConfig & |
mbc, |
|
|
const Eigen::Vector3d & |
com |
|
) |
| |
Compute the centroidal momentum matrix.
- Parameters
-
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, motionSubspace. |
| com | CoM position. |
◆ computeMatrixAndMatrixDot()
| void rbd::CentroidalMomentumMatrix::computeMatrixAndMatrixDot |
( |
const MultiBody & |
mb, |
|
|
const MultiBodyConfig & |
mbc, |
|
|
const Eigen::Vector3d & |
com, |
|
|
const Eigen::Vector3d & |
comDot |
|
) |
| |
◆ computeMatrixDot()
| 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.
- Parameters
-
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, bodyVelW, bodyVelB, motionSubspace. |
| com | CoM position. |
| comDot | CoM velocity. |
◆ matrix()
| const Eigen::MatrixXd& rbd::CentroidalMomentumMatrix::matrix |
( |
| ) |
const |
- Returns
- Centroidal momentum matrix
◆ matrixDot()
| const Eigen::MatrixXd& rbd::CentroidalMomentumMatrix::matrixDot |
( |
| ) |
const |
- Returns
- Centroidal momentum matrix time derivative
◆ momentum()
| sva::ForceVecd rbd::CentroidalMomentumMatrix::momentum |
( |
const MultiBody & |
mb, |
|
|
const MultiBodyConfig & |
mbc, |
|
|
const Eigen::Vector3d & |
com |
|
) |
| const |
Compute the centroidal momentum (with weight) (J·alpha).
- Parameters
-
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, bodyVelB. |
| com | CoM position. |
- Returns
- Centroidal momentum at the CoM frame (with weight).
◆ normalMomentumDot() [1/2]
| 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).
- Parameters
-
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, bodyVelB, jointVelocity, parentToSon. |
| com | CoM position. |
| comDot | CoM velocity. |
- Returns
- Normal componant of the time derivative Centroidal momentum at the CoM frame (with weight).
◆ normalMomentumDot() [2/2]
| 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).
- Parameters
-
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, bodyVelB. |
| com | CoM position. |
| comDot | CoM velocity. |
| normalAccB | Normal bodies acceleration in body frame. |
- Returns
- Normal componant of the time derivative Centroidal momentum at the CoM frame (with weight).
◆ sComputeMatrix()
| void rbd::CentroidalMomentumMatrix::sComputeMatrix |
( |
const MultiBody & |
mb, |
|
|
const MultiBodyConfig & |
mbc, |
|
|
const Eigen::Vector3d & |
com |
|
) |
| |
safe version of
- See also
- computeMatrix.
- Exceptions
-
| std::domain_error | If mb don't match mbc. |
◆ sComputeMatrixAndMatrixDot()
| void rbd::CentroidalMomentumMatrix::sComputeMatrixAndMatrixDot |
( |
const MultiBody & |
mb, |
|
|
const MultiBodyConfig & |
mbc, |
|
|
const Eigen::Vector3d & |
com, |
|
|
const Eigen::Vector3d & |
comDot |
|
) |
| |
◆ sComputeMatrixDot()
| void rbd::CentroidalMomentumMatrix::sComputeMatrixDot |
( |
const MultiBody & |
mb, |
|
|
const MultiBodyConfig & |
mbc, |
|
|
const Eigen::Vector3d & |
com, |
|
|
const Eigen::Vector3d & |
comDot |
|
) |
| |
safe version of
- See also
- computeMatrixDot.
- Exceptions
-
| std::domain_error | If mb don't match mbc. |
◆ sMomentum()
| sva::ForceVecd rbd::CentroidalMomentumMatrix::sMomentum |
( |
const MultiBody & |
mb, |
|
|
const MultiBodyConfig & |
mbc, |
|
|
const Eigen::Vector3d & |
com |
|
) |
| const |
safe version of
- See also
- momentum.
- Exceptions
-
| std::domain_error | If mb don't match mbc. |
◆ sNormalMomentumDot() [1/2]
| sva::ForceVecd rbd::CentroidalMomentumMatrix::sNormalMomentumDot |
( |
const MultiBody & |
mb, |
|
|
const MultiBodyConfig & |
mbc, |
|
|
const Eigen::Vector3d & |
com, |
|
|
const Eigen::Vector3d & |
comDot |
|
) |
| |
safe version of
- See also
- normalMomentumDot.
- Exceptions
-
| std::domain_error | If mb don't match mbc. |
◆ sNormalMomentumDot() [2/2]
| 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
- See also
- normalMomentumDot.
- Exceptions
-
| std::domain_error | If mb don't match mbc or normalAccB. |
The documentation for this class was generated from the following file: