Robot types with implemented inverse kinematics. More...
#include <frame.h>
Public Types | |
enum | { BASE_NORMAL, BASE_GEOMETRY, BASE_COMBINED } |
enum | { FRAME_POSITION, FRAME_VELOCITY } |
Public Member Functions | |
void | addParent (CFrame *parent) |
CFrame () | |
CFrame (char *name) | |
virtual CFrame * | getBase () |
virtual char * | getBaseName () |
virtual unsigned int | getBaseType () |
virtual CFrame * | getByName (char *str) |
Returns frame associated with /a str. | |
virtual void * | getCopy () |
void | getDofs (std::vector< unsigned int > &dofs) |
void | getDofs (std::vector< double > &dofs_min, std::vector< double > &dofs_max) |
virtual unsigned int | getFrameType () |
virtual char * | getName () |
int | getParentId (CFrame *parent) |
std::vector< CFrame * > & | getParents () |
virtual CMatrix | getPose () |
virtual void | getPose (CMatrix &pose) |
virtual CMatrix | getRelativeToBase () |
Returns pose in the base (frame with no predecessor) frame. | |
virtual void | getRelativeToBase (CMatrix &mat) |
virtual double | getTime () |
virtual bool | hasName (char *str) |
virtual void | invalidate () |
virtual void | invalidateAll () |
bool | isData () |
bool | isUpdated () |
bool | isValid () |
void | lock () |
void | removeParent (CFrame *parent) |
virtual void | setBase (CFrame *base) |
virtual void | setBaseName (const char *str) |
virtual void | setBaseType (unsigned int type) |
bool | setData (bool value) |
void | setDofs (const std::vector< double > &dofs_min, const std::vector< double > &dofs_max) |
virtual void | setFrameType (unsigned int type) |
virtual void | setName (const char *str) |
virtual void | setPose (const CMatrix &pose) |
virtual void | setPoseNoInvalidation (const CMatrix &pose) |
virtual void | setRelativePose (const CMatrix &value) |
virtual void | setTime (double time) |
void | unlock () |
virtual void | update () |
Updates the frames. | |
virtual | ~CFrame () |
Public Attributes | |
unsigned long int | baseCounter |
unsigned long int | counter |
Protected Types | |
enum | { FRAME_X, FRAME_Y, FRAME_Z, FRAME_RX, FRAME_RY, FRAME_RZ, FRAME_DOFS } |
Protected Attributes | |
bool | _isData |
bool | _isLocked |
bool | _isUpdated |
bool | _isValid |
CFrame * | base |
(Relative) base frame (f.e. the static robot frame or the frame of the previous link in a kinematic chain) | |
std::string | baseName |
Name associated with frame. | |
int | baseType |
std::vector< CFrame * > | childs |
std::vector< double > | dofs_max |
std::vector< double > | dofs_min |
int | frameType |
std::string | name |
std::vector< CFrame * > | parents |
CMatrix | pose |
Translation and rotation relative to base frame (f.e. denavit hartenberg matrix) | |
CMatrix | relativePose |
double | time |
CMatrix | tmpMatrix |
Robot types with implemented inverse kinematics.
Frame in cartesian space
anonymous enum [protected] |
anonymous enum |
robotLibPbD::CFrame::CFrame | ( | char * | name | ) |
robotLibPbD::CFrame::~CFrame | ( | ) | [virtual] |
void robotLibPbD::CFrame::addParent | ( | CFrame * | parent | ) |
CFrame * robotLibPbD::CFrame::getBase | ( | ) | [inline, virtual] |
virtual char* robotLibPbD::CFrame::getBaseName | ( | ) | [inline, virtual] |
virtual unsigned int robotLibPbD::CFrame::getBaseType | ( | ) | [inline, virtual] |
CFrame * robotLibPbD::CFrame::getByName | ( | char * | str | ) | [virtual] |
void * robotLibPbD::CFrame::getCopy | ( | ) | [virtual] |
Reimplemented from CCopyInterface.
Reimplemented in robotLibPbD::CFrameCombination.
void robotLibPbD::CFrame::getDofs | ( | std::vector< unsigned int > & | dofs | ) |
void robotLibPbD::CFrame::getDofs | ( | std::vector< double > & | dofs_min, |
std::vector< double > & | dofs_max | ||
) |
virtual unsigned int robotLibPbD::CFrame::getFrameType | ( | ) | [inline, virtual] |
virtual char* robotLibPbD::CFrame::getName | ( | ) | [inline, virtual] |
int robotLibPbD::CFrame::getParentId | ( | CFrame * | parent | ) | [inline] |
std::vector<CFrame*>& robotLibPbD::CFrame::getParents | ( | ) | [inline] |
virtual CMatrix robotLibPbD::CFrame::getPose | ( | ) | [inline, virtual] |
virtual void robotLibPbD::CFrame::getPose | ( | CMatrix & | pose | ) | [inline, virtual] |
CMatrix robotLibPbD::CFrame::getRelativeToBase | ( | ) | [inline, virtual] |
Returns pose in the base (frame with no predecessor) frame.
Reimplemented in robotLibPbD::CFrameCombination, and robotLibPbD::CFrameReference.
void robotLibPbD::CFrame::getRelativeToBase | ( | CMatrix & | mat | ) | [inline, virtual] |
Reimplemented in robotLibPbD::CFrameCombination, and robotLibPbD::CFrameReference.
virtual double robotLibPbD::CFrame::getTime | ( | ) | [inline, virtual] |
bool robotLibPbD::CFrame::hasName | ( | char * | str | ) | [virtual] |
void robotLibPbD::CFrame::invalidate | ( | ) | [virtual] |
Reimplemented in robotLibPbD::CFrameCombination.
void robotLibPbD::CFrame::invalidateAll | ( | ) | [virtual] |
Reimplemented in robotLibPbD::CFrameCombination.
bool robotLibPbD::CFrame::isData | ( | ) | [inline] |
bool robotLibPbD::CFrame::isUpdated | ( | ) | [inline] |
bool robotLibPbD::CFrame::isValid | ( | ) | [inline] |
void robotLibPbD::CFrame::lock | ( | ) | [inline] |
void robotLibPbD::CFrame::removeParent | ( | CFrame * | parent | ) |
void robotLibPbD::CFrame::setBase | ( | CFrame * | base | ) | [virtual] |
virtual void robotLibPbD::CFrame::setBaseName | ( | const char * | str | ) | [inline, virtual] |
virtual void robotLibPbD::CFrame::setBaseType | ( | unsigned int | type | ) | [inline, virtual] |
bool robotLibPbD::CFrame::setData | ( | bool | value | ) | [inline] |
void robotLibPbD::CFrame::setDofs | ( | const std::vector< double > & | dofs_min, |
const std::vector< double > & | dofs_max | ||
) |
virtual void robotLibPbD::CFrame::setFrameType | ( | unsigned int | type | ) | [inline, virtual] |
void robotLibPbD::CFrame::setName | ( | const char * | str | ) | [virtual] |
virtual void robotLibPbD::CFrame::setPose | ( | const CMatrix & | pose | ) | [inline, virtual] |
Reimplemented in robotLibPbD::CFrameReference.
virtual void robotLibPbD::CFrame::setPoseNoInvalidation | ( | const CMatrix & | pose | ) | [inline, virtual] |
void robotLibPbD::CFrame::setRelativePose | ( | const CMatrix & | value | ) | [virtual] |
virtual void robotLibPbD::CFrame::setTime | ( | double | time | ) | [inline, virtual] |
void robotLibPbD::CFrame::unlock | ( | ) | [inline] |
void robotLibPbD::CFrame::update | ( | ) | [virtual] |
bool robotLibPbD::CFrame::_isData [protected] |
bool robotLibPbD::CFrame::_isLocked [protected] |
bool robotLibPbD::CFrame::_isUpdated [protected] |
bool robotLibPbD::CFrame::_isValid [protected] |
CFrame* robotLibPbD::CFrame::base [protected] |
unsigned long int robotLibPbD::CFrame::baseCounter |
std::string robotLibPbD::CFrame::baseName [protected] |
int robotLibPbD::CFrame::baseType [protected] |
std::vector<CFrame*> robotLibPbD::CFrame::childs [protected] |
unsigned long int robotLibPbD::CFrame::counter |
std::vector<double> robotLibPbD::CFrame::dofs_max [protected] |
std::vector<double> robotLibPbD::CFrame::dofs_min [protected] |
int robotLibPbD::CFrame::frameType [protected] |
std::string robotLibPbD::CFrame::name [protected] |
std::vector<CFrame*> robotLibPbD::CFrame::parents [protected] |
CMatrix robotLibPbD::CFrame::pose [protected] |
CMatrix robotLibPbD::CFrame::relativePose [protected] |
double robotLibPbD::CFrame::time [protected] |
CMatrix robotLibPbD::CFrame::tmpMatrix [protected] |