00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include "collada_urdf/collada_urdf.h"
00038 #include "collada_urdf/collada_writer.h"
00039
00040 using std::string;
00041 using boost::shared_ptr;
00042
00043 namespace collada_urdf {
00044
00045 ColladaUrdfException::ColladaUrdfException(std::string const& what)
00046 : std::runtime_error(what)
00047 {
00048 }
00049
00050 bool colladaFromUrdfFile(string const& file, shared_ptr<DAE>& dom) {
00051 TiXmlDocument urdf_xml;
00052 if (!urdf_xml.LoadFile(file)) {
00053 ROS_ERROR("Could not load XML file");
00054 return false;
00055 }
00056
00057 return colladaFromUrdfXml(&urdf_xml, dom);
00058 }
00059
00060 bool colladaFromUrdfString(string const& xml, shared_ptr<DAE>& dom) {
00061 TiXmlDocument urdf_xml;
00062 if (urdf_xml.Parse(xml.c_str()) == 0) {
00063 ROS_ERROR("Could not parse XML document");
00064 return false;
00065 }
00066
00067 return colladaFromUrdfXml(&urdf_xml, dom);
00068 }
00069
00070 bool colladaFromUrdfXml(TiXmlDocument* xml_doc, shared_ptr<DAE>& dom) {
00071 urdf::Model robot_model;
00072 if (!robot_model.initXml(xml_doc)) {
00073 ROS_ERROR("Could not generate robot model");
00074 return false;
00075 }
00076
00077 return colladaFromUrdfModel(robot_model, dom);
00078 }
00079
00080 bool colladaFromUrdfModel(urdf::Model const& robot_model, shared_ptr<DAE>& dom) {
00081 ColladaWriter writer(robot_model);
00082 dom = writer.convert();
00083
00084 return dom != shared_ptr<DAE>();
00085 }
00086
00087 bool colladaToFile(shared_ptr<DAE> dom, string const& file) {
00088 daeString uri = dom->getDoc(0)->getDocumentURI()->getURI();
00089 return dom->writeTo(uri, file);
00090 }
00091
00092 }