KDL::Segment Class Reference

This class encapsulates a simple segment, that is a "rigid body" (i.e., a frame and a rigid body 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

const FramegetFrameToTip () const
 Request the pose from the joint end to the tip of the segment.
const RigidBodyInertiagetInertia () const
 Request the inertia of the segment.
const JointgetJoint () const
 Request the joint of the segment.
const std::string & getName () const
 Request the name of the segment.
Segmentoperator= (const Segment &arg)
Frame pose (const double &q) const
 Request the pose of the segment, given the joint position q.
 Segment (const Segment &in)
 Segment (const Joint &joint=Joint(Joint::None), const Frame &f_tip=Frame::Identity(), const RigidBodyInertia &I=RigidBodyInertia::Zero())
 Constructor of the segment.
 Segment (const std::string &name, const Joint &joint=Joint(Joint::None), const Frame &f_tip=Frame::Identity(), const RigidBodyInertia &I=RigidBodyInertia::Zero())
 Constructor of the segment.
void setInertia (const RigidBodyInertia &Iin)
 Request the inertia of the segment.
Twist twist (const double &q, const double &qdot) const
 Request the 6D-velocity of the tip of the segment, given the joint position q and the joint velocity qdot.
virtual ~Segment ()

Friends

class Chain

Detailed Description

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

A simple segment is described by the following properties :

Definition at line 46 of file segment.hpp.


Constructor & Destructor Documentation

KDL::Segment::Segment ( const std::string &  name,
const Joint joint = Joint(Joint::None),
const Frame f_tip = Frame::Identity(),
const RigidBodyInertia I = RigidBodyInertia::Zero() 
)

Constructor of the segment.

Parameters:
name name of the segment
joint joint of the segment, default: Joint(Joint::None)
f_tip frame from the end of the joint to the tip of the segment, default: Frame::Identity()
I rigid body inertia of the segment, default: Inertia::Zero()

Definition at line 24 of file Robot/App/kdl_cp/Segment.cpp.

KDL::Segment::Segment ( const Joint joint = Joint(Joint::None),
const Frame f_tip = Frame::Identity(),
const RigidBodyInertia I = RigidBodyInertia::Zero() 
)

Constructor of the segment.

Parameters:
joint joint of the segment, default: Joint(Joint::None)
f_tip frame from the end of the joint to the tip of the segment, default: Frame::Identity()
I rigid body inertia of the segment, default: Inertia::Zero()

Definition at line 31 of file Robot/App/kdl_cp/Segment.cpp.

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

Definition at line 38 of file Robot/App/kdl_cp/Segment.cpp.

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

Definition at line 53 of file Robot/App/kdl_cp/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 149 of file segment.hpp.

Referenced by Robot::Robot6Axis::Save().

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

Request the inertia of the segment.

Returns:
const reference to the inertia of the segment

Definition at line 128 of file segment.hpp.

Referenced by KDL::ChainIdSolver_RNE::CartToJnt(), and KDL::ChainDynParam::JntToMass().

const Joint& KDL::Segment::getJoint (  )  const [inline]
const std::string& KDL::Segment::getName ( void   )  const [inline]

Request the name of the segment.

Returns:
const reference to the name of the segment

Definition at line 108 of file segment.hpp.

Referenced by KDL::Tree::addChain(), and KDL::Tree::addSegment().

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

Definition at line 44 of file Robot/App/kdl_cp/Segment.cpp.

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

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

Parameters:
q 1D position of the joint
Returns:
pose from the root to the tip of the segment

Definition at line 57 of file Robot/App/kdl_cp/Segment.cpp.

References KDL::Joint::pose().

Referenced by KDL::ChainIdSolver_RNE::CartToJnt(), KDL::Tree::getChain(), KDL::ChainFkSolverVel_recursive::JntToCart(), KDL::ChainFkSolverPos_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), and KDL::ChainDynParam::JntToMass().

void KDL::Segment::setInertia ( const RigidBodyInertia Iin  )  [inline]

Request the inertia of the segment.

Returns:
const reference to the inertia of the segment

Definition at line 138 of file segment.hpp.

Twist KDL::Segment::twist ( const double &  q,
const double &  qdot 
) const

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

Parameters:
q 1D position of the joint
qdot 1D 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 62 of file Robot/App/kdl_cp/Segment.cpp.

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

Referenced by KDL::ChainIdSolver_RNE::CartToJnt(), KDL::ChainFkSolverVel_recursive::JntToCart(), KDL::ChainJntToJacSolver::JntToJac(), and KDL::ChainDynParam::JntToMass().


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:

Generated on Wed Nov 23 19:02:19 2011 for FreeCAD by  doxygen 1.6.1