00001 00006 #include <string> 00007 #include <vector> 00008 #include <iterator> 00009 00010 #include <rtt/os/startstop.h> 00011 00012 #include <ocl/DeploymentComponent.hpp> 00013 #include <ocl/TaskBrowser.hpp> 00014 #include <ocl/LoggingService.hpp> 00015 #include <rtt/Logger.hpp> 00016 #include <rtt/deployment/ComponentLoader.hpp> 00017 #include <rtt/scripting/Scripting.hpp> 00018 #include <rtt/internal/GlobalService.hpp> 00019 00020 #include <ros/package.h> 00021 00022 #include <boost/assign/std/vector.hpp> 00023 using namespace boost::assign; 00024 00025 #include <gtest/gtest.h> 00026 00027 boost::shared_ptr<OCL::DeploymentComponent> deployer; 00028 boost::shared_ptr<RTT::Scripting> scripting_service; 00029 RTT::Service::shared_ptr global_service; 00030 00031 TEST(BasicTest, Import) 00032 { 00033 // Import rtt_ros plugin 00034 RTT::ComponentLoader::Instance()->import("rtt_ros", "" ); 00035 } 00036 00037 TEST(BasicTest, PackageFinding) 00038 { 00039 // Import rtt_ros plugin 00040 EXPECT_TRUE(scripting_service->eval("ros.import(\"rtt_rospack_tests\")")); 00041 00042 RTT::OperationCaller<std::string(const std::string&)> rpf = global_service->provides("ros")->getOperation("find"); 00043 std::string roscpp_dir = ros::package::getPath("roscpp"); 00044 EXPECT_EQ(roscpp_dir,rpf("roscpp")); 00045 00046 std::string rtt_rospack_tests_dir = ros::package::getPath("rtt_rospack_tests"); 00047 EXPECT_EQ(rtt_rospack_tests_dir,rpf("rtt_rospack_tests")); 00048 } 00049 00050 00051 int main(int argc, char** argv) { 00052 testing::InitGoogleTest(&argc, argv); 00053 00054 // Initialize Orocos 00055 __os_init(argc, argv); 00056 00057 deployer = boost::make_shared<OCL::DeploymentComponent>(); 00058 scripting_service = deployer->getProvider<RTT::Scripting>("scripting"); 00059 global_service = RTT::internal::GlobalService::Instance(); 00060 00061 RTT::Logger::log().setStdStream(std::cerr); 00062 RTT::Logger::log().mayLogStdOut(true); 00063 RTT::Logger::log().setLogLevel(RTT::Logger::Debug); 00064 00065 return RUN_ALL_TESTS(); 00066 }