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 More... | |
bool | _ExtractArticulatedSystem (domInstance_articulated_systemRef ias, KinematicsSceneBindings &bindings) |
extracts an articulated system. Note that an articulated system can include other articulated systems More... | |
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 More... | |
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 More... | |
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. More... | |
std::string | _ExtractLinkName (domLinkRef pdomlink) |
domTechniqueRef | _ExtractOpenRAVEProfile (const domTechnique_Array &arr) |
void | _ExtractRobotAttachedActuators (const domArticulated_systemRef as) |
extract the robot actuators More... | |
void | _ExtractRobotAttachedSensors (const domArticulated_systemRef as) |
Extract Sensors attached to a Robot. More... | |
void | _ExtractRobotManipulators (const domArticulated_systemRef as) |
extract the robot manipulators More... | |
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. More... | |
template<typename T > | |
static boost::array< double, 12 > | _ExtractFullTransformFromChildren (const T pelt) |
Travel by the transformation array and calls the _getTransform method. More... | |
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) |
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. More... | |
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 95 of file collada_parser.cpp.
|
private |
Enumerator | |
---|---|
GeomNone | |
GeomBox | |
GeomSphere | |
GeomCylinder | |
GeomTrimesh |
Definition at line 190 of file collada_parser.cpp.
|
inline |
Definition at line 420 of file collada_parser.cpp.
|
inlinevirtual |
Definition at line 424 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2788 of file collada_parser.cpp.
|
inlineprotected |
Definition at line 2414 of file collada_parser.cpp.
|
inlineprotected |
Definition at line 2535 of file collada_parser.cpp.
|
inlineprotected |
Definition at line 1193 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2772 of file collada_parser.cpp.
|
inlineprotected |
Definition at line 2354 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2768 of file collada_parser.cpp.
|
inlineprotected |
the first possible robot in the scene
Definition at line 470 of file collada_parser.cpp.
|
inlineprotected |
extracts an articulated system. Note that an articulated system can include other articulated systems
Definition at line 535 of file collada_parser.cpp.
|
inlinestaticprotected |
Travel by the transformation array and calls the _getTransform method.
Definition at line 2335 of file collada_parser.cpp.
|
inlinestaticprotected |
Travel by the transformation array and calls the _getTransform method.
Definition at line 2344 of file collada_parser.cpp.
|
inlineprotected |
Extract Geometry and apply the transformations of the node
pdomnode | Node to extract the goemetry |
plink | Link of the kinematics model |
Definition at line 1384 of file collada_parser.cpp.
|
inlineprotected |
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 1527 of file collada_parser.cpp.
|
inlineprotected |
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 1608 of file collada_parser.cpp.
|
inlineprotected |
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 1699 of file collada_parser.cpp.
|
inlineprotected |
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 1793 of file collada_parser.cpp.
|
inlineprotected |
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 1872 of file collada_parser.cpp.
|
inlineprotected |
returns an openrave interface type from the extra array
Definition at line 2386 of file collada_parser.cpp.
|
inlineprotected |
Definition at line 616 of file collada_parser.cpp.
|
inlineprotected |
append the kinematics model to the openrave kinbody
Definition at line 664 of file collada_parser.cpp.
|
inlinestaticprotected |
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 2460 of file collada_parser.cpp.
|
inlineprotected |
Extract Link info and add it to an existing body.
Definition at line 812 of file collada_parser.cpp.
|
inlineprotected |
Definition at line 2401 of file collada_parser.cpp.
|
inlineprotected |
Definition at line 2375 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2512 of file collada_parser.cpp.
|
inlineprotected |
extract the robot actuators
Definition at line 2026 of file collada_parser.cpp.
|
inlineprotected |
Extract Sensors attached to a Robot.
Definition at line 2069 of file collada_parser.cpp.
|
inlineprotected |
extract the robot manipulators
Definition at line 2063 of file collada_parser.cpp.
|
inlineprotected |
Paint the Geometry with the color material
pmat | Material info of the COLLADA's model |
geom | Geometry properties in OpenRAVE |
Definition at line 1496 of file collada_parser.cpp.
|
inlineprotected |
Definition at line 2074 of file collada_parser.cpp.
|
inlineprotected |
Definition at line 2428 of file collada_parser.cpp.
|
inlinestaticprotected |
Travels recursively the node parents of the given one to extract the Transform arrays that affects the node given
Definition at line 2326 of file collada_parser.cpp.
|
inlinestaticprotected |
Gets all transformations applied to the node.
Definition at line 2272 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2370 of file collada_parser.cpp.
|
inlineprotected |
Definition at line 2564 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2659 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2695 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2664 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2265 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2796 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2685 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2629 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2576 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2594 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2603 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2621 of file collada_parser.cpp.
|
inlineprotected |
Definition at line 510 of file collada_parser.cpp.
|
inlineprotected |
Definition at line 2545 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2704 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2720 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2643 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2780 of file collada_parser.cpp.
|
inlineprotectedvirtual |
Definition at line 2360 of file collada_parser.cpp.
|
inlineprotectedvirtual |
Definition at line 2365 of file collada_parser.cpp.
|
inline |
Definition at line 449 of file collada_parser.cpp.
|
inline |
Definition at line 430 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2187 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2242 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2214 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2079 of file collada_parser.cpp.
|
inlinestaticprotected |
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 2093 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2165 of file collada_parser.cpp.
|
inlinestaticprotected |
Definition at line 2176 of file collada_parser.cpp.
|
protected |
Definition at line 2806 of file collada_parser.cpp.
|
protected |
Definition at line 2807 of file collada_parser.cpp.
|
protected |
Definition at line 2810 of file collada_parser.cpp.
|
protected |
Definition at line 2812 of file collada_parser.cpp.
|
protected |
Definition at line 2809 of file collada_parser.cpp.
|
protected |
Definition at line 2809 of file collada_parser.cpp.
|
protected |
Definition at line 2811 of file collada_parser.cpp.
|
protected |
Definition at line 2813 of file collada_parser.cpp.
|
protected |
Definition at line 2814 of file collada_parser.cpp.
|
protected |
Definition at line 2808 of file collada_parser.cpp.