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 00019 #include <boost/assign/std/vector.hpp> 00020 using namespace boost::assign; 00021 00022 #include <gtest/gtest.h> 00023 00024 boost::shared_ptr<OCL::DeploymentComponent> deployer; 00025 boost::shared_ptr<RTT::Scripting> scripting_service; 00026 00027 TEST(BasicTest, Import) 00028 { 00029 // Import rtt_ros plugin 00030 EXPECT_TRUE(RTT::ComponentLoader::Instance()->import("rtt_ros", "" )); 00031 EXPECT_TRUE(RTT::ComponentLoader::Instance()->import("rtt_roscomm", "" )); 00032 } 00033 00034 TEST(BasicTest, ImportTypekit) 00035 { 00036 // Import rtt_ros plugin 00037 EXPECT_TRUE(RTT::ComponentLoader::Instance()->import("rtt_std_msgs", "" )); 00038 EXPECT_TRUE(scripting_service->eval("var ConnPolicy float_out = ros.topic(\"float_out\")")); 00039 } 00040 00041 int main(int argc, char** argv) { 00042 testing::InitGoogleTest(&argc, argv); 00043 00044 // Initialize Orocos 00045 __os_init(argc, argv); 00046 00047 deployer = boost::make_shared<OCL::DeploymentComponent>(); 00048 scripting_service = deployer->getProvider<RTT::Scripting>("scripting"); 00049 00050 RTT::Logger::log().setStdStream(std::cerr); 00051 RTT::Logger::log().mayLogStdOut(true); 00052 RTT::Logger::log().setLogLevel(RTT::Logger::Debug); 00053 00054 return RUN_ALL_TESTS(); 00055 } 00056