KDL
1.4.0
|
6D Inertia of a articulated body More...
#include <src/articulatedbodyinertia.hpp>
Public Member Functions | |
ArticulatedBodyInertia () | |
This constructor creates a zero articulated body inertia matrix,. More... | |
ArticulatedBodyInertia (const RigidBodyInertia &rbi) | |
This constructor creates a cartesian space articulated body inertia matrix, the arguments is a rigid body inertia. More... | |
ArticulatedBodyInertia (double m, const Vector &oc=Vector::Zero(), const RotationalInertia &Ic=RotationalInertia::Zero()) | |
This constructor creates a cartesian space inertia matrix, the arguments are the mass, the vector from the reference point to cog and the rotational inertia in the cog. More... | |
~ArticulatedBodyInertia () | |
ArticulatedBodyInertia | RefPoint (const Vector &p) |
Reference point change with v the vector from the old to the new point expressed in the current reference frame. More... | |
ArticulatedBodyInertia (const Eigen::Matrix3d &M, const Eigen::Matrix3d &H, const Eigen::Matrix3d &I) | |
Static Public Member Functions | |
static ArticulatedBodyInertia | Zero () |
Creates an inertia with zero mass, and zero RotationalInertia. More... | |
Public Attributes | |
Eigen::Matrix3d | M |
Eigen::Matrix3d | H |
Eigen::Matrix3d | I |
Friends | |
ArticulatedBodyInertia | operator* (double a, const ArticulatedBodyInertia &I) |
Scalar product: I_new = double * I_old. More... | |
ArticulatedBodyInertia | operator+ (const ArticulatedBodyInertia &Ia, const ArticulatedBodyInertia &Ib) |
addition I: I_new = I_old1 + I_old2, make sure that I_old1 and I_old2 are expressed in the same reference frame/point, otherwise the result is worth nothing More... | |
ArticulatedBodyInertia | operator+ (const ArticulatedBodyInertia &Ia, const RigidBodyInertia &Ib) |
ArticulatedBodyInertia | operator- (const ArticulatedBodyInertia &Ia, const ArticulatedBodyInertia &Ib) |
ArticulatedBodyInertia | operator- (const ArticulatedBodyInertia &Ia, const RigidBodyInertia &Ib) |
Wrench | operator* (const ArticulatedBodyInertia &I, const Twist &t) |
calculate spatial momentum: h = I*v make sure that the twist v and the inertia are expressed in the same reference frame/point More... | |
ArticulatedBodyInertia | operator* (const Frame &T, const ArticulatedBodyInertia &I) |
Coordinate system transform Ia = T_a_b*Ib with T_a_b the frame from a to b. More... | |
ArticulatedBodyInertia | operator* (const Rotation &R, const ArticulatedBodyInertia &I) |
Reference frame orientation change Ia = R_a_b*Ib with R_a_b the rotation of b expressed in a. More... | |
6D Inertia of a articulated body
The inertia is defined in a certain reference point and a certain reference base. The reference point does not have to coincide with the origin of the reference frame.
|
inline |
This constructor creates a zero articulated body inertia matrix,.
References KDL::RotationalInertia::Zero(), Zero(), and KDL::Vector::Zero().
Referenced by Zero(), and ~ArticulatedBodyInertia().
KDL::ArticulatedBodyInertia::ArticulatedBodyInertia | ( | const RigidBodyInertia & | rbi | ) |
This constructor creates a cartesian space articulated body inertia matrix, the arguments is a rigid body inertia.
References KDL::RotationalInertia::data, KDL::RigidBodyInertia::h, KDL::RigidBodyInertia::I, and KDL::RigidBodyInertia::m.
|
explicit |
This constructor creates a cartesian space inertia matrix, the arguments are the mass, the vector from the reference point to cog and the rotational inertia in the cog.
|
inline |
References ArticulatedBodyInertia(), H, I, M, operator*, operator+, operator-, and RefPoint().
KDL::ArticulatedBodyInertia::ArticulatedBodyInertia | ( | const Eigen::Matrix3d & | M, |
const Eigen::Matrix3d & | H, | ||
const Eigen::Matrix3d & | I | ||
) |
ArticulatedBodyInertia KDL::ArticulatedBodyInertia::RefPoint | ( | const Vector & | p | ) |
Reference point change with v the vector from the old to the new point expressed in the current reference frame.
Referenced by ~ArticulatedBodyInertia().
|
inlinestatic |
Creates an inertia with zero mass, and zero RotationalInertia.
References ArticulatedBodyInertia().
Referenced by ArticulatedBodyInertia().
|
friend |
Scalar product: I_new = double * I_old.
Referenced by ~ArticulatedBodyInertia().
|
friend |
calculate spatial momentum: h = I*v make sure that the twist v and the inertia are expressed in the same reference frame/point
|
friend |
Coordinate system transform Ia = T_a_b*Ib with T_a_b the frame from a to b.
|
friend |
Reference frame orientation change Ia = R_a_b*Ib with R_a_b the rotation of b expressed in a.
|
friend |
addition I: I_new = I_old1 + I_old2, make sure that I_old1 and I_old2 are expressed in the same reference frame/point, otherwise the result is worth nothing
Referenced by ~ArticulatedBodyInertia().
|
friend |
|
friend |
Referenced by ~ArticulatedBodyInertia().
|
friend |
Eigen::Matrix3d KDL::ArticulatedBodyInertia::H |
Referenced by KDL::operator*(), KDL::operator+(), KDL::operator-(), and ~ArticulatedBodyInertia().
Eigen::Matrix3d KDL::ArticulatedBodyInertia::I |
Referenced by KDL::operator*(), KDL::operator+(), KDL::operator-(), and ~ArticulatedBodyInertia().
Eigen::Matrix3d KDL::ArticulatedBodyInertia::M |
Referenced by KDL::operator*(), KDL::operator+(), KDL::operator-(), and ~ArticulatedBodyInertia().