Classes | Public Member Functions | Static Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
ColladaReader Class Reference

The colladadom reader that fills in the BodyInfoCollada_impl class. More...

Inheritance diagram for ColladaReader:
Inheritance graph
[legend]

Classes

class  ConstraintBinding
 
class  JointAxisBinding
 
class  KinematicsSceneBindings
 inter-collada bindings for a kinematics scene More...
 
class  LinkBinding
 

Public Member Functions

bool _ExtractActuator (boost::shared_ptr< LinkInfo > plink, daeElementRef instance_actuator)
 Extract an instance of a sensor. More...
 
template<typename T >
void _ExtractFullTransform (DblArray12 &tres, const T pelt)
 Travel by the transformation array and calls the getTransform method. More...
 
template<typename T >
void _ExtractFullTransformFromChildren (DblArray12 &tres, const T pelt)
 Travel by the transformation array and calls the getTransform method. More...
 
bool _ExtractGeometry (BodyInfoCollada_impl *pkinbody, boost::shared_ptr< LinkInfo > plink, const domTrianglesRef triRef, const domVerticesRef vertsRef, const map< string, int > &mapmaterials, const map< string, int > &maptextures)
 
bool _ExtractGeometry (BodyInfoCollada_impl *pkinbody, boost::shared_ptr< LinkInfo > plink, const domTrifansRef triRef, const domVerticesRef vertsRef, const map< string, int > &mapmaterials, const map< string, int > &maptextures)
 
bool _ExtractGeometry (BodyInfoCollada_impl *pkinbody, boost::shared_ptr< LinkInfo > plink, const domTristripsRef triRef, const domVerticesRef vertsRef, const map< string, int > &mapmaterials, const map< string, int > &maptextures)
 
bool _ExtractGeometry (BodyInfoCollada_impl *pkinbody, boost::shared_ptr< LinkInfo > plink, const domPolylistRef triRef, const domVerticesRef vertsRef, const map< string, int > &mapmaterials, const map< string, int > &maptextures)
 
bool _ExtractSensor (SensorInfo &psensor, daeElementRef instance_sensor)
 Extract an instance of a sensor. More...
 
void _FillMaterial (MaterialInfo &mat, const domMaterialRef pdommat)
 
daeElementRef _getElementFromUrl (const daeURI &uri)
 
bool _Init ()
 
void _ResetRobotCache ()
 
 ColladaReader ()
 
bool Extract (BodyInfoCollada_impl *probot)
 the first possible robot in the scene More...
 
bool ExtractArticulatedSystem (BodyInfoCollada_impl *&probot, domInstance_articulated_systemRef ias, KinematicsSceneBindings &bindings)
 extracts an articulated system. Note that an articulated system can include other articulated systems More...
 
bool ExtractGeometry (BodyInfoCollada_impl *pkinbody, boost::shared_ptr< LinkInfo > plink, const DblArray12 &tlink, const domNodeRef pdomnode, const std::list< JointAxisBinding > &listAxisBindings, const std::vector< std::string > &vprocessednodes)
 
bool ExtractGeometry (BodyInfoCollada_impl *pkinbody, boost::shared_ptr< LinkInfo > plink, const domGeometryRef geom, const map< string, int > &mapmaterials, const map< string, int > &maptextures)
 
bool ExtractKinematicsModel (BodyInfoCollada_impl *pkinbody, domInstance_kinematics_modelRef ikm, KinematicsSceneBindings &bindings)
 
bool ExtractKinematicsModel (BodyInfoCollada_impl *pkinbody, domNodeRef pdomnode, const KinematicsSceneBindings &bindings, const std::vector< std::string > &vprocessednodes)
 extract one rigid link composed of the node hierarchy More...
 
bool ExtractKinematicsModel (BodyInfoCollada_impl *pkinbody, domKinematics_modelRef kmodel, domNodeRef pnode, domPhysics_modelRef pmodel, const KinematicsSceneBindings bindings)
 append the kinematics model to the kinbody More...
 
int ExtractLink (BodyInfoCollada_impl *pkinbody, const domLinkRef pdomlink, const domNodeRef pdomnode, const DblArray12 &tParentWorldLink, const DblArray12 &tParentLink, const std::vector< domJointRef > &vdomjoints, const KinematicsSceneBindings bindings)
 Extract Link info and add it to an existing body. More...
 
