38 #include <gtest/gtest.h>
42 #include <urdf_parser/urdf_parser.h>
44 static const char*
URDF_STR =
"<?xml version=\"1.0\" ?>"
45 "<robot name=\"one_robot\">"
46 "<link name=\"base_link\">"
48 " <mass value=\"2.81\"/>"
49 " <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>"
50 " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
52 " <collision name=\"my_collision\">"
53 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
55 " <box size=\"1 2 1\" />"
59 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
61 " <box size=\"1 2 1\" />"
65 "<joint name=\"joint_a\" type=\"continuous\">"
66 " <axis xyz=\"0 0 1\"/>"
67 " <parent link=\"base_link\"/>"
68 " <child link=\"link_a\"/>"
69 " <origin rpy=\" 0.0 0 0 \" xyz=\"0.0 0 0 \"/>"
71 "<link name=\"link_a\">"
73 " <mass value=\"1.0\"/>"
74 " <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>"
75 " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
78 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
80 " <box size=\"1 2 1\" />"
84 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
86 " <box size=\"1 2 1\" />"
90 "<joint name=\"joint_b\" type=\"fixed\">"
91 " <parent link=\"link_a\"/>"
92 " <child link=\"link_b\"/>"
93 " <origin rpy=\" 0.0 -0.42 0 \" xyz=\"0.0 0.5 0 \"/>"
95 "<link name=\"link_b\">"
97 " <mass value=\"1.0\"/>"
98 " <origin rpy=\"0 0 0\" xyz=\"0.0 0.0 .0\"/>"
99 " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
102 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
104 " <box size=\"1 2 1\" />"
108 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
110 " <box size=\"1 2 1\" />"
114 " <joint name=\"joint_c\" type=\"prismatic\">"
115 " <axis xyz=\"1 0 0\"/>"
116 " <limit effort=\"100.0\" lower=\"0.0\" upper=\"0.09\" velocity=\"0.2\"/>"
117 " <safety_controller k_position=\"20.0\" k_velocity=\"500.0\" "
118 "soft_lower_limit=\"0.0\" soft_upper_limit=\"0.089\"/>"
119 " <parent link=\"link_b\"/>"
120 " <child link=\"link_c\"/>"
121 " <origin rpy=\" 0.0 0.42 0.0 \" xyz=\"0.0 -0.1 0 \"/>"
123 "<link name=\"link_c\">"
125 " <mass value=\"1.0\"/>"
126 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 .0\"/>"
127 " <inertia ixx=\"0.1\" ixy=\"-0.2\" ixz=\"0.5\" iyy=\"-.09\" iyz=\"1\" izz=\"0.101\"/>"
130 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
132 " <box size=\"1 2 1\" />"
136 " <origin rpy=\"0 0 0\" xyz=\"0.0 0 0\"/>"
138 " <box size=\"1 2 1\" />"
142 " <joint name=\"mim_f\" type=\"prismatic\">"
143 " <axis xyz=\"1 0 0\"/>"
144 " <limit effort=\"100.0\" lower=\"0.0\" upper=\"0.19\" velocity=\"0.2\"/>"
145 " <parent link=\"link_c\"/>"
146 " <child link=\"link_d\"/>"
147 " <origin rpy=\" 0.0 0.1 0.0 \" xyz=\"0.1 0.1 0 \"/>"
148 " <mimic joint=\"joint_f\" multiplier=\"1.5\" offset=\"0.1\"/>"
150 " <joint name=\"joint_f\" type=\"prismatic\">"
151 " <axis xyz=\"1 0 0\"/>"
152 " <limit effort=\"100.0\" lower=\"0.0\" upper=\"0.19\" velocity=\"0.2\"/>"
153 " <parent link=\"link_d\"/>"
154 " <child link=\"link_e\"/>"
155 " <origin rpy=\" 0.0 0.1 0.0 \" xyz=\"0.1 0.1 0 \"/>"
157 "<link name=\"link_d\">"
159 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
161 " <box size=\"1 2 1\" />"
165 " <origin rpy=\"0 1 0\" xyz=\"0 0.1 0\"/>"
167 " <box size=\"1 2 1\" />"
171 "<link name=\"link_e\">"
173 " <origin rpy=\"0 0 0\" xyz=\"0 0 0\"/>"
175 " <box size=\"1 2 1\" />"
179 " <origin rpy=\"0 1 0\" xyz=\"0 0.1 0\"/>"
181 " <box size=\"1 2 1\" />"
188 "<?xml version=\"1.0\" ?>"
189 "<robot name=\"one_robot\">"
190 "<virtual_joint name=\"base_joint\" child_link=\"base_link\" parent_frame=\"odom_combined\" type=\"planar\"/>"
191 "<group name=\"base_from_joints\">"
192 "<joint name=\"base_joint\"/>"
193 "<joint name=\"joint_a\"/>"
194 "<joint name=\"joint_c\"/>"
196 "<group name=\"mim_joints\">"
197 "<joint name=\"joint_f\"/>"
198 "<joint name=\"mim_f\"/>"
200 "<group name=\"base_with_subgroups\">"
201 "<group name=\"base_from_base_to_tip\"/>"
202 "<joint name=\"joint_c\"/>"
204 "<group name=\"base_from_base_to_tip\">"
205 "<chain base_link=\"base_link\" tip_link=\"link_b\"/>"
206 "<joint name=\"base_joint\"/>"
221 static moveit::core::RobotModelPtr model;
224 urdf::ModelInterfaceSharedPtr
urdf(urdf::parseURDF(
URDF_STR));
225 auto srdf = std::make_shared<srdf::Model>();
227 model = std::make_shared<moveit::core::RobotModel>(
urdf,
srdf);
235 moveit::core::RobotModelPtr model =
getModel();
247 TEST(LockedRobotState, URDF_sanity)
249 moveit::core::RobotModelPtr model =
getModel();
276 TEST(LockedRobotState, robotStateChanged)
278 moveit::core::RobotModelPtr model =
getModel();
338 moveit::core::RobotStateConstPtr
s = locked_state.
getState();
359 for (
int i = 0; i < cnt; ++i)
375 for (
int loops = 0; loops < 100; ++loops)
394 for (
int loops = 0; loops < 100; ++loops)
432 for (
int loops = 0; loops < 100; ++loops)
458 for (
int i = 0; counters[i]; ++i)
460 if (counters[i][0] < max)
481 moveit::core::RobotModelPtr model =
getModel();
484 int num = ncheck + nset + nmod;
486 typedef int* int_ptr;
487 typedef boost::thread* thread_ptr;
488 int* cnt =
new int[num];
489 int_ptr* counters =
new int_ptr[num + 1];
490 thread_ptr* threads =
new thread_ptr[num];
496 for (
int i = 0; i < ncheck; ++i)
499 counters[p] = &cnt[p];
506 for (
int i = 0; i < nset; ++i)
509 counters[p] = &cnt[p];
516 for (
int i = 0; i < nmod; ++i)
519 counters[p] = &cnt[p];
526 counters[p] =
nullptr;
533 for (
int i = 0; i < p; ++i)
540 for (
int i = 0; i < p; ++i)
557 #define OPT_TEST(F, N) TEST(F, N)
559 #define OPT_TEST(F, N) TEST(F, DISABLED_##N)
622 int main(
int argc,
char** argv)
624 testing::InitGoogleTest(&argc, argv);
625 return RUN_ALL_TESTS();