Public Types | Public Member Functions | Public Attributes | Protected Types | Protected Attributes | List of all members
robotLibPbD::CFrame Class Reference

Robot types with implemented inverse kinematics. More...

#include <frame.h>

Inheritance diagram for robotLibPbD::CFrame:
Inheritance graph
[legend]

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 CFramegetBase ()
 
virtual char * getBaseName ()
 
virtual unsigned int getBaseType ()
 
virtual CFramegetByName (char *str)
 Returns frame associated with /a str. More...
 
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. More...
 
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. More...
 
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
 
CFramebase
 (Relative) base frame (f.e. the static robot frame or the frame of the previous link in a kinematic chain) More...
 
std::string baseName
 Name associated with frame. More...
 
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) More...
 
CMatrix relativePose
 
double time
 
CMatrix tmpMatrix
 

Detailed Description

Robot types with implemented inverse kinematics.

Frame in cartesian space

Definition at line 39 of file frame.h.

Member Enumeration Documentation

anonymous enum
protected
Enumerator
FRAME_X 
FRAME_Y 
FRAME_Z 
FRAME_RX 
FRAME_RY 
FRAME_RZ 
FRAME_DOFS 

Definition at line 42 of file frame.h.

anonymous enum
Enumerator
BASE_NORMAL 
BASE_GEOMETRY 
BASE_COMBINED 

Definition at line 69 of file frame.h.

anonymous enum
Enumerator
FRAME_POSITION 
FRAME_VELOCITY 

Definition at line 76 of file frame.h.

Constructor & Destructor Documentation

robotLibPbD::CFrame::CFrame ( )

Definition at line 509 of file frame.cpp.

robotLibPbD::CFrame::CFrame ( char *  name)

Definition at line 536 of file frame.cpp.

robotLibPbD::CFrame::~CFrame ( )
virtual

Definition at line 551 of file frame.cpp.

Member Function Documentation

void robotLibPbD::CFrame::addParent ( CFrame parent)

Definition at line 426 of file frame.cpp.

CFrame * robotLibPbD::CFrame::getBase ( )
inlinevirtual

Definition at line 482 of file frame.h.

virtual char* robotLibPbD::CFrame::getBaseName ( )
inlinevirtual

Definition at line 105 of file frame.h.

virtual unsigned int robotLibPbD::CFrame::getBaseType ( )
inlinevirtual

Definition at line 109 of file frame.h.

CFrame * robotLibPbD::CFrame::getByName ( char *  str)
virtual

Returns frame associated with /a str.

Definition at line 393 of file frame.cpp.

void * robotLibPbD::CFrame::getCopy ( )
virtual

Reimplemented from CCopyInterface.

Reimplemented in robotLibPbD::CFrameCombination.

Definition at line 451 of file frame.cpp.

void robotLibPbD::CFrame::getDofs ( std::vector< unsigned int > &  dofs)

Definition at line 501 of file frame.cpp.

void robotLibPbD::CFrame::getDofs ( std::vector< double > &  dofs_min,
std::vector< double > &  dofs_max 
)

Definition at line 493 of file frame.cpp.

virtual unsigned int robotLibPbD::CFrame::getFrameType ( )
inlinevirtual

Definition at line 114 of file frame.h.

virtual char* robotLibPbD::CFrame::getName ( )
inlinevirtual

Definition at line 103 of file frame.h.

int robotLibPbD::CFrame::getParentId ( CFrame parent)
inline

Definition at line 93 of file frame.h.

std::vector<CFrame*>& robotLibPbD::CFrame::getParents ( )
inline

Definition at line 90 of file frame.h.

virtual CMatrix robotLibPbD::CFrame::getPose ( )
inlinevirtual

Definition at line 118 of file frame.h.

virtual void robotLibPbD::CFrame::getPose ( CMatrix pose)
inlinevirtual

Definition at line 119 of file frame.h.

CMatrix robotLibPbD::CFrame::getRelativeToBase ( )
inlinevirtual

Returns pose in the base (frame with no predecessor) frame.

Reimplemented in robotLibPbD::CFrameCombination, and robotLibPbD::CFrameReference.

Definition at line 508 of file frame.h.

void robotLibPbD::CFrame::getRelativeToBase ( CMatrix mat)
inlinevirtual

Reimplemented in robotLibPbD::CFrameCombination, and robotLibPbD::CFrameReference.

Definition at line 488 of file frame.h.

virtual double robotLibPbD::CFrame::getTime ( )
inlinevirtual

Definition at line 134 of file frame.h.

bool robotLibPbD::CFrame::hasName ( char *  str)
virtual

Definition at line 605 of file frame.cpp.

void robotLibPbD::CFrame::invalidate ( )
virtual

Reimplemented in robotLibPbD::CFrameCombination.

Definition at line 1292 of file frame.cpp.

