1 #include <boost/algorithm/string.hpp>
5 #include <gtest/gtest.h>
8 "<?xml version='1.0' ?>"
10 " <link name='link_0'/>"
11 " <joint name='first_joint' type='fixed'>"
12 " <origin rpy='0 0 0' xyz='1 1 1'/>"
13 " <parent link='link_0'/>"
14 " <child link='link_1'/>"
16 " <link name='link_1'/>"
17 " <joint name='second_joint' type='revolute'>"
18 " <origin rpy='0 0 0' xyz='0 0 0'/>"
19 " <axis xyz='0 0 1'/>"
20 " <limit effort='30' lower='-1.57' upper='1.57' velocity='0.524'/>"
21 " <parent link='link_1'/>"
22 " <child link='link_2'/>"
24 " <link name='link_2'/>"
25 " <joint name='third_joint' type='fixed'>"
26 " <origin rpy='0 -1.5 0' xyz='0 0 0.0526'/>"
27 " <parent link='link_2'/>"
28 " <child link='link_3'/>"
30 " <link name='link_3'/>"
34 "<?xml version=\"1.0\" ?>\n"
35 "<robot name=\"test\">\n"
36 " <link name=\"link_0\" />\n"
37 " <joint name=\"first_joint\" type=\"fixed\">\n"
38 " <origin rpy=\"0 0 0\" xyz=\"1 1 1\" />\n"
39 " <parent link=\"link_0\" />\n"
40 " <child link=\"link_1\" />\n"
42 " <link name=\"link_1\" />\n"
43 " <joint name=\"second_joint\" type=\"revolute\">\n"
44 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\" />\n"
45 " <axis xyz=\"0 0 1\" />\n"
46 " <limit effort=\"30\" lower=\"-1.57\" upper=\"1.57\" velocity=\"0.524\" />\n"
47 " <parent link=\"link_1\" />\n"
48 " <child link=\"link_2\" />\n"
49 " <calibration rising=\"0.245\" />\n"
51 " <link name=\"link_2\" />\n"
52 " <joint name=\"third_joint\" type=\"fixed\">\n"
53 " <origin rpy=\"1.57000000 -1.50000000 0.00000000\" xyz=\"0.00000000 0.00000000 0.05260000\" />\n"
54 " <parent link=\"link_2\" />\n"
55 " <child link=\"link_3\" />\n"
57 " <link name=\"link_3\" />\n"
60 TEST(CalibrationOffsetParserTests, test_urdf_update)
64 p.
add(
"second_joint");
65 p.
addFrame(
"third_joint",
true,
true,
true,
true,
true,
true);
67 double params[7] = {0.245, 0, 0, 0, 0, 0, 0};
70 KDL::Rotation
r = KDL::Rotation::RPY(1.57, 0, 0);
78 std::vector<std::string> s_pieces;
79 std::vector<std::string> robot_pieces;
81 boost::split(s_pieces,
s, boost::is_any_of(
"\n"));
84 for (
size_t i = 0; i < robot_pieces.size(); ++i)
86 ASSERT_STREQ(robot_pieces[i].c_str(), s_pieces[i].c_str());
90 TEST(CalibrationOffsetParserTests, test_multi_step)
94 p.
add(
"first_step_joint1");
95 p.
add(
"first_step_joint2");
97 double params[2] = {0.245, 0.44};
109 p.
add(
"second_step_joint1");
124 p.
add(
"first_step_joint1");
135 int main(
int argc,
char** argv)
137 testing::InitGoogleTest(&argc, argv);
138 return RUN_ALL_TESTS();