kdl_parser/urdf_parser/test/memtest.cpp

25 lines
497 B
C++

#include <urdf_parser/urdf_parser.h>
#include <ros/ros.h>
#include <fstream>
#include <iostream>
int main(int argc, char** argv){
ros::init(argc, argv, "memtest");
while (ros::ok()){
urdf::URDFParser urdf;
std::string xml_string;
std::fstream xml_file(argv[1], std::fstream::in);
while ( xml_file.good() )
{
std::string line;
std::getline( xml_file, line);
xml_string += (line + "\n");
}
xml_file.close();
urdf.initURDF(xml_string);
}
}