Go to the documentation of this file.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 #include "collada_urdf/collada_urdf.h"
00031
00032 #include <gtest/gtest.h>
00033
00034 #include <fstream>
00035 #include <sstream>
00036 #include <string>
00037
00038 std::string readTestUrdfString() {
00039 std::ifstream file("test/pr2.urdf");
00040 std::stringstream ss;
00041 ss << file.rdbuf();
00042 return ss.str();
00043 }
00044
00045 TEST(collada_urdf, collada_from_urdf_file_works)
00046 {
00047 boost::shared_ptr<DAE> dom;
00048 ASSERT_TRUE(collada_urdf::colladaFromUrdfFile("test/pr2.urdf", dom));
00049 ASSERT_TRUE(collada_urdf::colladaToFile(dom, "test/pr2.dae"));
00050 }
00051
00052 TEST(collada_urdf, collada_from_urdf_string_works)
00053 {
00054 std::string urdf_str = readTestUrdfString();
00055
00056 boost::shared_ptr<DAE> dom;
00057 ASSERT_TRUE(collada_urdf::colladaFromUrdfString(urdf_str, dom));
00058 ASSERT_TRUE(collada_urdf::colladaToFile(dom, "test/pr2.dae"));
00059 }
00060
00061 TEST(collada_urdf, collada_from_urdf_xml_works)
00062 {
00063 TiXmlDocument urdf_xml;
00064 ASSERT_TRUE(urdf_xml.Parse(readTestUrdfString().c_str()) > 0);
00065
00066 boost::shared_ptr<DAE> dom;
00067 ASSERT_TRUE(collada_urdf::colladaFromUrdfXml(&urdf_xml, dom));
00068 ASSERT_TRUE(collada_urdf::colladaToFile(dom, "test/pr2.dae"));
00069 }
00070
00071 TEST(collada_urdf, collada_from_urdf_model_works)
00072 {
00073 urdf::Model robot_model;
00074 TiXmlDocument urdf_xml;
00075 ASSERT_TRUE(urdf_xml.Parse(readTestUrdfString().c_str()) > 0);
00076 ASSERT_TRUE(robot_model.initXml(&urdf_xml));
00077
00078 boost::shared_ptr<DAE> dom;
00079 ASSERT_TRUE(collada_urdf::colladaFromUrdfModel(robot_model, dom));
00080 ASSERT_TRUE(collada_urdf::colladaToFile(dom, "test/pr2.dae"));
00081 }
00082
00083 int main(int argc, char **argv) {
00084 testing::InitGoogleTest(&argc, argv);
00085 return RUN_ALL_TESTS();
00086 }