void robotLibPbD::CFrame::invalidateAll ( )
virtual

Reimplemented in robotLibPbD::CFrameCombination.

Definition at line 528 of file frame.cpp.

bool robotLibPbD::CFrame::isData ( )
inline

Definition at line 95 of file frame.h.

bool robotLibPbD::CFrame::isUpdated ( )
inline

Definition at line 98 of file frame.h.

bool robotLibPbD::CFrame::isValid ( )
inline

Definition at line 97 of file frame.h.

void robotLibPbD::CFrame::lock ( )
inline

Definition at line 99 of file frame.h.

void robotLibPbD::CFrame::removeParent ( CFrame parent)

Definition at line 402 of file frame.cpp.

void robotLibPbD::CFrame::setBase ( CFrame base)
virtual

Definition at line 587 of file frame.cpp.

virtual void robotLibPbD::CFrame::setBaseName ( const char *  str)
inlinevirtual

Definition at line 104 of file frame.h.

virtual void robotLibPbD::CFrame::setBaseType ( unsigned int  type)
inlinevirtual

Definition at line 108 of file frame.h.

bool robotLibPbD::CFrame::setData ( bool  value)
inline

Definition at line 96 of file frame.h.

void robotLibPbD::CFrame::setDofs ( const std::vector< double > &  dofs_min,
const std::vector< double > &  dofs_max 
)

Definition at line 84 of file frame.cpp.

virtual void robotLibPbD::CFrame::setFrameType ( unsigned int  type)
inlinevirtual

Definition at line 113 of file frame.h.

void robotLibPbD::CFrame::setName ( const char *  str)
virtual

Definition at line 610 of file frame.cpp.

virtual void robotLibPbD::CFrame::setPose ( const CMatrix pose)
inlinevirtual

Reimplemented in robotLibPbD::CFrameReference.

Definition at line 120 of file frame.h.

virtual void robotLibPbD::CFrame::setPoseNoInvalidation ( const CMatrix pose)
inlinevirtual

Definition at line 121 of file frame.h.

void robotLibPbD::CFrame::setRelativePose ( const CMatrix value)
virtual

Definition at line 576 of file frame.cpp.

virtual void robotLibPbD::CFrame::setTime ( double  time)
inlinevirtual

Definition at line 133 of file frame.h.

void robotLibPbD::CFrame::unlock ( )
inline

Definition at line 100 of file frame.h.

void robotLibPbD::CFrame::update ( )
virtual

Updates the frames.

Definition at line 615 of file frame.cpp.

Member Data Documentation

bool robotLibPbD::CFrame::_isData
protected

Definition at line 53 of file frame.h.

bool robotLibPbD::CFrame::_isLocked
protected

Definition at line 56 of file frame.h.

bool robotLibPbD::CFrame::_isUpdated
protected

Definition at line 56 of file frame.h.

bool robotLibPbD::CFrame::_isValid
protected

Definition at line 56 of file frame.h.

CFrame* robotLibPbD::CFrame::base
protected

(Relative) base frame (f.e. the static robot frame or the frame of the previous link in a kinematic chain)

Definition at line 57 of file frame.h.

unsigned long int robotLibPbD::CFrame::baseCounter

Definition at line 67 of file frame.h.

std::string robotLibPbD::CFrame::baseName
protected

Name associated with frame.

Definition at line 60 of file frame.h.

int robotLibPbD::CFrame::baseType
protected

Definition at line 61 of file frame.h.

std::vector<CFrame*> robotLibPbD::CFrame::childs
protected

Definition at line 65 of file frame.h.

unsigned long int robotLibPbD::CFrame::counter

Definition at line 67 of file frame.h.

std::vector<double> robotLibPbD::CFrame::dofs_max
protected

Definition at line 52 of file frame.h.

std::vector<double> robotLibPbD::CFrame::dofs_min
protected

Definition at line 52 of file frame.h.

int robotLibPbD::CFrame::frameType
protected

Definition at line 62 of file frame.h.

std::string robotLibPbD::CFrame::name
protected

Definition at line 60 of file frame.h.

std::vector<CFrame*> robotLibPbD::CFrame::parents
protected

Definition at line 65 of file frame.h.

CMatrix robotLibPbD::CFrame::pose
protected

Translation and rotation relative to base frame (f.e. denavit hartenberg matrix)

Definition at line 58 of file frame.h.

CMatrix robotLibPbD::CFrame::relativePose
protected

Definition at line 59 of file frame.h.

double robotLibPbD::CFrame::time
protected

Definition at line 63 of file frame.h.

CMatrix robotLibPbD::CFrame::tmpMatrix
protected

Definition at line 55 of file frame.h.


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


asr_kinematic_chain_optimizer
Author(s): Aumann Florian, Heller Florian, Jäkel Rainer, Wittenbeck Valerij
autogenerated on Mon Jun 10 2019 12:35:36