$search
00001 #include <cerrno> 00002 #include <cstdlib> 00003 #include <iostream> 00004 #include <string> 00005 00006 #include <boost/filesystem/fstream.hpp> 00007 #include <boost/filesystem/path.hpp> 00008 #include <boost/format.hpp> 00009 00010 #include <ros/ros.h> 00011 00012 #include "file.hh" 00013 #include "names.hh" 00014 00015 00016 std::string 00017 getInitFileFromModelName (const std::string& modelName, 00018 const std::string& defaultPath) 00019 { 00020 boost::format fmt("%1%/%2%/%2%.init"); 00021 fmt % defaultPath % modelName; 00022 return fmt.str (); 00023 } 00024 00025 std::string 00026 getModelFileFromModelName (const std::string& modelName, 00027 const std::string& defaultPath) 00028 { 00029 boost::format fmt("%1%/%2%/%2%.wrl"); 00030 fmt % defaultPath % modelName; 00031 return fmt.str (); 00032 } 00033 00034 std::string 00035 getConfigurationFileFromModelName (const std::string& modelName, 00036 const std::string& defaultPath) 00037 { 00038 boost::format fmt("%1%/%2%/%2%.xml"); 00039 fmt % defaultPath % modelName; 00040 return fmt.str (); 00041 } 00042 00043 std::string 00044 getInitialPoseFileFromModelName (const std::string& modelName, 00045 const std::string& defaultPath) 00046 { 00047 boost::format fmt("%1%/%2%/%2%.0.pos"); 00048 fmt % defaultPath % modelName; 00049 return fmt.str (); 00050 } 00051 00052 bool 00053 makeModelFile(boost::filesystem::ofstream& modelStream, 00054 std::string& fullModelPath) 00055 { 00056 std::string modelDescription; 00057 if (!ros::param::has(visp_tracker::model_description_param)) 00058 { 00059 ROS_ERROR_STREAM("Failed to initialize: no model is provided."); 00060 return false; 00061 } 00062 ROS_DEBUG_STREAM("Trying to load the model from the parameter server."); 00063 00064 ros::param::get(visp_tracker::model_description_param, modelDescription); 00065 00066 char* tmpname = strdup("/tmp/tmpXXXXXX"); 00067 if (mkdtemp(tmpname) == NULL) 00068 { 00069 ROS_ERROR_STREAM 00070 ("Failed to create the temporary directory: " << strerror(errno)); 00071 return false; 00072 } 00073 boost::filesystem::path path(tmpname); 00074 path /= "model.wrl"; 00075 free(tmpname); 00076 00077 fullModelPath = path.external_file_string(); 00078 00079 modelStream.open(path); 00080 if (!modelStream.good()) 00081 { 00082 ROS_ERROR_STREAM 00083 ("Failed to create the temporary file: " << path); 00084 return false; 00085 } 00086 modelStream << modelDescription; 00087 modelStream.flush(); 00088 return true; 00089 }