typekit_corba_test.cpp
Go to the documentation of this file.
1 #include <stdlib.h>
2 
3 #include <gtest/gtest.h>
4 #include <ocl/CorbaDeploymentComponent.hpp>
5 #include <rtt/os/main.h>
6 #include <rtt/TaskContext.hpp>
8 
10 
11 class KDLCORBAPluginTest : public testing::Test {
12 
13 protected:
16  std::string tmpdir;
17 
19  depl("Deployer"), tc(0)
20  {}
21 
22  int system(const std::string& command) {
23  return ::system(command.c_str());
24  }
25 
26  virtual void SetUp() {
27  // Create temporary directory to hold PID files
28  char tmpdir_c[] = "/tmp/kdl_typekitXXXXXX";
29  ASSERT_TRUE(mkdtemp(tmpdir_c) != NULL);
30  tmpdir = tmpdir_c;
31 
32  //Start CORBA nameserver (as a fallback if none is running yet)
33  system("omniNames -start -logdir $(mktemp -d) -errlog /dev/null &"
34  "echo $! > " + tmpdir + "/omniNames.pid &");
35  //Start server
36  system("./setupcomponent.ops &"
37  "echo $! > " + tmpdir + "/setupcomponent.pid &");
38  // Wait for server to startup
39  sleep(3);
40  //Setup corba
41  ASSERT_TRUE(RTT::corba::TaskContextServer::InitOrb( 0,0 )) << "Failed to bring up CORBA";
43  ASSERT_TRUE(depl.import("kdl_typekit"));
44  ASSERT_TRUE(depl.loadComponent("testcomponent","CORBA"));
45 
46  tc = 0;
47  tc = depl.getPeer("testcomponent");
48  ASSERT_FALSE(tc == 0);
49  }
50  virtual void TearDown(){
51  depl.shutdownDeployment();
54  system("kill $(cat " + tmpdir + "/setupcomponent.pid)");
55  system("kill $(cat " + tmpdir + "/omniNames.pid)");
56  }
57 };
58 
59 TEST_F(KDLCORBAPluginTest, VectorTest) {
60 
61  KDL::Vector v1(1.,2.,3.);
62  KDL::Vector v2(3.,2.,1.);
63  KDL::Vector v3(4.,5.,6.);
64 
65  //Set remote property
67  ASSERT_FALSE (prop == 0);
68  prop->set(v1);
69  EXPECT_EQ(prop->get(),v1) << "Failed to set remote KDL::Vector property";
70 
71  // Call vector operation (return current value of prop as return value and sets argument as new value)
73  KDL::Vector v4 = op(v2);
74  EXPECT_EQ(v4,v1) << "Failed to call remote operation with KDL type";
75 
76  //Write new value to port, will set current value of prop to outport and prop to new value
79  depl.addPort(wport);
80  depl.addPort(rport);
81  ASSERT_TRUE(wport.connectTo(tc->getPort("VectorIn")) && wport.connected()) << "Failed to connect to remote input port";
82  ASSERT_TRUE(rport.connectTo(tc->getPort("VectorOut")) && rport.connected()) << "Failed to connect to remote output port";
83 
84  wport.write(v3);
85  //wait for remote to handle write
86  sleep(1);
87  KDL::Vector v5;
88  ASSERT_EQ(rport.read(v5),RTT::NewData) << "Failed to read data from port";
89 
90  //Check if read value equals last value of property:
91  EXPECT_EQ(v5,v2) << "Failed to read KDL Vector from port";
92  //Check if current value of property is the written value:
93  KDL::Vector v6 = prop->get();
94  EXPECT_EQ(v6,v3) << "Failed to write KDL Vector to port";
95 }
96 
97 int ORO_main(int argc, char **argv){
98  testing::InitGoogleTest(&argc,argv);
99  return RUN_ALL_TESTS();
100 }
101 
DataSourceType get() const
Property< T > * getPropertyType(const std::string &name) const
base::PortInterface * getPort(const std::string &name) const
TEST_F(KDLCORBAPluginTest, VectorTest)
Variable opBinary s not applicable to op
bool import(const std::string &package)
FlowStatus read(base::DataSourceBase::shared_ptr source)
static RTT_CORBA_API bool InitOrb(int argc, char *argv[], Seconds orb_timeout=0)
virtual TaskContext * getPeer(const std::string &peer_name) const
RTT::TaskContext * tc
base::PortInterface & addPort(const std::string &name, base::PortInterface &port)
virtual bool connectTo(PortInterface *other, ConnPolicy const &policy)
WriteStatus write(const T &sample)
virtual bool connectTo(PortInterface *other, ConnPolicy const &policy)
int system(const std::string &command)
virtual bool connected() const
unsigned int sleep(unsigned int s)
PropertyBag * properties()
OperationInterfacePart * getOperation(std::string name)
bool loadComponent(const std::string &name, const std::string &type)
virtual bool connected() const
reference_t set()
static void ShutdownOrb(bool wait_for_completion=true)
int ORO_main(int argc, char **argv)
OCL::CorbaDeploymentComponent depl


kdl_typekit
Author(s): Steven Bellens, Ruben Smits
autogenerated on Tue Jan 5 2021 03:41:43