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
00031
00032 #include <string>
00033 #include <vector>
00034 #include <stdlib.h>
00035 #include <unistd.h>
00036 #include <boost/thread.hpp>
00037 #include <gtest/gtest.h>
00038 #include "ros/package.h"
00039
00040 void string_split(const std::string &s, std::vector<std::string> &t, const std::string &d)
00041 { t.clear();
00042 size_t start = 0, end;
00043 while ((end = s.find_first_of(d, start)) != std::string::npos)
00044 {
00045 if((end-start) > 0)
00046 t.push_back(s.substr(start, end-start));
00047 start = end + 1;
00048 }
00049 if(start < s.size())
00050 t.push_back(s.substr(start));
00051 }
00052
00053 char g_rr_buf[1024];
00054 void set_env_vars(void)
00055 {
00056
00057
00058 getcwd(g_rr_buf, sizeof(g_rr_buf));
00059 setenv("ROS_PACKAGE_PATH", g_rr_buf, 1);
00060 strncpy(g_rr_buf+strlen(g_rr_buf), "/tmp.XXXXXX", sizeof(g_rr_buf)-strlen(g_rr_buf)-1);
00061 g_rr_buf[sizeof(g_rr_buf)-1] = '\0';
00062 mkdtemp(g_rr_buf);
00063 setenv("ROS_ROOT", g_rr_buf, 1);
00064 }
00065 void cleanup_env_vars(void)
00066 {
00067
00068 rmdir(g_rr_buf);
00069 memset(g_rr_buf, 0, sizeof(g_rr_buf));
00070 }
00071
00072 TEST(roslib, commandListNames)
00073 {
00074 set_env_vars();
00075
00076 std::string output = ros::package::command("list-names");
00077 std::vector<std::string> output_list;
00078 string_split(output, output_list, "\n");
00079 ASSERT_EQ((int)output_list.size(), 1);
00080 ASSERT_STREQ(output_list[0].c_str(), "roslib");
00081
00082 cleanup_env_vars();
00083 }
00084
00085 TEST(roslib, commandList)
00086 {
00087 set_env_vars();
00088
00089 std::string output = ros::package::command("list");
00090 std::vector<std::string> output_list;
00091 std::vector<std::string> name_path;
00092 string_split(output, output_list, "\n");
00093 ASSERT_EQ((int)output_list.size(), 1);
00094 string_split(output_list[0], name_path, " ");
00095 ASSERT_EQ((int)name_path.size(), 2);
00096 ASSERT_STREQ(name_path[0].c_str(), "roslib");
00097
00098 cleanup_env_vars();
00099 }
00100
00101 TEST(roslib, getAll)
00102 {
00103 set_env_vars();
00104
00105 std::vector<std::string> output_list;
00106 ASSERT_TRUE(ros::package::getAll(output_list));
00107 ASSERT_EQ((int)output_list.size(), 1);
00108 ASSERT_STREQ(output_list[0].c_str(), "roslib");
00109
00110 cleanup_env_vars();
00111 }
00112
00113 void
00114 roslib_caller()
00115 {
00116 struct timespec ts = {0, 100000};
00117 std::string output;
00118 for(int i=0;i<100;i++)
00119 {
00120 output = ros::package::command("plugins --attrib=foo roslib");
00121 nanosleep(&ts, NULL);
00122 }
00123 }
00124
00125 TEST(roslib, concurrent_access)
00126 {
00127 set_env_vars();
00128 const int size = 10;
00129 boost::thread t[size];
00130 for(int i=0;i<size; i++)
00131 t[i] = boost::thread(boost::bind(roslib_caller));
00132 for(int i=0;i<size; i++)
00133 t[i].join();
00134 cleanup_env_vars();
00135 }
00136
00137 int main(int argc, char **argv)
00138 {
00139 testing::InitGoogleTest(&argc, argv);
00140 return RUN_ALL_TESTS();
00141 }
00142