40 #include <gtest/gtest.h> 41 #include <kdl/jntarray.hpp> 42 #include <kdl/chainidsolver_recursive_newton_euler.hpp> 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));
87 solver.CartToJnt(q, qdot, qdotdot, wrenches, torques_1);
98 ASSERT_TRUE(tree_2->
getChain(
"base_link",
"link2", chain));
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();
TEST_F(TestInertiaRPY, test_torques)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
TestInertiaRPY()
constructor
unsigned int getNrOfJoints() const
KDL_PARSER_PUBLIC bool treeFromFile(const std::string &file, KDL::Tree &tree)
int main(int argc, char **argv)
bool getChain(const std::string &chain_root, const std::string &chain_tip, Chain &chain) const
~TestInertiaRPY()
Destructor.
unsigned int getNrOfSegments() const
unsigned int getNrOfJoints() const