Note: This tutorial assumes you have already created your own URDF file or that you are working with the existing PR2 URDF file.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Exporting URDF to COLLADA

Description: This tutorial teaches you how to export an URDF file to a COLLADA document

Tutorial Level: BEGINNER

Building collada_urdf

$ rosdep install collada_urdf

This will install all the external dependencies for collada_urdf. To build the package, run:

$ rosmake collada_urdf

Using in your code

First, add the package as a dependency to your manifest.xml file:

<package>
    ...
    <depend package="collada_urdf" />
    ...
</package>

To start using the exporter in your C++ code, include the following file:

   1 #include <collada_urdf/collada_urdf.h>
   2 

Now there are different ways to proceed. You can construct a COLLADA Document Object Model (DOM) from URDF in a variety of ways:

From a file

   1 boost::shared_ptr<DAE> dom;
   2 if (!collada_urdf::colladaFromUrdfFile("filename.urdf", dom)) {
   3     ROS_ERROR("Failed to construct COLLADA DOM");
   4     return false;
   5 }

To create the PR2 URDF file, run the following command:

$ rosrun xacro xacro.py `rospack find pr2_description`/robots/pr2.urdf.xacro > pr2.urdf

From the parameter server

   1 boost::shared_ptr<DAE> dom;
   2 ros::NodeHandle node;
   3 std::string robot_desc_string;
   4 node.param("robot_description", robot_desc_string, std::string());
   5 if (!collada_urdf::colladaFromUdfString(robot_desc_string, dom)) {
   6     ROS_ERROR("Failed to construct COLLADA DOM");
   7     return false;
   8 }

From an XML document

   1 boost::shared_ptr<DAE> dom;
   2 TiXmlDocument xml_doc;
   3 xml_doc.Parse(xml_string.c_str());
   4 xml_root = xml_doc.FirstChildElement("robot");
   5 if (!xml_root) {
   6     ROS_ERROR("Failed to find robot element in XML document");
   7     return false;
   8 }
   9 if (!collada_urdf::colladaFromUrdfXml(xml_root, dom)) {
  10     ROS_ERROR("Failed to construct COLLADA DOM");
  11     return false;
  12 }

From an URDF model

   1 boost::shared_ptr<DAE> dom;
   2 urdf::Model my_model;
   3 if (!my_model.initXml(....)) {
   4     ROS_ERROR("Failed to parse URDF robot model");
   5     return false;
   6 }
   7 if (!collada_urdf::colladaFromUrdfModel(my_model, dom)){
   8     ROS_ERROR("Failed to construct COLLADA DOM");
   9     return false;
  10 }

Writing COLLADA to file

Once you have your COLLADA document loaded, you can write the document to a file:

   1 collada_urdf::colladaToFile(dom, "filename.dae");

For more details, take a look at the API documentation.

Wiki: collada_urdf/Tutorials/Exporting URDF to COLLADA (last edited 2011-06-22 16:25:14 by Yiping Liu)