40 #include <gtest/gtest.h>
41 #include <kdl/jntarray.hpp>
42 #include <kdl/chainidsolver_recursive_newton_euler.hpp>
69 KDL::Tree * tree_1 =
new KDL::Tree;
70 KDL::Tree * tree_2 =
new KDL::Tree;
71 KDL::JntArray torques_1;
72 KDL::JntArray torques_2;
76 KDL::Vector gravity(0, 0, -9.81);
78 std::cout <<
"number of joints: " << tree_1->getNrOfJoints() << std::endl;
79 std::cout <<
"number of segments: " << tree_1->getNrOfSegments() << std::endl;
81 ASSERT_TRUE(tree_1->getChain(
"base_link",
"link2", chain));
82 KDL::ChainIdSolver_RNE solver(chain, gravity);
83 KDL::JntArray q(chain.getNrOfJoints());
84 KDL::JntArray qdot(chain.getNrOfJoints());
85 KDL::JntArray qdotdot(chain.getNrOfJoints());
86 std::vector<KDL::Wrench> wrenches(chain.getNrOfJoints());
87 solver.CartToJnt(q, qdot, qdotdot, wrenches, torques_1);
95 KDL::Vector gravity(0, 0, -9.81);
98 ASSERT_TRUE(tree_2->getChain(
"base_link",
"link2", chain));
99 KDL::ChainIdSolver_RNE solver(chain, gravity);
100 KDL::JntArray q(chain.getNrOfJoints());
101 KDL::JntArray qdot(chain.getNrOfJoints());
102 KDL::JntArray qdotdot(chain.getNrOfJoints());
103 std::vector<KDL::Wrench> wrenches(chain.getNrOfJoints());
104 solver.CartToJnt(q, qdot, qdotdot, wrenches, torques_2);
110 ASSERT_TRUE(torques_1 == torques_2);
115 int main(
int argc,
char ** argv)
117 testing::InitGoogleTest(&argc, argv);
118 ros::init(argc, argv,
"test_kdl_parser");
119 for (
size_t i = 0; i < argc; ++i) {
120 std::cout << argv[i] << std::endl;
124 return RUN_ALL_TESTS();