Classes | |
| struct | GEOMPROPERTIES |
| class | JointAxisBinding |
| class | KinematicsSceneBindings |
| inter-collada bindings for a kinematics scene More... | |
| class | LinkBinding |
| bindings for links between different spaces More... | |
| struct | USERDATA |
Public Member Functions | |
| ColladaModelReader (urdf::ModelInterfaceSharedPtr model) | |
| bool | InitFromData (const std::string &pdata) |
| bool | InitFromFile (const std::string &filename) |
| virtual | ~ColladaModelReader () |
Protected Member Functions | |
| bool | _checkMathML (daeElementRef pelt, const std::string &type) |
| size_t | _countChildren (daeElement *pelt) |
| urdf::GeometrySharedPtr | _CreateGeometry (const std::string &name, const std::list< GEOMPROPERTIES > &listGeomProperties) |
| void | _decompose (const boost::array< double, 12 > &tm, Pose &tout, Vector3 &vscale) |
| bool | _Extract () |
| the first possible robot in the scene | |
| bool | _ExtractArticulatedSystem (domInstance_articulated_systemRef ias, KinematicsSceneBindings &bindings) |
| extracts an articulated system. Note that an articulated system can include other articulated systems | |
| void | _ExtractGeometry (const domNodeRef pdomnode, std::list< GEOMPROPERTIES > &listGeomProperties, const std::list< JointAxisBinding > &listAxisBindings, const Pose &tlink) |
| bool | _ExtractGeometry (const domTrianglesRef triRef, const domVerticesRef vertsRef, const std::map< std::string, domMaterialRef > &mapmaterials, std::list< GEOMPROPERTIES > &listGeomProperties) |
| bool | _ExtractGeometry (const domTrifansRef triRef, const domVerticesRef vertsRef, const std::map< std::string, domMaterialRef > &mapmaterials, std::list< GEOMPROPERTIES > &listGeomProperties) |
| bool | _ExtractGeometry (const domTristripsRef triRef, const domVerticesRef vertsRef, const std::map< std::string, domMaterialRef > &mapmaterials, std::list< GEOMPROPERTIES > &listGeomProperties) |
| bool | _ExtractGeometry (const domPolylistRef triRef, const domVerticesRef vertsRef, const std::map< std::string, domMaterialRef > &mapmaterials, std::list< GEOMPROPERTIES > &listGeomProperties) |
| bool | _ExtractGeometry (const domGeometryRef geom, const std::map< std::string, domMaterialRef > &mapmaterials, std::list< GEOMPROPERTIES > &listGeomProperties) |
| boost::shared_ptr< std::string > | _ExtractInterfaceType (const domExtra_Array &arr) |
| returns an openrave interface type from the extra array | |
| bool | _ExtractKinematicsModel (domInstance_kinematics_modelRef ikm, KinematicsSceneBindings &bindings) |
| bool | _ExtractKinematicsModel (domKinematics_modelRef kmodel, domNodeRef pnode, domPhysics_modelRef pmodel, const KinematicsSceneBindings &bindings) |
| append the kinematics model to the openrave kinbody | |
| urdf::LinkSharedPtr | _ExtractLink (const domLinkRef pdomlink, const domNodeRef pdomnode, const Pose &tParentWorldLink, const Pose &tParentLink, const std::vector< domJointRef > &vdomjoints, const KinematicsSceneBindings &bindings) |
| Extract Link info and add it to an existing body. | |
| std::string | _ExtractLinkName (domLinkRef pdomlink) |
| domTechniqueRef | _ExtractOpenRAVEProfile (const domTechnique_Array &arr) |
| void | _ExtractRobotAttachedActuators (const domArticulated_systemRef as) |
| extract the robot actuators | |
| void | _ExtractRobotAttachedSensors (const domArticulated_systemRef as) |
| Extract Sensors attached to a Robot. | |
| void | _ExtractRobotManipulators (const domArticulated_systemRef as) |
| extract the robot manipulators | |
| void | _FillGeometryColor (const domMaterialRef pmat, GEOMPROPERTIES &geom) |
| daeElementRef | _getElementFromUrl (const daeURI &uri) |
| urdf::JointSharedPtr | _getJointFromRef (xsToken targetref, daeElementRef peltref) |
| USERDATA * | _getUserData (daeElement *pelt) |
| void | _PostProcess () |
| void | _processUserData (daeElement *pelt, double scale) |
| virtual void | handleError (daeString msg) |
| virtual void | handleWarning (daeString msg) |
Static Protected Member Functions | |
| static Vector3 | _add3 (const Vector3 &v0, const Vector3 &v1) |
| static Vector3 | _cross3 (const Vector3 &v0, const Vector3 &v1) |
| static double | _dot3 (const Vector3 &v0, const Vector3 &v1) |
| template<typename T > | |
| static boost::array< double, 12 > | _ExtractFullTransform (const T pelt) |
| Travel by the transformation array and calls the _getTransform method. | |
| template<typename T > | |
| static boost::array< double, 12 > | _ExtractFullTransformFromChildren (const T pelt) |
| Travel by the transformation array and calls the _getTransform method. | |
| static void | _ExtractKinematicsVisualBindings (domInstance_with_extraRef viscene, domInstance_kinematics_sceneRef kiscene, KinematicsSceneBindings &bindings) |
| go through all kinematics binds to get a kinematics/visual pair | |
| static void | _ExtractPhysicsBindings (domCOLLADA::domSceneRef allscene, KinematicsSceneBindings &bindings) |
| template<typename T > | |
| static boost::array< double, 12 > | _getNodeParentTransform (const T pelt) |
| static boost::array< double, 12 > | _getTransform (daeElementRef pelt) |
| Gets all transformations applied to the node. | |
| static double | _GetUnitScale (daeElement *pelt) |
| static boost::array< double, 12 > | _matrixFromAxisAngle (const Vector3 &axis, double angle) |
| static boost::array< double, 12 > | _matrixFromPose (const Pose &t) |
| static boost::array< double, 12 > | _matrixFromQuat (const Rotation &quat) |
| static boost::array< double, 12 > | _matrixIdentity () |
| static Vector3 | _normalize3 (const Vector3 &v0) |
| static Pose | _poseFromMatrix (const boost::array< double, 12 > &m) |
| static Pose | _poseInverse (const Pose &p) |
| static Vector3 | _poseMult (const Pose &p, const Vector3 &v) |
| static Vector3 | _poseMult (const boost::array< double, 12 > &m, const Vector3 &v) |
| static boost::array< double, 12 > | _poseMult (const boost::array< double, 12 > &m0, const boost::array< double, 12 > &m1) |
| static Pose | _poseMult (const Pose &p0, const Pose &p1) |
| static Rotation | _quatFromAxisAngle (double x, double y, double z, double angle) |
| static Rotation | _quatFromMatrix (const boost::array< double, 12 > &mat) |
| static Rotation | _quatMult (const Rotation &quat0, const Rotation &quat1) |
| static Vector3 | _sub3 (const Vector3 &v0, const Vector3 &v1) |
| 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 ¶mArray) |
| static daeElement * | searchBindingArray (daeString ref, const domInstance_kinematics_model_Array ¶mArray) |
Protected Attributes | |
| boost::shared_ptr< DAE > | _collada |
| domCOLLADA * | _dom |
| std::string | _filename |
| urdf::ModelInterfaceSharedPtr | _model |
| int | _nGlobalManipulatorId |
| int | _nGlobalSensorId |
| std::string | _resourcedir |
| Pose | _RootOrigin |
| Pose | _VisualRootOrigin |
| std::vector< USERDATA > | _vuserdata |
Private Types | |
| enum | GeomType { GeomNone = 0, GeomBox = 1, GeomSphere = 2, GeomCylinder = 3, GeomTrimesh = 4 } |
Definition at line 91 of file collada_parser.cpp.
enum urdf::ColladaModelReader::GeomType [private] |
Definition at line 186 of file collada_parser.cpp.
| urdf::ColladaModelReader::ColladaModelReader | ( | urdf::ModelInterfaceSharedPtr | model | ) | [inline] |
Definition at line 416 of file collada_parser.cpp.
| virtual urdf::ColladaModelReader::~ColladaModelReader | ( | ) | [inline, virtual] |
Definition at line 420 of file collada_parser.cpp.
| static Vector3 urdf::ColladaModelReader::_add3 | ( | const Vector3 & | v0, |
| const Vector3 & | v1 | ||
| ) | [inline, static, protected] |
Definition at line 2784 of file collada_parser.cpp.
| bool urdf::ColladaModelReader::_checkMathML | ( | daeElementRef | pelt, |
| const std::string & | type | ||
| ) | [inline, protected] |
Definition at line 2410 of file collada_parser.cpp.
| size_t urdf::ColladaModelReader::_countChildren | ( | daeElement * | pelt | ) | [inline, protected] |
Definition at line 2531 of file collada_parser.cpp.
| urdf::GeometrySharedPtr urdf::ColladaModelReader::_CreateGeometry | ( | const std::string & | name, |
| const std::list< GEOMPROPERTIES > & | listGeomProperties | ||
| ) | [inline, protected] |
Definition at line 1189 of file collada_parser.cpp.
| static Vector3 urdf::ColladaModelReader::_cross3 | ( | const Vector3 & | v0, |
| const Vector3 & | v1 | ||
| ) | [inline, static, protected] |
Definition at line 2768 of file collada_parser.cpp.
| void urdf::ColladaModelReader::_decompose | ( | const boost::array< double, 12 > & | tm, |
| Pose & | tout, | ||
| Vector3 & | vscale | ||
| ) | [inline, protected] |
Definition at line 2350 of file collada_parser.cpp.
| static double urdf::ColladaModelReader::_dot3 | ( | const Vector3 & | v0, |
| const Vector3 & | v1 | ||
| ) | [inline, static, protected] |
Definition at line 2764 of file collada_parser.cpp.
| bool urdf::ColladaModelReader::_Extract | ( | ) | [inline, protected] |
the first possible robot in the scene
Definition at line 466 of file collada_parser.cpp.
| bool urdf::ColladaModelReader::_ExtractArticulatedSystem | ( | domInstance_articulated_systemRef | ias, |
| KinematicsSceneBindings & | bindings | ||
| ) | [inline, protected] |
extracts an articulated system. Note that an articulated system can include other articulated systems
Definition at line 531 of file collada_parser.cpp.
| static boost::array<double,12> urdf::ColladaModelReader::_ExtractFullTransform | ( | const T | pelt | ) | [inline, static, protected] |
Travel by the transformation array and calls the _getTransform method.
Definition at line 2331 of file collada_parser.cpp.
| static boost::array<double,12> urdf::ColladaModelReader::_ExtractFullTransformFromChildren | ( | const T | pelt | ) | [inline, static, protected] |
Travel by the transformation array and calls the _getTransform method.
Definition at line 2340 of file collada_parser.cpp.
| void urdf::ColladaModelReader::_ExtractGeometry | ( | const domNodeRef | pdomnode, |
| std::list< GEOMPROPERTIES > & | listGeomProperties, | ||
| const std::list< JointAxisBinding > & | listAxisBindings, | ||
| const Pose & | tlink | ||
| ) | [inline, protected] |
Extract Geometry and apply the transformations of the node
| pdomnode | Node to extract the goemetry |
| plink | Link of the kinematics model |
Definition at line 1380 of file collada_parser.cpp.
| bool urdf::ColladaModelReader::_ExtractGeometry | ( | const domTrianglesRef | triRef, |
| const domVerticesRef | vertsRef, | ||
| const std::map< std::string, domMaterialRef > & | mapmaterials, | ||
| std::list< GEOMPROPERTIES > & | listGeomProperties | ||
| ) | [inline, protected] |
Extract the Geometry in TRIANGLES and adds it to OpenRave
| triRef | Array of triangles of the COLLADA's model |
| vertsRef | Array of vertices of the COLLADA's model |
| mapmaterials | Materials applied to the geometry |
| plink | Link of the kinematics model |
Definition at line 1523 of file collada_parser.cpp.
| bool urdf::ColladaModelReader::_ExtractGeometry | ( | const domTrifansRef | triRef, |
| const domVerticesRef | vertsRef, | ||
| const std::map< std::string, domMaterialRef > & | mapmaterials, | ||
| std::list< GEOMPROPERTIES > & | listGeomProperties | ||
| ) | [inline, protected] |
Extract the Geometry in TRIGLE FANS and adds it to OpenRave
| triRef | Array of triangle fans of the COLLADA's model |
| vertsRef | Array of vertices of the COLLADA's model |
| mapmaterials | Materials applied to the geometry |
Definition at line 1604 of file collada_parser.cpp.
| bool urdf::ColladaModelReader::_ExtractGeometry | ( | const domTristripsRef | triRef, |
| const domVerticesRef | vertsRef, | ||
| const std::map< std::string, domMaterialRef > & | mapmaterials, | ||
| std::list< GEOMPROPERTIES > & | listGeomProperties | ||
| ) | [inline, protected] |
Extract the Geometry in TRIANGLE STRIPS and adds it to OpenRave
| triRef | Array of Triangle Strips of the COLLADA's model |
| vertsRef | Array of vertices of the COLLADA's model |
| mapmaterials | Materials applied to the geometry |
Definition at line 1695 of file collada_parser.cpp.
| bool urdf::ColladaModelReader::_ExtractGeometry | ( | const domPolylistRef | triRef, |
| const domVerticesRef | vertsRef, | ||
| const std::map< std::string, domMaterialRef > & | mapmaterials, | ||
| std::list< GEOMPROPERTIES > & | listGeomProperties | ||
| ) | [inline, protected] |
Extract the Geometry in TRIANGLE STRIPS and adds it to OpenRave
| triRef | Array of Triangle Strips of the COLLADA's model |
| vertsRef | Array of vertices of the COLLADA's model |
| mapmaterials | Materials applied to the geometry |
Definition at line 1789 of file collada_parser.cpp.
| bool urdf::ColladaModelReader::_ExtractGeometry | ( | const domGeometryRef | geom, |
| const std::map< std::string, domMaterialRef > & | mapmaterials, | ||
| std::list< GEOMPROPERTIES > & | listGeomProperties | ||
| ) | [inline, protected] |
Extract the Geometry and adds it to OpenRave
| geom | Geometry to extract of the COLLADA's model |
| mapmaterials | Materials applied to the geometry |
Definition at line 1868 of file collada_parser.cpp.
| boost::shared_ptr<std::string> urdf::ColladaModelReader::_ExtractInterfaceType | ( | const domExtra_Array & | arr | ) | [inline, protected] |
returns an openrave interface type from the extra array
Definition at line 2382 of file collada_parser.cpp.
| bool urdf::ColladaModelReader::_ExtractKinematicsModel | ( | domInstance_kinematics_modelRef | ikm, |
| KinematicsSceneBindings & | bindings | ||
| ) | [inline, protected] |
Definition at line 612 of file collada_parser.cpp.
| bool urdf::ColladaModelReader::_ExtractKinematicsModel | ( | domKinematics_modelRef | kmodel, |
| domNodeRef | pnode, | ||
| domPhysics_modelRef | pmodel, | ||
| const KinematicsSceneBindings & | bindings | ||
| ) | [inline, protected] |
append the kinematics model to the openrave kinbody
Definition at line 660 of file collada_parser.cpp.
| static void urdf::ColladaModelReader::_ExtractKinematicsVisualBindings | ( | domInstance_with_extraRef | viscene, |
| domInstance_kinematics_sceneRef | kiscene, | ||
| KinematicsSceneBindings & | bindings | ||
| ) | [inline, static, protected] |
go through all kinematics binds to get a kinematics/visual pair
| kiscene | instance of one kinematics scene, binds the kinematic and visual models |
| bindings | the extracted bindings |
Definition at line 2456 of file collada_parser.cpp.
| urdf::LinkSharedPtr urdf::ColladaModelReader::_ExtractLink | ( | const domLinkRef | pdomlink, |
| const domNodeRef | pdomnode, | ||
| const Pose & | tParentWorldLink, | ||
| const Pose & | tParentLink, | ||
| const std::vector< domJointRef > & | vdomjoints, | ||
| const KinematicsSceneBindings & | bindings | ||
| ) | [inline, protected] |
Extract Link info and add it to an existing body.
Definition at line 808 of file collada_parser.cpp.
| std::string urdf::ColladaModelReader::_ExtractLinkName | ( | domLinkRef | pdomlink | ) | [inline, protected] |
Definition at line 2397 of file collada_parser.cpp.
| domTechniqueRef urdf::ColladaModelReader::_ExtractOpenRAVEProfile | ( | const domTechnique_Array & | arr | ) | [inline, protected] |
Definition at line 2371 of file collada_parser.cpp.
| static void urdf::ColladaModelReader::_ExtractPhysicsBindings | ( | domCOLLADA::domSceneRef | allscene, |
| KinematicsSceneBindings & | bindings | ||
| ) | [inline, static, protected] |
Definition at line 2508 of file collada_parser.cpp.
| void urdf::ColladaModelReader::_ExtractRobotAttachedActuators | ( | const domArticulated_systemRef | as | ) | [inline, protected] |
extract the robot actuators
Definition at line 2022 of file collada_parser.cpp.
| void urdf::ColladaModelReader::_ExtractRobotAttachedSensors | ( | const domArticulated_systemRef | as | ) | [inline, protected] |
Extract Sensors attached to a Robot.
Definition at line 2065 of file collada_parser.cpp.
| void urdf::ColladaModelReader::_ExtractRobotManipulators | ( | const domArticulated_systemRef | as | ) | [inline, protected] |
extract the robot manipulators
Definition at line 2059 of file collada_parser.cpp.
| void urdf::ColladaModelReader::_FillGeometryColor | ( | const domMaterialRef | pmat, |
| GEOMPROPERTIES & | geom | ||
| ) | [inline, protected] |
Paint the Geometry with the color material
| pmat | Material info of the COLLADA's model |
| geom | Geometry properties in OpenRAVE |
Definition at line 1492 of file collada_parser.cpp.
| daeElementRef urdf::ColladaModelReader::_getElementFromUrl | ( | const daeURI & | uri | ) | [inline, protected] |
Definition at line 2070 of file collada_parser.cpp.
| urdf::JointSharedPtr urdf::ColladaModelReader::_getJointFromRef | ( | xsToken | targetref, |
| daeElementRef | peltref | ||
| ) | [inline, protected] |
Definition at line 2424 of file collada_parser.cpp.
| static boost::array<double,12> urdf::ColladaModelReader::_getNodeParentTransform | ( | const T | pelt | ) | [inline, static, protected] |
Travels recursively the node parents of the given one to extract the Transform arrays that affects the node given
Definition at line 2322 of file collada_parser.cpp.
| static boost::array<double,12> urdf::ColladaModelReader::_getTransform | ( | daeElementRef | pelt | ) | [inline, static, protected] |
Gets all transformations applied to the node.
Definition at line 2268 of file collada_parser.cpp.
| static double urdf::ColladaModelReader::_GetUnitScale | ( | daeElement * | pelt | ) | [inline, static, protected] |
Definition at line 2366 of file collada_parser.cpp.
| USERDATA* urdf::ColladaModelReader::_getUserData | ( | daeElement * | pelt | ) | [inline, protected] |
Definition at line 2560 of file collada_parser.cpp.
| static boost::array<double,12> urdf::ColladaModelReader::_matrixFromAxisAngle | ( | const Vector3 & | axis, |
| double | angle | ||
| ) | [inline, static, protected] |
Definition at line 2655 of file collada_parser.cpp.
| static boost::array<double,12> urdf::ColladaModelReader::_matrixFromPose | ( | const Pose & | t | ) | [inline, static, protected] |
Definition at line 2691 of file collada_parser.cpp.
| static boost::array<double,12> urdf::ColladaModelReader::_matrixFromQuat | ( | const Rotation & | quat | ) | [inline, static, protected] |
Definition at line 2660 of file collada_parser.cpp.
| static boost::array<double,12> urdf::ColladaModelReader::_matrixIdentity | ( | ) | [inline, static, protected] |
Definition at line 2261 of file collada_parser.cpp.
| static Vector3 urdf::ColladaModelReader::_normalize3 | ( | const Vector3 & | v0 | ) | [inline, static, protected] |
Definition at line 2792 of file collada_parser.cpp.
| static Pose urdf::ColladaModelReader::_poseFromMatrix | ( | const boost::array< double, 12 > & | m | ) | [inline, static, protected] |
Definition at line 2681 of file collada_parser.cpp.
| static Pose urdf::ColladaModelReader::_poseInverse | ( | const Pose & | p | ) | [inline, static, protected] |
Definition at line 2625 of file collada_parser.cpp.
| static Vector3 urdf::ColladaModelReader::_poseMult | ( | const Pose & | p, |
| const Vector3 & | v | ||
| ) | [inline, static, protected] |
Definition at line 2572 of file collada_parser.cpp.
| static Vector3 urdf::ColladaModelReader::_poseMult | ( | const boost::array< double, 12 > & | m, |
| const Vector3 & | v | ||
| ) | [inline, static, protected] |
Definition at line 2590 of file collada_parser.cpp.
| static boost::array<double,12> urdf::ColladaModelReader::_poseMult | ( | const boost::array< double, 12 > & | m0, |
| const boost::array< double, 12 > & | m1 | ||
| ) | [inline, static, protected] |
Definition at line 2599 of file collada_parser.cpp.
| static Pose urdf::ColladaModelReader::_poseMult | ( | const Pose & | p0, |
| const Pose & | p1 | ||
| ) | [inline, static, protected] |
Definition at line 2617 of file collada_parser.cpp.
| void urdf::ColladaModelReader::_PostProcess | ( | ) | [inline, protected] |
Definition at line 506 of file collada_parser.cpp.
| void urdf::ColladaModelReader::_processUserData | ( | daeElement * | pelt, |
| double | scale | ||
| ) | [inline, protected] |
Definition at line 2541 of file collada_parser.cpp.
| static Rotation urdf::ColladaModelReader::_quatFromAxisAngle | ( | double | x, |
| double | y, | ||
| double | z, | ||
| double | angle | ||
| ) | [inline, static, protected] |
Definition at line 2700 of file collada_parser.cpp.
| static Rotation urdf::ColladaModelReader::_quatFromMatrix | ( | const boost::array< double, 12 > & | mat | ) | [inline, static, protected] |
Definition at line 2716 of file collada_parser.cpp.
| static Rotation urdf::ColladaModelReader::_quatMult | ( | const Rotation & | quat0, |
| const Rotation & | quat1 | ||
| ) | [inline, static, protected] |
Definition at line 2639 of file collada_parser.cpp.
| static Vector3 urdf::ColladaModelReader::_sub3 | ( | const Vector3 & | v0, |
| const Vector3 & | v1 | ||
| ) | [inline, static, protected] |
Definition at line 2776 of file collada_parser.cpp.
| virtual void urdf::ColladaModelReader::handleError | ( | daeString | msg | ) | [inline, protected, virtual] |
Definition at line 2356 of file collada_parser.cpp.
| virtual void urdf::ColladaModelReader::handleWarning | ( | daeString | msg | ) | [inline, protected, virtual] |
Definition at line 2361 of file collada_parser.cpp.
| bool urdf::ColladaModelReader::InitFromData | ( | const std::string & | pdata | ) | [inline] |
Definition at line 445 of file collada_parser.cpp.
| bool urdf::ColladaModelReader::InitFromFile | ( | const std::string & | filename | ) | [inline] |
Definition at line 426 of file collada_parser.cpp.
| static xsBoolean urdf::ColladaModelReader::resolveBool | ( | domCommon_bool_or_paramRef | paddr, |
| const U & | parent | ||
| ) | [inline, static, protected] |
Definition at line 2183 of file collada_parser.cpp.
| static bool urdf::ColladaModelReader::resolveCommon_float_or_param | ( | daeElementRef | pcommon, |
| daeElementRef | parent, | ||
| float & | f | ||
| ) | [inline, static, protected] |
Definition at line 2238 of file collada_parser.cpp.
| static domFloat urdf::ColladaModelReader::resolveFloat | ( | domCommon_float_or_paramRef | paddr, |
| const U & | parent | ||
| ) | [inline, static, protected] |
Definition at line 2210 of file collada_parser.cpp.
| static daeElement* urdf::ColladaModelReader::searchBinding | ( | domCommon_sidref_or_paramRef | paddr, |
| daeElementRef | parent | ||
| ) | [inline, static, protected] |
Definition at line 2075 of file collada_parser.cpp.
| static daeElement* urdf::ColladaModelReader::searchBinding | ( | daeString | ref, |
| daeElementRef | parent | ||
| ) | [inline, static, protected] |
Search a given parameter reference and stores the new reference to search.
| ref | the reference name to search |
| parent | The array of parameter where the method searchs. |
Definition at line 2089 of file collada_parser.cpp.
| static daeElement* urdf::ColladaModelReader::searchBindingArray | ( | daeString | ref, |
| const domInstance_articulated_system_Array & | paramArray | ||
| ) | [inline, static, protected] |
Definition at line 2161 of file collada_parser.cpp.
| static daeElement* urdf::ColladaModelReader::searchBindingArray | ( | daeString | ref, |
| const domInstance_kinematics_model_Array & | paramArray | ||
| ) | [inline, static, protected] |
Definition at line 2172 of file collada_parser.cpp.
boost::shared_ptr<DAE> urdf::ColladaModelReader::_collada [protected] |
Definition at line 2802 of file collada_parser.cpp.
domCOLLADA* urdf::ColladaModelReader::_dom [protected] |
Definition at line 2803 of file collada_parser.cpp.
std::string urdf::ColladaModelReader::_filename [protected] |
Definition at line 2806 of file collada_parser.cpp.
urdf::ModelInterfaceSharedPtr urdf::ColladaModelReader::_model [protected] |
Definition at line 2808 of file collada_parser.cpp.
int urdf::ColladaModelReader::_nGlobalManipulatorId [protected] |
Definition at line 2805 of file collada_parser.cpp.
int urdf::ColladaModelReader::_nGlobalSensorId [protected] |
Definition at line 2805 of file collada_parser.cpp.
std::string urdf::ColladaModelReader::_resourcedir [protected] |
Definition at line 2807 of file collada_parser.cpp.
Pose urdf::ColladaModelReader::_RootOrigin [protected] |
Definition at line 2809 of file collada_parser.cpp.
Pose urdf::ColladaModelReader::_VisualRootOrigin [protected] |
Definition at line 2810 of file collada_parser.cpp.
std::vector<USERDATA> urdf::ColladaModelReader::_vuserdata [protected] |
Definition at line 2804 of file collada_parser.cpp.