|
Blender V4.3
|
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>
Public Member Functions | |
| Segment (const Joint &joint=Joint(), const Frame &f_tip=Frame::Identity(), const Inertia &M=Inertia::Zero()) | |
| Segment (const Segment &in) | |
| Segment & | operator= (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 Joint & | getJoint () const |
| const Inertia & | getInertia () const |
| const Frame & | getFrameToTip () const |
Friends | |
| class | Chain |
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 :
Definition at line 46 of file segment.hpp.
| KDL::Segment::Segment | ( | const Joint & | joint = Joint(), |
| const Frame & | f_tip = Frame::Identity(), | ||
| const Inertia & | M = Inertia::Zero() ) |
Constructor 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() |
| M | rigid body inertia of the segment, default: Inertia::Zero() |
Definition at line 27 of file segment.cpp.
Referenced by Chain, operator=(), and Segment().
| KDL::Segment::Segment | ( | const Segment & | in | ) |
Definition at line 33 of file segment.cpp.
References Segment().
|
virtual |
Definition at line 47 of file segment.cpp.
|
inline |
Request the pose from the joint end to the tip of the segment.
Definition at line 141 of file segment.hpp.
|
inline |
Request the inertia of the segment
Definition at line 130 of file segment.hpp.
|
inline |
Request the joint of the segment
Definition at line 120 of file segment.hpp.
Definition at line 39 of file segment.cpp.
References Segment().
Request the pose of the segment, given the joint position q.
| q | 1D position of the joint |
Definition at line 51 of file segment.cpp.
Referenced by twist().
Request the 6D-velocity of the tip of the segment, given the joint position q and the joint velocity qdot.
| q | ND position of the joint |
| qdot | ND velocity of the joint |
Definition at line 56 of file segment.cpp.
References pose(), and KDL::Twist::RefPoint().
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.
| f | joint pose frame + reference point |
| qdot | ND velocity of the joint |
Definition at line 66 of file segment.cpp.
References KDL::Frame::M, KDL::Frame::p, and KDL::Twist::RefPoint().
Request the 6D-velocity at a given point p, relative to base frame of the segment givven the joint velocity qdot.
| p | reference point |
| qdot | ND velocity of the joint |
Definition at line 61 of file segment.cpp.
References KDL::Twist::RefPoint().
|
friend |
Definition at line 47 of file segment.hpp.
References Chain, KDL::Frame::Identity(), Segment(), and KDL::Inertia::Zero().
Referenced by Chain.