#include <RBDyn/RBDyn/CoM.h>
|
| | CoMJacobian () |
| |
| | CoMJacobian (const MultiBody &mb) |
| |
| | CoMJacobian (const MultiBody &mb, std::vector< double > weight) |
| |
| void | updateInertialParameters (const MultiBody &mb) |
| |
| const std::vector< double > & | weight () const |
| |
| void | weight (const MultiBody &mb, std::vector< double > w) |
| | Per bodies weight setter. More...
|
| |
| const Eigen::MatrixXd & | jacobian (const MultiBody &mb, const MultiBodyConfig &mbc) |
| |
| const Eigen::MatrixXd & | jacobian () const noexcept |
| |
| const Eigen::MatrixXd & | jacobianDot (const MultiBody &mb, const MultiBodyConfig &mbc) |
| |
| const Eigen::MatrixXd & | jacobianDot () const noexcept |
| |
| Eigen::Vector3d | velocity (const MultiBody &mb, const MultiBodyConfig &mbc) const |
| |
| Eigen::Vector3d | normalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc) |
| |
| Eigen::Vector3d | normalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc, const std::vector< sva::MotionVecd > &normalAccB) const |
| |
| void | sUpdateInertialParameters (const MultiBody &mb) |
| |
| void | sWeight (const MultiBody &mb, std::vector< double > w) |
| |
| const Eigen::MatrixXd & | sJacobian (const MultiBody &mb, const MultiBodyConfig &mbc) |
| |
| const Eigen::MatrixXd & | sJacobianDot (const MultiBody &mb, const MultiBodyConfig &mbc) |
| |
| Eigen::Vector3d | sVelocity (const MultiBody &mb, const MultiBodyConfig &mbc) const |
| |
| Eigen::Vector3d | sNormalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc) |
| |
| Eigen::Vector3d | sNormalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc, const std::vector< sva::MotionVecd > &normalAccB) const |
| |
◆ CoMJacobian() [1/3]
| rbd::CoMJacobian::CoMJacobian |
( |
| ) |
|
◆ CoMJacobian() [2/3]
| rbd::CoMJacobian::CoMJacobian |
( |
const MultiBody & |
mb | ) |
|
◆ CoMJacobian() [3/3]
| rbd::CoMJacobian::CoMJacobian |
( |
const MultiBody & |
mb, |
|
|
std::vector< double > |
weight |
|
) |
| |
- Parameters
-
| mb | MultiBody used has model. |
| weight | Per body weight. |
◆ jacobian() [1/2]
| const Eigen::MatrixXd& rbd::CoMJacobian::jacobian |
( |
| ) |
const |
|
inlinenoexcept |
Access the last computed CoM jacobian
- Returns
- Latest CoM jacobian that was computed by this object
◆ jacobian() [2/2]
Compute the CoM jacobian.
- Parameters
-
| mb | MultiBody used as model. |
| mbc | Use bodyPosW and motionSubspace. |
- Returns
- CoM Jacobian of mb with mbc configuration.
◆ jacobianDot() [1/2]
| const Eigen::MatrixXd& rbd::CoMJacobian::jacobianDot |
( |
| ) |
const |
|
inlinenoexcept |
Access the last computed derivative of the CoM jacobian
- Returns
- Latest derivative of the CoM jacobian that was computed by this object
◆ jacobianDot() [2/2]
Compute the time derivative of the CoM jacobian.
- Parameters
-
| mb | MultiBody used as model. |
| mbc | Use bodyPosW, bodyVelB, bodyVelW, and motionSubspace. |
- Returns
- Time derivativo of the jacobian of mb with mbc configuration.
◆ normalAcceleration() [1/2]
Compute the com normal acceleration (with weight) (JDot·alpha).
- Parameters
-
| mb | MultiBody used as model. |
| mbc | Use bodyPosW, bodyVelW, bodyVelB, jointVelocity, parentToSon. |
- Returns
- CoM normal acceleration (with weight).
◆ normalAcceleration() [2/2]
| Eigen::Vector3d rbd::CoMJacobian::normalAcceleration |
( |
const MultiBody & |
mb, |
|
|
const MultiBodyConfig & |
mbc, |
|
|
const std::vector< sva::MotionVecd > & |
normalAccB |
|
) |
| const |
Compute the com normal acceleration (with weight) (JDot·alpha).
- Parameters
-
| mb | MultiBody used as model. |
| mbc | Use bodyPosW, bodyVelW, bodyVelB. |
| normalAccB | Normal bodies acceleration in body frame. |
- Returns
- CoM normal acceleration (with weight).
◆ sJacobian()
safe version of
- See also
- jacobian.
- Exceptions
-
| std::domain_error | If mb don't match mbc. |
◆ sJacobianDot()
safe version of
- See also
- jacobianDot.
- Exceptions
-
| std::domain_error | If mb don't match mbc. |
◆ sNormalAcceleration() [1/2]
safe version of
- See also
- normalAcceleration.
- Exceptions
-
| std::domain_error | If mb don't match mbc. |
◆ sNormalAcceleration() [2/2]
| Eigen::Vector3d rbd::CoMJacobian::sNormalAcceleration |
( |
const MultiBody & |
mb, |
|
|
const MultiBodyConfig & |
mbc, |
|
|
const std::vector< sva::MotionVecd > & |
normalAccB |
|
) |
| const |
safe version of
- See also
- normalAcceleration.
- Exceptions
-
| std::domain_error | If mb don't match mbc or normalAccB. |
◆ sUpdateInertialParameters()
| void rbd::CoMJacobian::sUpdateInertialParameters |
( |
const MultiBody & |
mb | ) |
|
safe version of
- See also
- updateInertialParameters.
- Exceptions
-
| std::domain_error | If mb don't match the mb used in constructor. |
◆ sVelocity()
safe version of
- See also
- velocity.
- Exceptions
-
| std::domain_error | If mb don't match mbc. |
◆ sWeight()
| void rbd::CoMJacobian::sWeight |
( |
const MultiBody & |
mb, |
|
|
std::vector< double > |
w |
|
) |
| |
safe version of
- See also
- weight.
- Exceptions
-
| std::domain_error | If mb don't match the mb used in constructor or w missmatch mb. |
◆ updateInertialParameters()
| void rbd::CoMJacobian::updateInertialParameters |
( |
const MultiBody & |
mb | ) |
|
Compute bodies CoM position and mass based on a MultiBody. This method allow to update some pre-computed parameters when MultiBody inertia has changed.
- Parameters
-
◆ velocity()
Compute the com velocity (with weight) (J·alpha).
- Parameters
-
| mb | MultiBody used as model. |
| mbc | Use bodyPosW, bodyVelB. |
- Returns
- CoM velocity (with weight).
◆ weight() [1/2]
| const std::vector<double>& rbd::CoMJacobian::weight |
( |
| ) |
const |
- Returns
- Per bodies weight.
◆ weight() [2/2]
| void rbd::CoMJacobian::weight |
( |
const MultiBody & |
mb, |
|
|
std::vector< double > |
w |
|
) |
| |
Per bodies weight setter.
The documentation for this class was generated from the following file: