utest.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 /* Author: Brian Gerkey */
00031 
00032 #include <stdexcept> // for std::runtime_error
00033 #include <string>
00034 #include <vector>
00035 #include <stdlib.h>
00036 #include <unistd.h>
00037 #include <stdio.h>
00038 #include <time.h>
00039 #include <gtest/gtest.h>
00040 #include <boost/algorithm/string.hpp>
00041 #include <boost/filesystem.hpp>
00042 #include "rospack/rospack.h"
00043 #include "utils.h"
00044 
00045 
00046 TEST(rospack, reentrant)
00047 {
00048   rospack::ROSPack rp;
00049   std::string output;
00050   int ret = rp.run(std::string("plugins --attrib=foo --top=precedence1 roslang"));
00051   ASSERT_EQ(ret, 0);
00052   ret = rp.run(std::string("find roslang"));
00053   ASSERT_EQ(ret, 0);
00054   ret = rp.run(std::string("list-names"));
00055   ASSERT_EQ(ret, 0);
00056   std::vector<std::string> output_list;
00057   output = rp.getOutput();
00058   boost::trim(output);
00059   boost::split(output_list, output, boost::is_any_of("\n"));
00060   ASSERT_EQ((int)output_list.size(), 4);
00061   ret = rp.run(std::string("list"));
00062   ASSERT_EQ(ret, 0);
00063   output = rp.getOutput();
00064   boost::trim(output);
00065   boost::split(output_list, output, boost::is_any_of("\n"));
00066   ASSERT_EQ((int)output_list.size(), 4);
00067   std::vector<std::string> path_name;
00068   boost::split(path_name, output_list[0], boost::is_any_of(" "));
00069   ASSERT_EQ((int)path_name.size(), 2);
00070 }
00071 
00072 TEST(rospack, multiple_rospack_objects)
00073 {
00074   rospack::ROSPack rp;
00075   std::string output;
00076   int ret = rp.run(std::string("plugins --attrib=foo --top=precedence1 roslang"));
00077   ASSERT_EQ(ret, 0);
00078   ret = rp.run(std::string("find roslang"));
00079   ASSERT_EQ(ret, 0);
00080   ret = rp.run(std::string("list-names"));
00081   ASSERT_EQ(ret, 0);
00082   std::vector<std::string> output_list;
00083   output = rp.getOutput();
00084   boost::trim(output);
00085   boost::split(output_list, output, boost::is_any_of("\n"));
00086   ASSERT_EQ((int)output_list.size(), 4);
00087   ret = rp.run(std::string("list"));
00088   ASSERT_EQ(ret, 0);
00089   output = rp.getOutput();
00090   boost::trim(output);
00091   boost::split(output_list, output, boost::is_any_of("\n"));
00092   ASSERT_EQ((int)output_list.size(), 4);
00093   std::vector<std::string> path_name;
00094   boost::split(path_name, output_list[0], boost::is_any_of(" "));
00095   ASSERT_EQ((int)path_name.size(), 2);
00096 
00097   rospack::ROSPack rp2;
00098   ret = rp2.run(std::string("plugins --attrib=foo --top=precedence1 roslang"));
00099   ASSERT_EQ(ret, 0);
00100   ret = rp2.run(std::string("find roslang"));
00101   ASSERT_EQ(ret, 0);
00102   ret = rp2.run(std::string("list-names"));
00103   ASSERT_EQ(ret, 0);
00104   output_list.clear();
00105   output = rp2.getOutput();
00106   boost::trim(output);
00107   boost::split(output_list, output, boost::is_any_of("\n"));
00108   ASSERT_EQ((int)output_list.size(), 4);
00109   ret = rp2.run(std::string("list"));
00110   ASSERT_EQ(ret, 0);
00111   output = rp2.getOutput();
00112   boost::trim(output);
00113   boost::split(output_list, output, boost::is_any_of("\n"));
00114   ASSERT_EQ((int)output_list.size(), 4);
00115   path_name.clear();
00116   boost::split(path_name, output_list[0], boost::is_any_of(" "));
00117   ASSERT_EQ((int)path_name.size(), 2);
00118 }
00119 
00120 TEST(rospack, deduplicate_tokens)
00121 {
00122   std::string input = "foo foo bar bat bar foobar batbar";
00123   std::string truth = "foo bar bat foobar batbar";
00124   std::string output;
00125   rospack::deduplicate_tokens(input, false, output);
00126   ASSERT_EQ(truth, output);
00127 }
00128 
00129 // Test that env var changes between runs still produce the right results.
00130 TEST(rospack, env_change)
00131 {
00132   // Get old path for resetting later, to avoid cross-talk with other tests
00133   char* oldrpp = getenv("ROS_PACKAGE_PATH");
00134   rospack::ROSPack rp;
00135 
00136   // Case 1: RPP=/test2
00137   char buf[1024];
00138   std::string rr = std::string(getcwd(buf, sizeof(buf))) + "/test2";
00139   setenv("ROS_PACKAGE_PATH", rr.c_str(), 1);
00140   std::vector<std::string> test_pkgs;
00141   test_pkgs.push_back("precedence1");
00142   test_pkgs.push_back("precedence2");
00143   test_pkgs.push_back("precedence3");
00144   test_pkgs.push_back("roslang");
00145   std::string output;
00146   int ret = rp.run(std::string("list-names"));
00147   EXPECT_EQ(ret, 0);
00148   std::vector<std::string> output_list;
00149   output = rp.getOutput();
00150   boost::trim(output);
00151   boost::split(output_list, output, boost::is_any_of("\n"));
00152   // Check that we get back the right list of packages (which could be in any
00153   // order).
00154   EXPECT_EQ(output_list.size(), test_pkgs.size());
00155   for(std::vector<std::string>::const_iterator it = output_list.begin();
00156       it != output_list.end();
00157       ++it)
00158   {
00159     bool found = false;
00160     for(std::vector<std::string>::const_iterator it2 = test_pkgs.begin();
00161         it2 != test_pkgs.end();
00162         ++it2)
00163     {
00164       if(*it == *it2)
00165       {
00166         EXPECT_FALSE(found);
00167         found = true;
00168       }
00169     }
00170     EXPECT_TRUE(found);
00171   }
00172 
00173   // Case 2: RPP=/test3
00174   rr = std::string(getcwd(buf, sizeof(buf))) + "/test3";
00175   setenv("ROS_PACKAGE_PATH", rr.c_str(), 1);
00176   test_pkgs.clear();
00177   test_pkgs.push_back("precedence1");
00178   test_pkgs.push_back("precedence2");
00179   test_pkgs.push_back("precedence3");
00180   ret = rp.run(std::string("list-names"));
00181   EXPECT_EQ(ret, 0);
00182   output_list.clear();
00183   output = rp.getOutput();
00184   boost::trim(output);
00185   boost::split(output_list, output, boost::is_any_of("\n"));
00186   // Check that we get back the right list of packages (which could be in any
00187   // order).
00188   EXPECT_EQ(output_list.size(), test_pkgs.size());
00189   for(std::vector<std::string>::const_iterator it = output_list.begin();
00190       it != output_list.end();
00191       ++it)
00192   {
00193     bool found = false;
00194     for(std::vector<std::string>::const_iterator it2 = test_pkgs.begin();
00195         it2 != test_pkgs.end();
00196         ++it2)
00197     {
00198       if(*it == *it2)
00199       {
00200         EXPECT_FALSE(found);
00201         found = true;
00202       }
00203     }
00204     EXPECT_TRUE(found);
00205   }
00206 
00207   // Case 3: RPP=/test_empty
00208   rr = std::string(getcwd(buf, sizeof(buf))) + "/test_empty";
00209   setenv("ROS_PACKAGE_PATH", rr.c_str(), 1);
00210   ret = rp.run(std::string("list-names"));
00211   EXPECT_EQ(ret, 0);
00212   output = rp.getOutput();
00213   boost::trim(output);
00214   EXPECT_EQ(output, std::string());
00215 
00216   // Reset old path, for other tests
00217   setenv("ROS_PACKAGE_PATH", oldrpp, 1);
00218 }
00219 
00220 int main(int argc, char **argv)
00221 {
00222   // Quiet some warnings
00223   (void)rospack::ROSPACK_NAME;
00224   (void)rospack::ROSSTACK_NAME;
00225 
00226   char buf[1024];
00227   std::string rr = std::string(getcwd(buf, sizeof(buf))) + "/test2";
00228   setenv("ROS_PACKAGE_PATH", rr.c_str(), 1);
00229   char path[PATH_MAX];
00230   if(getcwd(path,sizeof(path)))
00231   {
00232     boost::filesystem::path p(path);
00233     p = p.parent_path();
00234     std::string newpath = p.string();
00235     char* oldpath = getenv("PATH");
00236     if(oldpath)
00237       newpath += std::string(":") + oldpath;
00238     setenv("PATH", newpath.c_str(), 1);
00239   }
00240 
00241   testing::InitGoogleTest(&argc, argv);
00242   return RUN_ALL_TESTS();
00243 }


rospack
Author(s): Brian Gerkey, Morgan Quigley, Dirk Thomas
autogenerated on Sat Jun 8 2019 18:35:33