Blender V2.61 - r43446

KDL::Segment Class Reference

This class encapsulates a simple segment, that is a "rigid body" (i.e., a frame and an inertia) with a joint and with "handles", root and tip to connect to other segments. More...

#include <segment.hpp>

List of all members.

Public Member Functions

 Segment (const Joint &joint=Joint(), const Frame &f_tip=Frame::Identity(), const Inertia &M=Inertia::Zero())
 Segment (const Segment &in)
Segmentoperator= (const Segment &arg)
virtual ~Segment ()
Frame pose (const double &q) const
Twist twist (const double &q, const double &qdot, int dof=0) const
Twist twist (const Vector &p, const double &qdot, int dof=0) const
Twist twist (const Frame &f, const double &qdot, int dof) const
const JointgetJoint () const
const InertiagetInertia () const
const FramegetFrameToTip () const

Friends

class Chain

Detailed Description

This class encapsulates a simple segment, that is a "rigid body" (i.e., a frame and an inertia) with a joint and with "handles", root and tip to connect to other segments.

A simple segment is described by the following properties :

  • Joint
  • inertia: of the rigid body part of the Segment
  • Offset from the end of the joint to the tip of the segment: the joint is located at the root of the segment.

Definition at line 46 of file segment.hpp.


Constructor & Destructor Documentation

KDL::Segment::Segment ( const Joint joint = Joint(),
const Frame f_tip = Frame::Identity(),
const Inertia M = Inertia::Zero() 
)

Constructor of the segment

Parameters:
jointjoint of the segment, default: Joint(Joint::None)
f_tipframe from the end of the joint to the tip of the segment, default: Frame::Identity()
Mrigid body inertia of the segment, default: Inertia::Zero()

Definition at line 27 of file segment.cpp.

KDL::Segment::Segment ( const Segment in)

Definition at line 33 of file segment.cpp.

KDL::Segment::~Segment ( ) [virtual]

Definition at line 47 of file segment.cpp.


Member Function Documentation

const Frame& KDL::Segment::getFrameToTip ( ) const [inline]

Request the pose from the joint end to the tip of the segment.

Returns:
const reference to the joint end - segment tip pose.

Definition at line 141 of file segment.hpp.

Referenced by KDL::ChainJntToJacSolver::JntToJac(), and KDL::operator<<().

const Inertia& KDL::Segment::getInertia ( ) const [inline]

Request the inertia of the segment

Returns:
const reference to the inertia of the segment

Definition at line 130 of file segment.hpp.

References M.

const Joint& KDL::Segment::getJoint ( ) const [inline]

Request the joint of the segment

Returns:
const reference to the joint of the segment

Definition at line 120 of file segment.hpp.

Referenced by KDL::Chain::addSegment(), KDL::Tree::addSegment(), KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), and KDL::operator<<().

Segment & KDL::Segment::operator= ( const Segment arg)

Definition at line 39 of file segment.cpp.

Frame KDL::Segment::pose ( const double &  q) const

Request the pose of the segment, given the joint position q.

Parameters:
q1D position of the joint
Returns:
pose from the root to the tip of the segment

Definition at line 51 of file segment.cpp.

References KDL::Joint::pose().

Referenced by KDL::ChainFkSolverPos_recursive::JntToCart(), and twist().

Twist KDL::Segment::twist ( const Vector p,
const double &  qdot,
int  dof = 0 
) const

Request the 6D-velocity at a given point p, relative to base frame of the segment givven the joint velocity qdot.

Parameters:
preference point
qdotND velocity of the joint
Returns:
6D-velocity at a given point p, expressed in the base-frame of the segment(root)

Definition at line 61 of file segment.cpp.

References KDL::Twist::RefPoint(), and KDL::Joint::twist().

Twist KDL::Segment::twist ( const double &  q,
const double &  qdot,
int  dof = 0 
) const

Request the 6D-velocity of the tip of the segment, given the joint position q and the joint velocity qdot.

Parameters:
qND position of the joint
qdotND velocity of the joint
Returns:
6D-velocity of the tip of the segment, expressed in the base-frame of the segment(root) and with the tip of the segment as reference point.

Definition at line 56 of file segment.cpp.

References p, pose(), KDL::Twist::RefPoint(), and KDL::Joint::twist().

Referenced by KDL::ChainJntToJacSolver::JntToJac().

Twist KDL::Segment::twist ( const Frame f,
const double &  qdot,
int  dof 
) const

Request the 6D-velocity at a given frame origin, relative to base frame of the segment assuming the frame rotation is the rotation of the joint.

Parameters:
fjoint pose frame + reference point
qdotND velocity of the joint
Returns:
6D-velocity at frame reference point, expressed in the base-frame of the segment(root)

Definition at line 66 of file segment.cpp.

References KDL::Frame::M, KDL::Frame::p, and KDL::Joint::twist().


Friends And Related Function Documentation

friend class Chain [friend]

Definition at line 47 of file segment.hpp.


The documentation for this class was generated from the following files: