Public Member Functions | Private Attributes | Friends
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

Frame getFrameToTip () const
const RigidBodyInertiagetInertia () const
const JointgetJoint () const
const std::string & getName () const
Segmentoperator= (const Segment &arg)
Frame pose (const double &q) const
 Segment (const std::string &name, const Joint &joint=Joint(Joint::None), const Frame &f_tip=Frame::Identity(), const RigidBodyInertia &I=RigidBodyInertia::Zero())
 Segment (const Joint &joint=Joint(Joint::None), const Frame &f_tip=Frame::Identity(), const RigidBodyInertia &I=RigidBodyInertia::Zero())
 Segment (const Segment &in)
void setInertia (const RigidBodyInertia &Iin)
Twist twist (const double &q, const double &qdot) const
virtual ~Segment ()

Private Attributes

Frame f_tip
RigidBodyInertia I
Joint joint
std::string name

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() 
) [explicit]

Constructor of the segment

Parameters:
namename of the segment
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 24 of file segment.cpp.

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

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 31 of file segment.cpp.

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

Definition at line 38 of file segment.cpp.

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

Definition at line 53 of file segment.cpp.


Member Function Documentation

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

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

Returns:
the original parent end - segment end pose.

Definition at line 149 of file segment.hpp.

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.

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 118 of file segment.hpp.

const std::string& KDL::Segment::getName ( ) 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.

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

Definition at line 44 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 57 of file segment.cpp.

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:
q1D position of the joint
qdot1D 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 segment.cpp.


Friends And Related Function Documentation

friend class Chain [friend]

Definition at line 47 of file segment.hpp.


Member Data Documentation

Definition at line 52 of file segment.hpp.

Definition at line 51 of file segment.hpp.

Definition at line 50 of file segment.hpp.

std::string KDL::Segment::name [private]

Definition at line 49 of file segment.hpp.


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


orocos_kdl
Author(s): Ruben Smits, Erwin Aertbelien, Orocos Developers
autogenerated on Sat Dec 28 2013 17:17:26