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 #include "robot_description.hpp"
00022 #include "../helpers/filesystem_helpers.hpp"
00023
00024 namespace naoqi{
00025
00026 namespace tools{
00027
00028 std::string getRobotDescription( const robot::Robot& robot){
00029 std::string urdf_path;
00030 static std::string robot_desc;
00031 if(!robot_desc.empty())
00032 return robot_desc;
00033
00034 if ( robot == robot::PEPPER)
00035 {
00036 urdf_path = helpers::filesystem::getURDF("pepper.urdf");
00037 }
00038 else if ( robot == robot::NAO )
00039 {
00040 urdf_path = helpers::filesystem::getURDF("nao.urdf");
00041 }
00042 else if ( robot == robot::ROMEO )
00043 {
00044 urdf_path = helpers::filesystem::getURDF("romeo.urdf");
00045 }
00046 else
00047 {
00048 std::cerr << " could not load urdf file from disk " << std::endl;
00049 return std::string();
00050 }
00051
00052 std::ifstream stream( (urdf_path).c_str() );
00053 if (!stream)
00054 {
00055 std::cerr << "failed to load robot description in joint_state_publisher: " << urdf_path << std::endl;
00056 return std::string();
00057 }
00058 robot_desc = std::string( (std::istreambuf_iterator<char>(stream)), std::istreambuf_iterator<char>());
00059 return robot_desc;
00060 }
00061
00062 }
00063
00064 }