#include <RBDyn/RBDyn/Jacobian.h>
Public Member Functions | |
| Jacobian () | |
| Jacobian (const MultiBody &mb, const std::string &bodyName, const Eigen::Vector3d &point=Eigen::Vector3d::Zero()) | |
| Jacobian (const MultiBody &mb, const std::string &bodyName, const std::string &refBodyName, const Eigen::Vector3d &point=Eigen::Vector3d::Zero()) | |
| const Eigen::MatrixXd & | jacobian (const MultiBody &mb, const MultiBodyConfig &mbc, const sva::PTransformd &X_0_p) |
| const Eigen::MatrixXd & | jacobian (const MultiBody &mb, const MultiBodyConfig &mbc) |
| const Eigen::MatrixXd & | bodyJacobian (const MultiBody &mb, const MultiBodyConfig &mbc) |
| const Eigen::MatrixXd & | vectorJacobian (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &vector) |
| const Eigen::MatrixXd & | vectorBodyJacobian (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &vector) |
| const Eigen::MatrixXd & | jacobianDot (const MultiBody &mb, const MultiBodyConfig &mbc) |
| const Eigen::MatrixXd & | bodyJacobianDot (const MultiBody &mb, const MultiBodyConfig &mbc) |
| sva::MotionVecd | velocity (const MultiBody &mb, const MultiBodyConfig &mbc, const sva::PTransformd &X_b_p) const |
| sva::MotionVecd | velocity (const MultiBody &mb, const MultiBodyConfig &mbc) const |
| sva::MotionVecd | bodyVelocity (const MultiBody &mb, const MultiBodyConfig &mbc) const |
| sva::MotionVecd | normalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc, const sva::PTransformd &X_b_p, const sva::MotionVecd &V_b_p) const |
| sva::MotionVecd | normalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc) const |
| sva::MotionVecd | bodyNormalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc) const |
| sva::MotionVecd | normalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc, const std::vector< sva::MotionVecd > &normalAccB, const sva::PTransformd &X_b_p, const sva::MotionVecd &V_b_p) const |
| sva::MotionVecd | normalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc, const std::vector< sva::MotionVecd > &normalAccB) const |
| sva::MotionVecd | bodyNormalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc, const std::vector< sva::MotionVecd > &normalAccB) const |
| void | translateJacobian (const Eigen::Ref< const Eigen::MatrixXd > &jac, const MultiBodyConfig &mbc, const Eigen::Vector3d &point, Eigen::MatrixXd &res) |
| void | translateBodyJacobian (const Eigen::Ref< const Eigen::MatrixXd > &jac, const MultiBodyConfig &mbc, const Eigen::Vector3d &point, Eigen::MatrixXd &res) |
| void | fullJacobian (const MultiBody &mb, const Eigen::Ref< const Eigen::MatrixXd > &jac, Eigen::MatrixXd &res) const |
| void | addFullJacobian (const MultiBody &mb, const Eigen::Ref< const Eigen::MatrixXd > &jac, Eigen::MatrixXd &res) const |
| void | addFullJacobian (const Blocks &compactPath, const Eigen::Ref< const Eigen::MatrixXd > &jac, Eigen::MatrixXd &res) const |
| Eigen::MatrixXd | expand (const rbd::MultiBody &mb, const Eigen::Ref< const Eigen::MatrixXd > &jac) const |
| void | expandAdd (const rbd::MultiBody &mb, const Eigen::Ref< const Eigen::MatrixXd > &jac, Eigen::MatrixXd &res) const |
| Blocks | compactPath (const rbd::MultiBody &mb) const |
| void | expandAdd (const Blocks &compactPath, const Eigen::Ref< const Eigen::MatrixXd > &jac, Eigen::MatrixXd &res) const |
| MultiBody | subMultiBody (const MultiBody &mb) const |
| const std::vector< int > & | jointsPath () const |
| int | dof () const |
| const Eigen::Vector3d & | point () const |
| void | point (const Eigen::Vector3d &point) |
| const Eigen::MatrixXd & | sJacobian (const MultiBody &mb, const MultiBodyConfig &mbc, const sva::PTransformd &X_0_p) |
| const Eigen::MatrixXd & | sJacobian (const MultiBody &mb, const MultiBodyConfig &mbc) |
| const Eigen::MatrixXd & | sBodyJacobian (const MultiBody &mb, const MultiBodyConfig &mbc) |
| const Eigen::MatrixXd & | sVectorJacobian (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &vec) |
| const Eigen::MatrixXd & | sVectorBodyJacobian (const MultiBody &mb, const MultiBodyConfig &mbc, const Eigen::Vector3d &vec) |
| MultiBody | sSubMultiBody (const MultiBody &mb) const |
| const Eigen::MatrixXd & | sJacobianDot (const MultiBody &mb, const MultiBodyConfig &mbc) |
| const Eigen::MatrixXd & | sBodyJacobianDot (const MultiBody &mb, const MultiBodyConfig &mbc) |
| void | sTranslateJacobian (const Eigen::MatrixXd &jac, const MultiBodyConfig &mbc, const Eigen::Vector3d &point, Eigen::MatrixXd &res) |
| void | sFullJacobian (const MultiBody &mb, const Eigen::MatrixXd &jac, Eigen::MatrixXd &res) const |
| sva::MotionVecd | sVelocity (const MultiBody &mb, const MultiBodyConfig &mbc, const sva::PTransformd &X_b_p) const |
| sva::MotionVecd | sVelocity (const MultiBody &mb, const MultiBodyConfig &mbc) const |
| sva::MotionVecd | sNormalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc, const sva::PTransformd &X_b_p, const sva::MotionVecd &V_b_p) const |
| sva::MotionVecd | sNormalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc, const std::vector< sva::MotionVecd > &normalAccB, const sva::PTransformd &X_b_p, const sva::MotionVecd &V_b_p) const |
| sva::MotionVecd | sNormalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc) const |
| sva::MotionVecd | sBodyVelocity (const MultiBody &mb, const MultiBodyConfig &mbc) const |
| sva::MotionVecd | sBodyNormalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc) const |
| sva::MotionVecd | sNormalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc, const std::vector< sva::MotionVecd > &normalAccB) const |
| sva::MotionVecd | sBodyNormalAcceleration (const MultiBody &mb, const MultiBodyConfig &mbc, const std::vector< sva::MotionVecd > &normalAccB) const |
Algorithm to compute the jacobian of a specified body.
| rbd::Jacobian::Jacobian | ( | ) |
| rbd::Jacobian::Jacobian | ( | const MultiBody & | mb, |
| const std::string & | bodyName, | ||
| const Eigen::Vector3d & | point = Eigen::Vector3d::Zero() |
||
| ) |
Create a jacobian from the root body to the specified body.
| mb | Multibody where bodyName is in. |
| bodyName | Specified body. |
| point | Point in the body expressed in body coordinate. |
| std::out_of_range | If bodyName don't exist. |
| rbd::Jacobian::Jacobian | ( | const MultiBody & | mb, |
| const std::string & | bodyName, | ||
| const std::string & | refBodyName, | ||
| const Eigen::Vector3d & | point = Eigen::Vector3d::Zero() |
||
| ) |
Create a jacobian from a reference body to the specified body.
| mb | Multibody where bodyName is in. |
| bodyName | Specified body. |
| refBodyName | Reference body. |
| point | Point in the body expressed in body coordinate. |
| std::out_of_range | If bodyName don't exist. |
| void rbd::Jacobian::addFullJacobian | ( | const Blocks & | compactPath, |
| const Eigen::Ref< const Eigen::MatrixXd > & | jac, | ||
| Eigen::MatrixXd & | res | ||
| ) | const |
| void rbd::Jacobian::addFullJacobian | ( | const MultiBody & | mb, |
| const Eigen::Ref< const Eigen::MatrixXd > & | jac, | ||
| Eigen::MatrixXd & | res | ||
| ) | const |
| const Eigen::MatrixXd& rbd::Jacobian::bodyJacobian | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) |
| const Eigen::MatrixXd& rbd::Jacobian::bodyJacobianDot | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) |
Compute the time derivative of the jacobian in body frame.
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, bodyVelB, bodyVelW, and motionSubspace. |
| sva::MotionVecd rbd::Jacobian::bodyNormalAcceleration | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) | const |
Compute the end body point normal acceleration in body coordinate (JDotBody·alpha).
| mb | MultiBody used has model. |
| mbc | Use bodyVelB, jointVelocity, parentToSon. |
| sva::MotionVecd rbd::Jacobian::bodyNormalAcceleration | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const std::vector< sva::MotionVecd > & | normalAccB | ||
| ) | const |
Compute the end body point normal acceleration in body coordinate (JDotBody·alpha).
| mb | MultiBody used has model. |
| mbc | Use nothing. |
| normalAccB | Normal bodies acceleration in body frame. |
| sva::MotionVecd rbd::Jacobian::bodyVelocity | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) | const |
Compute the end body point velocity in body coordinate (JBody·alpha).
| mb | MultiBody used has model. |
| mbc | Use bodyVelB. |
| Blocks rbd::Jacobian::compactPath | ( | const rbd::MultiBody & | mb | ) | const |
Compute a compact kinematic path, i.e. the sequence of consecutive blocks of DoF contained in the original path.
| mb | MultiBody used as model. |
|
inline |
| Eigen::MatrixXd rbd::Jacobian::expand | ( | const rbd::MultiBody & | mb, |
| const Eigen::Ref< const Eigen::MatrixXd > & | jac | ||
| ) | const |
Expand a symmetric product of a jacobian by its transpose onto every DoF.
| mb | MultiBody used as model. |
| jac | Result to expand |
| void rbd::Jacobian::expandAdd | ( | const Blocks & | compactPath, |
| const Eigen::Ref< const Eigen::MatrixXd > & | jac, | ||
| Eigen::MatrixXd & | res | ||
| ) | const |
Expand a symmetric product of a jacobian by its transpose onto every DoF and accumulate the result using a compact representation of the DoF.
| compactPath | Blocks representing the compact path kinematic path of the Jacobian |
| jac | Result to expand and accumulate |
| res | Accumulator matrix |
| void rbd::Jacobian::expandAdd | ( | const rbd::MultiBody & | mb, |
| const Eigen::Ref< const Eigen::MatrixXd > & | jac, | ||
| Eigen::MatrixXd & | res | ||
| ) | const |
Expand a symmetric product of a jacobian by its transpose onto every DoF and accumulate the result.
| mb | MultiBody used as model. |
| jac | Result to expand and accumulate |
| res | Accumulator matrix |
| void rbd::Jacobian::fullJacobian | ( | const MultiBody & | mb, |
| const Eigen::Ref< const Eigen::MatrixXd > & | jac, | ||
| Eigen::MatrixXd & | res | ||
| ) | const |
| const Eigen::MatrixXd& rbd::Jacobian::jacobian | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) |
| const Eigen::MatrixXd& rbd::Jacobian::jacobian | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const sva::PTransformd & | X_0_p | ||
| ) |
| const Eigen::MatrixXd& rbd::Jacobian::jacobianDot | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) |
Compute the time derivative of the jacobian.
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, bodyVelB, bodyVelW, and motionSubspace. |
|
inline |
| sva::MotionVecd rbd::Jacobian::normalAcceleration | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) | const |
Compute the end body point normal acceleration in world coordinate (JDot·alpha).
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, bodyVelW, bodyVelB, jointVelocity, parentToSon. |
| sva::MotionVecd rbd::Jacobian::normalAcceleration | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const std::vector< sva::MotionVecd > & | normalAccB | ||
| ) | const |
Compute the end body point normal acceleration in world coordinate (JDot·alpha).
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, bodyVelW, bodyVelB. |
| normalAccB | Normal bodies acceleration in body frame. |
| sva::MotionVecd rbd::Jacobian::normalAcceleration | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const std::vector< sva::MotionVecd > & | normalAccB, | ||
| const sva::PTransformd & | X_b_p, | ||
| const sva::MotionVecd & | V_b_p | ||
| ) | const |
Compute the end body point normal acceleration in world coordinate (JDot·alpha).
| mb | MultiBody used has model. |
| mbc | Use bodyVelB. |
| normalAccB | Normal bodies acceleration in body frame. |
| X_b_p | normal acceleration point/frame. |
| V_b_p | X_b_p velocity. |
| sva::MotionVecd rbd::Jacobian::normalAcceleration | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const sva::PTransformd & | X_b_p, | ||
| const sva::MotionVecd & | V_b_p | ||
| ) | const |
Compute the end body point normal acceleration in world coordinate (JDot·alpha).
| mb | MultiBody used has model. |
| mbc | Use bodyVelB, jointVelocity, parentToSon. |
| X_b_p | normal acceleration point/frame. |
| V_b_p | X_b_p velocity. |
|
inline |
|
inline |
| point | Static translation in the body exprimed in body coordinate. |
| const Eigen::MatrixXd& rbd::Jacobian::sBodyJacobian | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) |
safe version of
| std::domain_error | If mb don't match mbc or jointPath. |
| const Eigen::MatrixXd& rbd::Jacobian::sBodyJacobianDot | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) |
safe version of
| std::domain_error | If mb don't match mbc or jointPath. |
| sva::MotionVecd rbd::Jacobian::sBodyNormalAcceleration | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) | const |
| sva::MotionVecd rbd::Jacobian::sBodyNormalAcceleration | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const std::vector< sva::MotionVecd > & | normalAccB | ||
| ) | const |
safe version of
| std::domain_error | If mb don't match mbc or normalAccB. |
| sva::MotionVecd rbd::Jacobian::sBodyVelocity | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) | const |
| void rbd::Jacobian::sFullJacobian | ( | const MultiBody & | mb, |
| const Eigen::MatrixXd & | jac, | ||
| Eigen::MatrixXd & | res | ||
| ) | const |
safe version of
| std::domain_error | If mb don't match jointPath or res size missmatch. |
| const Eigen::MatrixXd& rbd::Jacobian::sJacobian | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) |
| const Eigen::MatrixXd& rbd::Jacobian::sJacobian | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const sva::PTransformd & | X_0_p | ||
| ) |
| const Eigen::MatrixXd& rbd::Jacobian::sJacobianDot | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) |
safe version of
| std::domain_error | If mb don't match mbc or jointPath. |
| sva::MotionVecd rbd::Jacobian::sNormalAcceleration | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) | const |
| sva::MotionVecd rbd::Jacobian::sNormalAcceleration | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const std::vector< sva::MotionVecd > & | normalAccB | ||
| ) | const |
safe version of
| std::domain_error | If mb don't match mbc or normalAccB. |
| sva::MotionVecd rbd::Jacobian::sNormalAcceleration | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const std::vector< sva::MotionVecd > & | normalAccB, | ||
| const sva::PTransformd & | X_b_p, | ||
| const sva::MotionVecd & | V_b_p | ||
| ) | const |
safe version of
| std::domain_error | If mb don't match mbc or normalAccB. |
| sva::MotionVecd rbd::Jacobian::sNormalAcceleration | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const sva::PTransformd & | X_b_p, | ||
| const sva::MotionVecd & | V_b_p | ||
| ) | const |
safe version of
| std::domain_error | If mb don't match mbc or normalAccB. |
| void rbd::Jacobian::sTranslateJacobian | ( | const Eigen::MatrixXd & | jac, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | point, | ||
| Eigen::MatrixXd & | res | ||
| ) |
safe version of
| std::domain_error | If mb don't match mbc or jointPath or res size missmatch. |
| const Eigen::MatrixXd& rbd::Jacobian::sVectorBodyJacobian | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | vec | ||
| ) |
safe version of
| std::domain_error | If mb don't match mbc or jointPath. |
| const Eigen::MatrixXd& rbd::Jacobian::sVectorJacobian | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | vec | ||
| ) |
safe version of
| std::domain_error | If mb don't match mbc or jointPath. |
| sva::MotionVecd rbd::Jacobian::sVelocity | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) | const |
| sva::MotionVecd rbd::Jacobian::sVelocity | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const sva::PTransformd & | X_b_p | ||
| ) | const |
| void rbd::Jacobian::translateBodyJacobian | ( | const Eigen::Ref< const Eigen::MatrixXd > & | jac, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | point, | ||
| Eigen::MatrixXd & | res | ||
| ) |
Translate a jacobian at a given position in body frame.
| jac | Jacobian to translate. |
| mbc | Use bodyPosW. |
| point | Point to translate jacobian. |
| res | Translated jacobian (must be allocated). |
| void rbd::Jacobian::translateJacobian | ( | const Eigen::Ref< const Eigen::MatrixXd > & | jac, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | point, | ||
| Eigen::MatrixXd & | res | ||
| ) |
Translate a jacobian at a given position.
| jac | Jacobian to translate. |
| mbc | Use bodyPosW. |
| point | Point to translate jacobian. |
| res | Translated jacobian (must be allocated). |
| const Eigen::MatrixXd& rbd::Jacobian::vectorBodyJacobian | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | vector | ||
| ) |
| const Eigen::MatrixXd& rbd::Jacobian::vectorJacobian | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const Eigen::Vector3d & | vector | ||
| ) |
| sva::MotionVecd rbd::Jacobian::velocity | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc | ||
| ) | const |
Compute the end body point velocity in world coordinate (J·alpha).
| mb | MultiBody used has model. |
| mbc | Use bodyPosW, bodyVelB. |
| sva::MotionVecd rbd::Jacobian::velocity | ( | const MultiBody & | mb, |
| const MultiBodyConfig & | mbc, | ||
| const sva::PTransformd & | X_b_p | ||
| ) | const |
Compute the end body point velocity at the point/frame specified by X_b_p.
| mb | MultiBody used has model. |
| mbc | Use bodyVelB. |
| X_b_p | velocity point/frame. |