typekit_test.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 #include <ocl/DeploymentComponent.hpp>
4 #include <rtt/types/Types.hpp>
6 #include <kdl/frames.hpp>
7 #include <kdl/chain.hpp>
8 #include <kdl/jacobian.hpp>
9 #include <kdl/jntarray.hpp>
10 #include <kdl/frames_io.hpp>
11 #include <rtt/os/main.h>
12 
13 class KDLPluginTest : public testing::Test {
14 
15 #define COMPNAME "Deployer"
16 
17 protected:
19  depl(COMPNAME),
20  chain_prop("chain",""),
21  frame_prop("frame",""),
22  jacobian_prop("jacobian",""),
23  jntarray_prop("jntarray",""),
24  joint_prop("joint",""),
25  rotation_prop("rotation",""),
26  segment_prop("segment",""),
27  twist_prop("twist",""),
28  vector_prop("vector",""),
29  wrench_prop("wrench","")
30  {}
31 
32  virtual void SetUp(){
33  }
34  virtual void TearDown(){
35  }
36 
58 };
59 
60 TEST_F(KDLPluginTest,loadTypekit)
61 {
62  ASSERT_TRUE(depl.import("kdl_typekit"));
63 }
64 
65 TEST_F(KDLPluginTest,getKDLTypes)
66 {
67  EXPECT_FALSE(NULL==RTT::types::Types()->getTypeInfo<KDL::Chain>());
68  EXPECT_FALSE(NULL==RTT::types::Types()->getTypeInfo<KDL::Frame>());
69  EXPECT_FALSE(NULL==RTT::types::Types()->getTypeInfo<KDL::Jacobian>());
70  EXPECT_FALSE(NULL==RTT::types::Types()->getTypeInfo<KDL::JntArray>());
71  EXPECT_FALSE(NULL==RTT::types::Types()->getTypeInfo<KDL::Joint>());
72  EXPECT_FALSE(NULL==RTT::types::Types()->getTypeInfo<KDL::Rotation>());
73  EXPECT_FALSE(NULL==RTT::types::Types()->getTypeInfo<KDL::Segment>());
74  EXPECT_FALSE(NULL==RTT::types::Types()->getTypeInfo<KDL::Twist>());
75  EXPECT_FALSE(NULL==RTT::types::Types()->getTypeInfo<KDL::Vector>());
76  EXPECT_FALSE(NULL==RTT::types::Types()->getTypeInfo<KDL::Wrench>());
77 }
78 //What do we want test:
79 //Create every type as property
80 //Write all types to file
81 //Read all types from file
82 //Write to other file
83 //Read again, are they the same??
84 
85 
86 TEST_F(KDLPluginTest,createProperties)
87 {
88  EXPECT_TRUE(depl.addProperty(chain_prop));
89  EXPECT_TRUE(depl.getProperty(chain_prop.getName())->ready());
90  EXPECT_TRUE(depl.addProperty(frame_prop));
91  EXPECT_TRUE(depl.addProperty(jacobian_prop));
92  EXPECT_TRUE(depl.addProperty(jntarray_prop));
93  EXPECT_TRUE(depl.addProperty(joint_prop));
94  EXPECT_TRUE(depl.addProperty(rotation_prop));
95  EXPECT_TRUE(depl.addProperty(segment_prop));
96  EXPECT_TRUE(depl.addProperty(twist_prop));
97  EXPECT_TRUE(depl.addProperty(vector_prop));
98  EXPECT_TRUE(depl.addProperty(wrench_prop));
99 
100 
101 }
102 
103 TEST_F(KDLPluginTest,writeProperties)
104 {
105  boost::shared_ptr<RTT::Marshalling> marsh = depl.getProvider<RTT::Marshalling>("marshalling");
106  //EXPECT_TRUE(depl.addProperty(chain_prop));
107  //EXPECT_TRUE(depl.getProperty(chain_prop.getName())->ready());
108  EXPECT_TRUE(depl.addProperty(frame_prop));
109  //EXPECT_TRUE(depl.addProperty(jacobian_prop));
110  EXPECT_TRUE(depl.addProperty(jntarray_prop));
111  EXPECT_TRUE(depl.addProperty(joint_prop));
112  EXPECT_TRUE(depl.addProperty(rotation_prop));
113  EXPECT_TRUE(depl.addProperty(segment_prop));
114  EXPECT_TRUE(depl.addProperty(twist_prop));
115  EXPECT_TRUE(depl.addProperty(vector_prop));
116  EXPECT_TRUE(depl.addProperty(wrench_prop));
117 
123  jntarray.resize(3);
124  KDL::random(jntarray(0));
125  KDL::random(jntarray(1));
126  KDL::random(jntarray(2));
133 
134  EXPECT_TRUE(marsh->storeProperties("test.cpf"));
135  EXPECT_TRUE(marsh->writeProperties("test1.cpf"));
136  EXPECT_TRUE(marsh->updateFile("test1.cpf"));
137  EXPECT_TRUE(marsh->readProperties("test.cpf"));
138 
139  EXPECT_EQ(frame_prop.value(),frame);
140  EXPECT_EQ(twist_prop.value(),twist);
141  EXPECT_EQ(vector_prop.value(),vector);
142  EXPECT_EQ(wrench_prop.value(),wrench);
143  EXPECT_EQ(rotation_prop.value(),rotation);
144  EXPECT_EQ(jntarray_prop.value(),jntarray);
145 }
146 
147 int ORO_main(int argc, char **argv){
148  testing::InitGoogleTest(&argc,argv);
149  return RUN_ALL_TESTS();
150 }
151 
RTT::Property< KDL::JntArray > jntarray_prop
#define COMPNAME
Property< T > & addProperty(const std::string &name, T &attr)
KDL::Chain chain
KDL::Wrench wrench
TEST_F(KDLPluginTest, loadTypekit)
bool import(const std::string &package)
RTT::Property< KDL::Rotation > rotation_prop
RTT::Property< KDL::Twist > twist_prop
RTT::Property< KDL::Segment > segment_prop
RTT::Property< KDL::Frame > frame_prop
KDL::Joint joint
KDL::Rotation rotation
OCL::DeploymentComponent depl
reference_t value()
KDL::Twist twist
RTT::Property< KDL::Jacobian > jacobian_prop
KDL::Vector vector
TypeInfoRepository::shared_ptr Types()
virtual void SetUp()
virtual void TearDown()
void resize(unsigned int newSize)
KDL::Segment segment
base::PropertyBase * getProperty(const std::string &name) const
RTT::Property< KDL::Joint > joint_prop
void random(Jacobian< T > &rv)
const std::string & getName() const
KDL::Frame frame
KDL::JntArray jntarray
KDL::Jacobian jac
RTT::Property< KDL::Vector > vector_prop
RTT::Property< KDL::Wrench > wrench_prop
RTT::Property< KDL::Chain > chain_prop
int ORO_main(int argc, char **argv)
boost::shared_ptr< ServiceType > getProvider(const std::string &name)


kdl_typekit
Author(s): Steven Bellens, Ruben Smits
autogenerated on Wed Jul 3 2019 19:39:45