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> 15 #define COMPNAME "Deployer" 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"));
148 testing::InitGoogleTest(&argc,argv);
149 return RUN_ALL_TESTS();
RTT::Property< KDL::JntArray > jntarray_prop
Property< T > & addProperty(const std::string &name, T &attr)
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
OCL::DeploymentComponent depl
RTT::Property< KDL::Jacobian > jacobian_prop
TypeInfoRepository::shared_ptr Types()
void resize(unsigned int newSize)
base::PropertyBase * getProperty(const std::string &name) const
RTT::Property< KDL::Joint > joint_prop
void random(Jacobian< T > &rv)
const std::string & getName() const
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)