void ExtractRobotAttachedActuators (BodyInfoCollada_impl *probot, const domArticulated_systemRef as)
 Extract Sensors attached to a Robot. More...
 
void ExtractRobotAttachedSensors (BodyInfoCollada_impl *probot, const domArticulated_systemRef as)
 Extract Sensors attached to a Robot. More...
 
void ExtractRobotManipulators (BodyInfoCollada_impl *probot, const domArticulated_systemRef as)
 extract the robot manipulators More...
 
boost::shared_ptr< LinkInfo > GetLink (const std::string &name)
 
template<typename T >
void getNodeParentTransform (DblArray12 &tres, const T pelt)
 
void getTransform (DblArray12 &tres, daeElementRef pelt)
 Gets all transformations applied to the node. More...
 
virtual void handleError (daeString msg)
 
virtual void handleWarning (daeString msg)
 
bool InitFromData (const string &pdata)
 
bool InitFromURL (const string &url)
 
void PostProcess (BodyInfoCollada_impl *probot)
 
virtual ~ColladaReader ()
 

Static Public Member Functions

template<typename U >
static xsBoolean resolveBool (domCommon_bool_or_paramRef paddr, const U &parent)
 
static bool resolveCommon_float_or_param (daeElementRef pcommon, daeElementRef parent, float &f)
 
template<typename U >
static domFloat resolveFloat (domCommon_float_or_paramRef paddr, const U &parent)
 
static daeElement * searchBinding (domCommon_sidref_or_paramRef paddr, daeElementRef parent)
 
static daeElement * searchBinding (daeString ref, daeElementRef parent)
 
static daeElement * searchBindingArray (daeString ref, const domInstance_articulated_system_Array &paramArray)
 
static daeElement * searchBindingArray (daeString ref, const domInstance_kinematics_model_Array &paramArray)
 

Private Member Functions

bool _checkMathML (daeElementRef pelt, const string &type)
 
std::string _ConvertToValidName (const std::string &name)
 
boost::shared_ptr< std::string > _ExtractInterfaceType (const daeElementRef pelt)
 returns an openrave interface type from the extra array More...
 
boost::shared_ptr< std::string > _ExtractInterfaceType (const domExtra_Array &arr)
 returns an openrave interface type from the extra array More...
 
std::string _ExtractLinkName (domLinkRef pdomlink)
 
std::string _ExtractMathML (daeElementRef proot, BodyInfoCollada_impl *pkinbody, daeElementRef pelt)
 Extracts MathML into fparser equation format. More...
 
domTechniqueRef _ExtractOpenRAVEProfile (const domTechnique_Array &arr)
 
daeElementRef _ExtractOpenRAVEProfile (const daeElementRef pelt)
 
std::string _ExtractParentId (daeElementRef p)
 
std::string _getElementName (daeElementRef pelt)
 get the element name without the namespace More...
 
std::pair< boost::shared_ptr< LinkInfo >,domJointRef > _getJointFromRef (xsToken targetref, daeElementRef peltref, BodyInfoCollada_impl *pkinbody)
 

Static Private Member Functions

static void _ExtractKinematicsVisualBindings (domInstance_with_extraRef viscene, domInstance_kinematics_sceneRef kiscene, KinematicsSceneBindings &bindings)
 go through all kinematics binds to get a kinematics/visual pair More...
 
static void _ExtractPhysicsBindings (domCOLLADA::domSceneRef allscene, KinematicsSceneBindings &bindings)
 
static dReal _GetUnitScale (daeElementRef pelt, dReal startscale)
 
static bool _IsValidCharInName (char c)
 
static bool _IsValidName (const std::string &s)
 

Private Attributes

bool _bOpeningZAE
 
boost::shared_ptr< DAE > _dae
 
domCOLLADA * _dom
 
dReal _fGlobalScale
 
std::string _filename
 
std::map< std::string, boost::shared_ptr< LinkInfo > > _mapJointIds
 
std::map< boost::shared_ptr< LinkInfo >, std::vector< dReal > > _mapJointUnits
 
std::map< std::string, boost::shared_ptr< LinkInfo > > _mapLinkNames
 
int _nGlobalActuatorId
 
int _nGlobalIndex
 
int _nGlobalManipulatorId
 
int _nGlobalSensorId
 
std::vector< std::string > _veclinknames
 
std::vector< boost::shared_ptr< LinkInfo > > _veclinks
 
DblArray12 rootOrigin
 
DblArray12 visualRootOrigin
 

Detailed Description

The colladadom reader that fills in the BodyInfoCollada_impl class.

It is separate from BodyInfoCollada_impl so that the colladadom resources do not have to remain allocated.

Definition at line 58 of file BodyInfoCollada_impl.cpp.

Constructor & Destructor Documentation

ColladaReader::ColladaReader ( )
inline

Definition at line 147 of file BodyInfoCollada_impl.cpp.

virtual ColladaReader::~ColladaReader ( )
inlinevirtual

Definition at line 151 of file BodyInfoCollada_impl.cpp.

Member Function Documentation

bool ColladaReader::_checkMathML ( daeElementRef  pelt,
const string &  type 
)
inlineprivate

Definition at line 2792 of file BodyInfoCollada_impl.cpp.

std::string ColladaReader::_ConvertToValidName ( const std::string &  name)
inlineprivate

Definition at line 3225 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::_ExtractActuator ( boost::shared_ptr< LinkInfo >  plink,
daeElementRef  instance_actuator 
)
inline

Extract an instance of a sensor.

Definition at line 2272 of file BodyInfoCollada_impl.cpp.

template<typename T >
void ColladaReader::_ExtractFullTransform ( DblArray12 &  tres,
const pelt 
)
inline

Travel by the transformation array and calls the getTransform method.

Definition at line 2583 of file BodyInfoCollada_impl.cpp.

template<typename T >
void ColladaReader::_ExtractFullTransformFromChildren ( DblArray12 &  tres,
const pelt 
)
inline

Travel by the transformation array and calls the getTransform method.

Definition at line 2594 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::_ExtractGeometry ( BodyInfoCollada_impl pkinbody,
boost::shared_ptr< LinkInfo >  plink,
const domTrianglesRef  triRef,
const domVerticesRef  vertsRef,
const map< string, int > &  mapmaterials,
const map< string, int > &  maptextures 
)
inline

Extract the Geometry in TRIANGLES and adds it to OpenRave

Parameters
triRefArray of triangles of the COLLADA's model
vertsRefArray of vertices of the COLLADA's model
mapmaterialsMaterials applied to the geometry
plinkLink of the kinematics model

Definition at line 1242 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::_ExtractGeometry ( BodyInfoCollada_impl pkinbody,
boost::shared_ptr< LinkInfo >  plink,
const domTrifansRef  triRef,
const domVerticesRef  vertsRef,
const map< string, int > &  mapmaterials,
const map< string, int > &  maptextures 
)
inline

Extract the Geometry in TRIGLE FANS and adds it to OpenRave

Parameters
triRefArray of triangle fans of the COLLADA's model
vertsRefArray of vertices of the COLLADA's model
mapmaterialsMaterials applied to the geometry
plinkLink of the kinematics model

Definition at line 1506 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::_ExtractGeometry ( BodyInfoCollada_impl pkinbody,
boost::shared_ptr< LinkInfo >  plink,
const domTristripsRef  triRef,
const domVerticesRef  vertsRef,
const map< string, int > &  mapmaterials,
const map< string, int > &  maptextures 
)
inline

Extract the Geometry in TRIANGLE STRIPS and adds it to OpenRave

Parameters
triRefArray of Triangle Strips of the COLLADA's model
vertsRefArray of vertices of the COLLADA's model
mapmaterialsMaterials applied to the geometry
plinkLink of the kinematics model

Definition at line 1601 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::_ExtractGeometry ( BodyInfoCollada_impl pkinbody,
boost::shared_ptr< LinkInfo >  plink,
const domPolylistRef  triRef,
const domVerticesRef  vertsRef,
const map< string, int > &  mapmaterials,
const map< string, int > &  maptextures 
)
inline

Extract the Geometry in TRIANGLE STRIPS and adds it to OpenRave

Parameters
triRefArray of Triangle Strips of the COLLADA's model
vertsRefArray of vertices of the COLLADA's model
mapmaterialsMaterials applied to the geometry
plinkLink of the kinematics model

Definition at line 1699 of file BodyInfoCollada_impl.cpp.

boost::shared_ptr<std::string> ColladaReader::_ExtractInterfaceType ( const daeElementRef  pelt)
inlineprivate

returns an openrave interface type from the extra array

Definition at line 2746 of file BodyInfoCollada_impl.cpp.

boost::shared_ptr<std::string> ColladaReader::_ExtractInterfaceType ( const domExtra_Array &  arr)
inlineprivate

returns an openrave interface type from the extra array

Definition at line 2764 of file BodyInfoCollada_impl.cpp.

static void ColladaReader::_ExtractKinematicsVisualBindings ( domInstance_with_extraRef  viscene,
domInstance_kinematics_sceneRef  kiscene,
KinematicsSceneBindings bindings 
)
inlinestaticprivate

go through all kinematics binds to get a kinematics/visual pair

Parameters
kisceneinstance of one kinematics scene, binds the kinematic and visual models
bindingsthe extracted bindings

Definition at line 2639 of file BodyInfoCollada_impl.cpp.

std::string ColladaReader::_ExtractLinkName ( domLinkRef  pdomlink)
inlineprivate

Definition at line 2779 of file BodyInfoCollada_impl.cpp.

std::string ColladaReader::_ExtractMathML ( daeElementRef  proot,
BodyInfoCollada_impl pkinbody,
daeElementRef  pelt 
)
inlineprivate

Extracts MathML into fparser equation format.

Definition at line 2857 of file BodyInfoCollada_impl.cpp.

domTechniqueRef ColladaReader::_ExtractOpenRAVEProfile ( const domTechnique_Array &  arr)
inlineprivate

Definition at line 2723 of file BodyInfoCollada_impl.cpp.

daeElementRef ColladaReader::_ExtractOpenRAVEProfile ( const daeElementRef  pelt)
inlineprivate

Definition at line 2733 of file BodyInfoCollada_impl.cpp.

std::string ColladaReader::_ExtractParentId ( daeElementRef  p)
inlineprivate

Definition at line 2846 of file BodyInfoCollada_impl.cpp.

static void ColladaReader::_ExtractPhysicsBindings ( domCOLLADA::domSceneRef  allscene,
KinematicsSceneBindings bindings 
)
inlinestaticprivate

Definition at line 2692 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::_ExtractSensor ( SensorInfo &  psensor,
daeElementRef  instance_sensor 
)
inline

Extract an instance of a sensor.

Definition at line 2088 of file BodyInfoCollada_impl.cpp.

void ColladaReader::_FillMaterial ( MaterialInfo &  mat,
const domMaterialRef  pdommat 
)
inline

Paint the Geometry with the color material

Parameters
pmatMaterial info of the COLLADA's model
geomGeometry properties in OpenRAVE

Definition at line 1946 of file BodyInfoCollada_impl.cpp.

daeElementRef ColladaReader::_getElementFromUrl ( const daeURI &  uri)
inline

Definition at line 2322 of file BodyInfoCollada_impl.cpp.

std::string ColladaReader::_getElementName ( daeElementRef  pelt)
inlineprivate

get the element name without the namespace

Definition at line 2837 of file BodyInfoCollada_impl.cpp.

std::pair<boost::shared_ptr<LinkInfo> ,domJointRef> ColladaReader::_getJointFromRef ( xsToken  targetref,
daeElementRef  peltref,
BodyInfoCollada_impl pkinbody 
)
inlineprivate

Definition at line 2806 of file BodyInfoCollada_impl.cpp.

static dReal ColladaReader::_GetUnitScale ( daeElementRef  pelt,
dReal  startscale 
)
inlinestaticprivate

Definition at line 3242 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::_Init ( )
inline

Definition at line 194 of file BodyInfoCollada_impl.cpp.

static bool ColladaReader::_IsValidCharInName ( char  c)
inlinestaticprivate

Definition at line 3217 of file BodyInfoCollada_impl.cpp.

static bool ColladaReader::_IsValidName ( const std::string &  s)
inlinestaticprivate

Definition at line 3218 of file BodyInfoCollada_impl.cpp.

void ColladaReader::_ResetRobotCache ( )
inline

Definition at line 205 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::Extract ( BodyInfoCollada_impl probot)
inline

the first possible robot in the scene

Definition at line 215 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::ExtractArticulatedSystem ( BodyInfoCollada_impl *&  probot,
domInstance_articulated_systemRef  ias,
KinematicsSceneBindings bindings 
)
inline

extracts an articulated system. Note that an articulated system can include other articulated systems

Parameters
probotthe robot to be created from the system

Definition at line 349 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::ExtractGeometry ( BodyInfoCollada_impl pkinbody,
boost::shared_ptr< LinkInfo >  plink,
const DblArray12 &  tlink,
const domNodeRef  pdomnode,
const std::list< JointAxisBinding > &  listAxisBindings,
const std::vector< std::string > &  vprocessednodes 
)
inline

Extract Geometry and apply the transformations of the node

Parameters
pdomnodeNode to extract the goemetry
plinkLink of the kinematics model

Definition at line 1104 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::ExtractGeometry ( BodyInfoCollada_impl pkinbody,
boost::shared_ptr< LinkInfo >  plink,
const domGeometryRef  geom,
const map< string, int > &  mapmaterials,
const map< string, int > &  maptextures 
)
inline

Extract the Geometry and adds it to OpenRave

Parameters
geomGeometry to extract of the COLLADA's model
mapmaterialsMaterials applied to the geometry
plinkLink of the kinematics model

Definition at line 1789 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::ExtractKinematicsModel ( BodyInfoCollada_impl pkinbody,
domInstance_kinematics_modelRef  ikm,
KinematicsSceneBindings bindings 
)
inline

Definition at line 440 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::ExtractKinematicsModel ( BodyInfoCollada_impl pkinbody,
domNodeRef  pdomnode,
const KinematicsSceneBindings bindings,
const std::vector< std::string > &  vprocessednodes 
)
inline

extract one rigid link composed of the node hierarchy

Definition at line 495 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::ExtractKinematicsModel ( BodyInfoCollada_impl pkinbody,
domKinematics_modelRef  kmodel,
domNodeRef  pnode,
domPhysics_modelRef  pmodel,
const KinematicsSceneBindings  bindings 
)
inline

append the kinematics model to the kinbody

Definition at line 527 of file BodyInfoCollada_impl.cpp.

int ColladaReader::ExtractLink ( BodyInfoCollada_impl pkinbody,
const domLinkRef  pdomlink,
const domNodeRef  pdomnode,
const DblArray12 &  tParentWorldLink,
const DblArray12 &  tParentLink,
const std::vector< domJointRef > &  vdomjoints,
const KinematicsSceneBindings  bindings 
)
inline

Extract Link info and add it to an existing body.

Definition at line 725 of file BodyInfoCollada_impl.cpp.

void ColladaReader::ExtractRobotAttachedActuators ( BodyInfoCollada_impl probot,
const domArticulated_systemRef  as 
)
inline

Extract Sensors attached to a Robot.

Definition at line 2064 of file BodyInfoCollada_impl.cpp.

void ColladaReader::ExtractRobotAttachedSensors ( BodyInfoCollada_impl probot,
const domArticulated_systemRef  as 
)
inline

Extract Sensors attached to a Robot.

Definition at line 2009 of file BodyInfoCollada_impl.cpp.

void ColladaReader::ExtractRobotManipulators ( BodyInfoCollada_impl probot,
const domArticulated_systemRef  as 
)
inline

extract the robot manipulators

Definition at line 1988 of file BodyInfoCollada_impl.cpp.

boost::shared_ptr<LinkInfo> ColladaReader::GetLink ( const std::string &  name)
inline

Definition at line 713 of file BodyInfoCollada_impl.cpp.

template<typename T >
void ColladaReader::getNodeParentTransform ( DblArray12 &  tres,
const pelt 
)
inline

Travels recursively the node parents of the given one to extract the Transform arrays that affects the node given

Definition at line 2570 of file BodyInfoCollada_impl.cpp.

void ColladaReader::getTransform ( DblArray12 &  tres,
daeElementRef  pelt 
)
inline

Gets all transformations applied to the node.

Definition at line 2515 of file BodyInfoCollada_impl.cpp.

virtual void ColladaReader::handleError ( daeString  msg)
inlinevirtual

Definition at line 2620 of file BodyInfoCollada_impl.cpp.

virtual void ColladaReader::handleWarning ( daeString  msg)
inlinevirtual

Definition at line 2628 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::InitFromData ( const string &  pdata)
inline

Definition at line 183 of file BodyInfoCollada_impl.cpp.

bool ColladaReader::InitFromURL ( const string &  url)
inline

Definition at line 156 of file BodyInfoCollada_impl.cpp.

void ColladaReader::PostProcess ( BodyInfoCollada_impl probot)
inline

Definition at line 275 of file BodyInfoCollada_impl.cpp.

template<typename U >
static xsBoolean ColladaReader::resolveBool ( domCommon_bool_or_paramRef  paddr,
const U &  parent 
)
inlinestatic

Definition at line 2436 of file BodyInfoCollada_impl.cpp.

static bool ColladaReader::resolveCommon_float_or_param ( daeElementRef  pcommon,
daeElementRef  parent,
float &  f 
)
inlinestatic

Definition at line 2491 of file BodyInfoCollada_impl.cpp.

template<typename U >
static domFloat ColladaReader::resolveFloat ( domCommon_float_or_paramRef  paddr,
const U &  parent 
)
inlinestatic

Definition at line 2463 of file BodyInfoCollada_impl.cpp.

static daeElement* ColladaReader::searchBinding ( domCommon_sidref_or_paramRef  paddr,
daeElementRef  parent 
)
inlinestatic

Definition at line 2327 of file BodyInfoCollada_impl.cpp.

static daeElement* ColladaReader::searchBinding ( daeString  ref,
daeElementRef  parent 
)
inlinestatic

Search a given parameter reference and stores the new reference to search.

Parameters
refthe reference name to search
parentThe array of parameter where the method searchs.

Definition at line 2341 of file BodyInfoCollada_impl.cpp.

static daeElement* ColladaReader::searchBindingArray ( daeString  ref,
const domInstance_articulated_system_Array &  paramArray 
)
inlinestatic

Definition at line 2414 of file BodyInfoCollada_impl.cpp.

static daeElement* ColladaReader::searchBindingArray ( daeString  ref,
const domInstance_kinematics_model_Array &  paramArray 
)
inlinestatic

Definition at line 2425 of file BodyInfoCollada_impl.cpp.

Member Data Documentation

bool ColladaReader::_bOpeningZAE
private

Definition at line 3256 of file BodyInfoCollada_impl.cpp.

boost::shared_ptr<DAE> ColladaReader::_dae
private

Definition at line 3255 of file BodyInfoCollada_impl.cpp.

domCOLLADA* ColladaReader::_dom
private

Definition at line 3257 of file BodyInfoCollada_impl.cpp.

dReal ColladaReader::_fGlobalScale
private

Definition at line 3258 of file BodyInfoCollada_impl.cpp.

std::string ColladaReader::_filename
private

Definition at line 3265 of file BodyInfoCollada_impl.cpp.

std::map<std::string,boost::shared_ptr<LinkInfo> > ColladaReader::_mapJointIds
private

Definition at line 3260 of file BodyInfoCollada_impl.cpp.

std::map<boost::shared_ptr<LinkInfo> , std::vector<dReal> > ColladaReader::_mapJointUnits
private

Definition at line 3259 of file BodyInfoCollada_impl.cpp.

std::map<std::string,boost::shared_ptr<LinkInfo> > ColladaReader::_mapLinkNames
private

Definition at line 3261 of file BodyInfoCollada_impl.cpp.

int ColladaReader::_nGlobalActuatorId
private

Definition at line 3264 of file BodyInfoCollada_impl.cpp.

int ColladaReader::_nGlobalIndex
private

Definition at line 3264 of file BodyInfoCollada_impl.cpp.

int ColladaReader::_nGlobalManipulatorId
private

Definition at line 3264 of file BodyInfoCollada_impl.cpp.

int ColladaReader::_nGlobalSensorId
private

Definition at line 3264 of file BodyInfoCollada_impl.cpp.

std::vector<std::string> ColladaReader::_veclinknames
private

Definition at line 3263 of file BodyInfoCollada_impl.cpp.

std::vector<boost::shared_ptr<LinkInfo> > ColladaReader::_veclinks
private

Definition at line 3262 of file BodyInfoCollada_impl.cpp.

DblArray12 ColladaReader::rootOrigin
private

Definition at line 3266 of file BodyInfoCollada_impl.cpp.

DblArray12 ColladaReader::visualRootOrigin
private

Definition at line 3267 of file BodyInfoCollada_impl.cpp.


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


openhrp3
Author(s): AIST, General Robotix Inc., Nakamura Lab of Dept. of Mechano Informatics at University of Tokyo
autogenerated on Sat May 8 2021 02:42:42