Public Member Functions | Public Attributes | Protected Member Functions
KinematicChain Class Reference

#include <KinematicChain.h>

Inheritance diagram for KinematicChain:
Inheritance graph
[legend]

List of all members.

Public Member Functions

std::map< std::string, double > getFullJointMap ()
std::vector< std::string > getJointName ()
std::vector< double > getJointPosition ()
int getNumberOfJoints ()
int getNumberOfLinks ()
 KinematicChain (int nlinks, int njoints)
void setJointPosition (double *q, int n)
void setJointPosition (std::vector< double > &q, std::vector< std::string > names=std::vector< std::string >())
void setJointVelocity (double *qdot, int n)
void setJointVelocity (std::vector< double > &qdot, std::vector< std::string > names=std::vector< std::string >())
 ~KinematicChain ()

Public Attributes

osg::ref_ptr
< osg::MatrixTransform > 
baseTransform
 pointer to the first node in the graph (base tranform)
std::vector< osg::ref_ptr
< osg::MatrixTransform > > 
joints
 pointers to transforms between links
std::vector< int > jointType
ros::WallTime last
 Bullet physics pointer to query.
std::vector< std::pair< double,
double > > 
limits
 Limits for joints by default -PI , PI.
std::vector< osg::ref_ptr
< osg::Node > > 
link
 pointers to link models
std::vector< MimicArmmimic
std::vector< std::string > names
BulletPhysicsphysics
std::vector< double > q
 Joint values.
std::vector< double > qLastSafe
 Last joint values not colliding.
int started
std::vector< osg::ref_ptr
< osg::MatrixTransform > > 
zerojoints
 pointers to original (zero) transforms between links

Protected Member Functions

virtual void updateJoints (std::vector< double > &q)=0
 Implemented by childs for joint position update.

Detailed Description

Abstract Kinematic Chain class for holding articulated 3D Models

Definition at line 33 of file KinematicChain.h.


Constructor & Destructor Documentation

KinematicChain::KinematicChain ( int  nlinks,
int  njoints 
)

Definition at line 17 of file KinematicChain.cpp.

Definition at line 191 of file KinematicChain.cpp.


Member Function Documentation

std::map< std::string, double > KinematicChain::getFullJointMap ( )

Definition at line 178 of file KinematicChain.cpp.

std::vector< std::string > KinematicChain::getJointName ( )

Definition at line 167 of file KinematicChain.cpp.

std::vector< double > KinematicChain::getJointPosition ( )

Definition at line 156 of file KinematicChain.cpp.

Get the number of joints

Definition at line 72 of file KinematicChain.h.

Get the number of links

Definition at line 67 of file KinematicChain.h.

void KinematicChain::setJointPosition ( double *  q,
int  n 
)

Definition at line 29 of file KinematicChain.cpp.

void KinematicChain::setJointPosition ( std::vector< double > &  q,
std::vector< std::string >  names = std::vector<std::string>() 
)

Definition at line 100 of file KinematicChain.cpp.

void KinematicChain::setJointVelocity ( double *  qdot,
int  n 
)

Definition at line 63 of file KinematicChain.cpp.

void KinematicChain::setJointVelocity ( std::vector< double > &  qdot,
std::vector< std::string >  names = std::vector<std::string>() 
)

Definition at line 128 of file KinematicChain.cpp.

virtual void KinematicChain::updateJoints ( std::vector< double > &  q) [protected, pure virtual]

Implemented by childs for joint position update.

Implemented in URDFRobot.


Member Data Documentation

osg::ref_ptr<osg::MatrixTransform> KinematicChain::baseTransform

pointer to the first node in the graph (base tranform)

Definition at line 45 of file KinematicChain.h.

std::vector<osg::ref_ptr<osg::MatrixTransform> > KinematicChain::joints

pointers to transforms between links

Definition at line 43 of file KinematicChain.h.

std::vector<int> KinematicChain::jointType

Definition at line 42 of file KinematicChain.h.

Bullet physics pointer to query.

Definition at line 53 of file KinematicChain.h.

std::vector<std::pair<double, double> > KinematicChain::limits

Limits for joints by default -PI , PI.

Definition at line 38 of file KinematicChain.h.

std::vector<osg::ref_ptr<osg::Node> > KinematicChain::link

pointers to link models

Definition at line 36 of file KinematicChain.h.

Definition at line 41 of file KinematicChain.h.

std::vector<std::string> KinematicChain::names

Definition at line 39 of file KinematicChain.h.

Definition at line 51 of file KinematicChain.h.

std::vector<double> KinematicChain::q

Joint values.

Definition at line 37 of file KinematicChain.h.

std::vector<double> KinematicChain::qLastSafe

Last joint values not colliding.

Definition at line 50 of file KinematicChain.h.

Definition at line 54 of file KinematicChain.h.

std::vector<osg::ref_ptr<osg::MatrixTransform> > KinematicChain::zerojoints

pointers to original (zero) transforms between links

Definition at line 44 of file KinematicChain.h.


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


uwsim
Author(s): Mario Prats , Javier Perez
autogenerated on Fri Aug 28 2015 13:28:58