V-ART
|
Inverse Kinematic Chain. More...
#include <ikchain.h>
Public Member Functions | |
IKChain (SGPath path, Point4D eePos, Point4D eeOri) | |
Main constructor. More... | |
void | SetEEPosition (const Point4D &eePos) |
Sets the position of End Effector. More... | |
void | SetTargetPosition (const Point4D &target) |
Sets the target position. More... | |
void | MoveTowardsSolution () |
Adjusts the chain towards solution. More... | |
Protected Attributes | |
std::list< Dof * > | dofChain |
Chain (list) of DOFs. More... | |
Point4D | eePosition |
Position of end effector. More... | |
Point4D | eeOrientation |
Orientation of end effector. More... | |
Point4D | targetPos |
Target position. More... | |
Inverse Kinematic Chain.
Describes an inverse kinematics chain to be used on some IK solver. An IK chain is a sequence of DOFs and an end effector (position + orientation).
Main constructor.
path | [in] A SGPath that contains all joints in chain. |
eePos | [in] End Effector Position. |
eeOri | [in] End Effector Orientation. |
Definition at line 12 of file ikchain.cpp.
References dofChain, VART::Joint::GetDofs(), and VART::SGPath::Traverse().
void VART::IKChain::MoveTowardsSolution | ( | ) |
Adjusts the chain towards solution.
Definition at line 30 of file ikchain.cpp.
References VART::Transform::CopyMatrix(), and VART::Transform::MakeIdentity().
void VART::IKChain::SetEEPosition | ( | const Point4D & | eePos | ) |
Sets the position of End Effector.
Definition at line 25 of file ikchain.cpp.
|
inline |
|
protected |
|
protected |
|
protected |
|
protected |