$search

KDL::ArticulatedBodyInertia Class Reference

6D Inertia of a articulated body More...

#include <articulatedbodyinertia.hpp>

List of all members.

Public Member Functions

 ArticulatedBodyInertia (const Eigen::Matrix3d &M, const Eigen::Matrix3d &H, const Eigen::Matrix3d &I)
 ArticulatedBodyInertia (double m, const Vector &oc=Vector::Zero(), const RotationalInertia &Ic=RotationalInertia::Zero())
 ArticulatedBodyInertia (const RigidBodyInertia &rbi)
 ArticulatedBodyInertia ()
ArticulatedBodyInertia RefPoint (const Vector &p)
 ~ArticulatedBodyInertia ()

Static Public Member Functions

static ArticulatedBodyInertia Zero ()

Public Attributes

Eigen::Matrix3d H
Eigen::Matrix3d I
Eigen::Matrix3d M

Friends

ArticulatedBodyInertia operator* (const Rotation &R, const ArticulatedBodyInertia &I)
ArticulatedBodyInertia operator* (const Frame &T, const ArticulatedBodyInertia &I)
Wrench operator* (const ArticulatedBodyInertia &I, const Twist &t)
ArticulatedBodyInertia operator* (double a, const ArticulatedBodyInertia &I)
ArticulatedBodyInertia operator+ (const ArticulatedBodyInertia &Ia, const RigidBodyInertia &Ib)
ArticulatedBodyInertia operator+ (const ArticulatedBodyInertia &Ia, const ArticulatedBodyInertia &Ib)
ArticulatedBodyInertia operator- (const ArticulatedBodyInertia &Ia, const RigidBodyInertia &Ib)
ArticulatedBodyInertia operator- (const ArticulatedBodyInertia &Ia, const ArticulatedBodyInertia &Ib)

Detailed Description

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.

Definition at line 37 of file articulatedbodyinertia.hpp.


Constructor & Destructor Documentation

KDL::ArticulatedBodyInertia::ArticulatedBodyInertia (  )  [inline]

This constructor creates a zero articulated body inertia matrix,

Definition at line 35 of file articulatedbodyinertia.hpp.

KDL::ArticulatedBodyInertia::ArticulatedBodyInertia ( const RigidBodyInertia rbi  ) 

This constructor creates a cartesian space articulated body inertia matrix, the arguments is a rigid body inertia.

Definition at line 30 of file articulatedbodyinertia.cpp.

KDL::ArticulatedBodyInertia::ArticulatedBodyInertia ( double  m,
const Vector oc = Vector::Zero(),
const RotationalInertia Ic = RotationalInertia::Zero() 
) [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.

Definition at line 40 of file articulatedbodyinertia.cpp.

KDL::ArticulatedBodyInertia::~ArticulatedBodyInertia (  )  [inline]

Definition at line 59 of file articulatedbodyinertia.hpp.

KDL::ArticulatedBodyInertia::ArticulatedBodyInertia ( const Eigen::Matrix3d &  M,
const Eigen::Matrix3d &  H,
const Eigen::Matrix3d &  I 
)

Member Function Documentation

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

Definition at line 99 of file articulatedbodyinertia.cpp.

static ArticulatedBodyInertia KDL::ArticulatedBodyInertia::Zero (  )  [inline, static]

Creates an inertia with zero mass, and zero RotationalInertia

Definition at line 54 of file articulatedbodyinertia.hpp.


Friends And Related Function Documentation

ArticulatedBodyInertia operator* ( const Rotation R,
const ArticulatedBodyInertia I 
) [friend]

Reference frame orientation change Ia = R_a_b*Ib with R_a_b the rotation of b expressed in a

Definition at line 94 of file articulatedbodyinertia.cpp.

ArticulatedBodyInertia operator* ( const Frame T,
const ArticulatedBodyInertia I 
) [friend]

Coordinate system transform Ia = T_a_b*Ib with T_a_b the frame from a to b.

Definition at line 79 of file articulatedbodyinertia.cpp.

Wrench operator* ( const ArticulatedBodyInertia I,
const Twist t 
) [friend]

calculate spatial momentum: h = I*v make sure that the twist v and the inertia are expressed in the same reference frame/point

Definition at line 72 of file articulatedbodyinertia.cpp.

ArticulatedBodyInertia operator* ( double  a,
const ArticulatedBodyInertia I 
) [friend]

Scalar product: I_new = double * I_old

Definition at line 53 of file articulatedbodyinertia.cpp.

ArticulatedBodyInertia operator+ ( const ArticulatedBodyInertia Ia,
const RigidBodyInertia Ib 
) [friend]
ArticulatedBodyInertia operator+ ( const ArticulatedBodyInertia Ia,
const ArticulatedBodyInertia Ib 
) [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

Definition at line 57 of file articulatedbodyinertia.cpp.

ArticulatedBodyInertia operator- ( const ArticulatedBodyInertia Ia,
const RigidBodyInertia Ib 
) [friend]
ArticulatedBodyInertia operator- ( const ArticulatedBodyInertia Ia,
const ArticulatedBodyInertia Ib 
) [friend]

Definition at line 64 of file articulatedbodyinertia.cpp.


Member Data Documentation

Definition at line 100 of file articulatedbodyinertia.hpp.

Definition at line 101 of file articulatedbodyinertia.hpp.

Definition at line 99 of file articulatedbodyinertia.hpp.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


orocos_kdl
Author(s): Ruben Smits, Erwin Aertbelien, Orocos Developers
autogenerated on Fri Mar 1 16:20:14 2013