39 #include <urdf_parser/urdf_parser.h>
41 #include <gtest/gtest.h>
42 #include <gmock/gmock-matchers.h>
50 constexpr
double EPSILON{ 1.e-9 };
53 #if 0 // unused function
54 static bool sameStringIgnoringWS(
const std::string& s1,
const std::string& s2)
58 while (i1 < s1.size() && isspace(s1[i1]))
60 while (i2 < s2.size() && isspace(s2[i2]))
62 while (i1 < s1.size() && i2 < s2.size())
64 if (i1 < s1.size() && i2 < s2.size())
71 while (i1 < s1.size() && isspace(s1[i1]))
73 while (i2 < s2.size() && isspace(s2[i2]))
76 return i1 == s1.size() && i2 == s2.size();
80 static void expect_near(
const Eigen::MatrixXd& x,
const Eigen::MatrixXd& y,
81 double eps = std::numeric_limits<double>::epsilon())
83 ASSERT_EQ(
x.rows(),
y.rows());
84 ASSERT_EQ(
x.cols(),
y.cols());
85 for (
int r = 0;
r <
x.rows(); ++
r)
86 for (
int c = 0; c <
x.cols(); ++c)
91 #define EXPECT_NEAR_TRACED(...) { \
92 SCOPED_TRACE("expect_near(" #__VA_ARGS__ ")"); \
93 expect_near(__VA_ARGS__); \
100 builder.
addVirtualJoint(
"odom_combined",
"base_link",
"floating",
"base_joint");
101 ASSERT_TRUE(builder.
isValid());
102 moveit::core::RobotModelPtr model = builder.
build();
112 EXPECT_EQ(std::string(
"myrobot"), model->getName());
115 const std::vector<moveit::core::LinkModel*>& links = model->getLinkModels();
116 EXPECT_EQ((
unsigned int)1, links.size());
118 const std::vector<moveit::core::JointModel*>& joints = model->getJointModels();
119 EXPECT_EQ((
unsigned int)1, joints.size());
121 const std::vector<std::string>& pgroups = model->getJointModelGroupNames();
122 EXPECT_EQ((
unsigned int)0, pgroups.size());
128 geometry_msgs::Pose pose;
129 tf2::toMsg(tf2::Vector3(-0.1, 0, 0), pose.position);
134 tf2::toMsg(tf2::Vector3(0, 0, 0), pose.position);
138 tf2::toMsg(tf2::Vector3(0, 0.099, 0), pose.position);
141 builder.
addInertial(
"base_link", 2.81, pose, 0.1, -0.2, 0.5, -0.09, 1, 0.101);
142 builder.
addVirtualJoint(
"odom_combined",
"base_link",
"planar",
"base_joint");
143 builder.
addGroup({}, {
"base_joint" },
"base");
145 ASSERT_TRUE(builder.
isValid());
146 moveit::core::RobotModelPtr model = builder.
build();
153 EXPECT_EQ((
unsigned int)1, (
unsigned int)model->getJointModelCount());
154 EXPECT_EQ((
unsigned int)3, (
unsigned int)model->getJointModels()[0]->getLocalVariableNames().size());
156 std::map<std::string, double> joint_values;
157 joint_values[
"base_joint/x"] = 10.0;
158 joint_values[
"base_joint/y"] = 8.0;
161 std::vector<std::string> missing_states;
163 ASSERT_EQ(missing_states.size(), 1u);
164 EXPECT_EQ(missing_states[0], std::string(
"base_joint/theta"));
165 joint_values[
"base_joint/theta"] = 0.1;
168 ASSERT_EQ(missing_states.size(), 0u);
174 const auto new_state = std::make_unique<moveit::core::RobotState>(state);
178 jv[state.
getRobotModel()->getVariableIndex(
"base_joint/x")] = 5.0;
179 jv[state.
getRobotModel()->getVariableIndex(
"base_joint/y")] = 4.0;
180 jv[state.
getRobotModel()->getVariableIndex(
"base_joint/theta")] = 0.0;
188 char const*
const urdf_description = R
"(
189 <robot name="minibot">
194 <joint name="link1_joint" type="prismatic">
195 <parent link="root"/>
196 <child link="link1"/>
197 <limit effort="1" velocity="1" lower="0" upper="1"/>
200 <joint name="link2_joint" type="fixed">
201 <parent link="link1"/>
202 <child link="link2"/>
207 char const*
const srdf_description = R
"(
208 <robot name="minibot">
209 <virtual_joint name="world_to_root" type="fixed" parent_frame="world" child_link="root"/>
213 auto urdf = std::make_shared<urdf::Model>();
214 ASSERT_TRUE(
urdf->initString(urdf_description));
215 auto srdf = std::make_shared<srdf::Model>();
216 ASSERT_TRUE(
srdf->initString(*
urdf, srdf_description));
217 moveit::core::RobotModelConstPtr model = std::make_shared<moveit::core::RobotModel>(
urdf,
srdf);
222 const auto& cstate = state;
226 EXPECT_FALSE(cstate.dirtyJointTransform(model->getJointModel(
"link1_joint")));
227 EXPECT_FALSE(cstate.dirtyJointTransform(model->getJointModel(
"link2_joint")));
229 std::cout << cstate << std::endl;
237 static const std::string MODEL2 = R
"(
238 <?xml version="1.0" ?>
239 <robot name="one_robot">
240 <link name="base_link">
243 <origin rpy="0 0 0" xyz="0.0 0.0 .0"/>
244 <inertia ixx="0.1" ixy="-0.2" ixz="0.5" iyy="-.09" iyz="1" izz="0.101"/>
246 <collision name="my_collision">
247 <origin rpy="0 0 0" xyz="0 0 0"/>
253 <origin rpy="0 0 0" xyz="0.0 0 0"/>
259 <joint name="joint_a" type="continuous">
261 <parent link="base_link"/>
262 <child link="link_a"/>
263 <origin rpy=" 0.0 0 0 " xyz="0.0 0 0 "/>
268 <origin rpy="0 0 0" xyz="0.0 0.0 .0"/>
269 <inertia ixx="0.1" ixy="-0.2" ixz="0.5" iyy="-.09" iyz="1" izz="0.101"/>
272 <origin rpy="0 0 0" xyz="0 0 0"/>
278 <origin rpy="0 0 0" xyz="0.0 0 0"/>
284 <joint name="joint_b" type="fixed">
285 <parent link="link_a"/>
286 <child link="link_b"/>
287 <origin rpy=" 0.0 -0.42 0 " xyz="0.0 0.5 0 "/>
292 <origin rpy="0 0 0" xyz="0.0 0.0 .0"/>
293 <inertia ixx="0.1" ixy="-0.2" ixz="0.5" iyy="-.09" iyz="1" izz="0.101"/>
296 <origin rpy="0 0 0" xyz="0 0 0"/>
302 <origin rpy="0 0 0" xyz="0.0 0 0"/>
308 <joint name="joint_c" type="prismatic">
310 <limit effort="100.0" lower="0.0" upper="0.09" velocity="0.2"/>
311 <safety_controller k_position="20.0" k_velocity="500.0" soft_lower_limit="0.0"
312 soft_upper_limit="0.089"/>
313 <parent link="link_b"/>
314 <child link="link_c"/>
315 <origin rpy=" 0.0 0.42 0.0 " xyz="0.0 -0.1 0 "/>
320 <origin rpy="0 0 0" xyz="0.0 0 .0"/>
321 <inertia ixx="0.1" ixy="-0.2" ixz="0.5" iyy="-.09" iyz="1" izz="0.101"/>
324 <origin rpy="0 0 0" xyz="0 0 0"/>
330 <origin rpy="0 0 0" xyz="0.0 0 0"/>
336 <joint name="mim_f" type="prismatic">
338 <limit effort="100.0" lower="0.0" upper="0.19" velocity="0.2"/>
339 <parent link="link_c"/>
340 <child link="link_d"/>
341 <origin rpy=" 0.0 0.0 0.0 " xyz="0.1 0.1 0 "/>
342 <mimic joint="joint_f" multiplier="1.5" offset="0.1"/>
344 <joint name="joint_f" type="prismatic">
346 <limit effort="100.0" lower="0.0" upper="0.19" velocity="0.2"/>
347 <parent link="link_d"/>
348 <child link="link_e"/>
349 <origin rpy=" 0.0 0.0 0.0 " xyz="0.1 0.1 0 "/>
353 <origin rpy="0 0 0" xyz="0 0 0"/>
359 <origin rpy="0 1 0" xyz="0 0.1 0"/>
367 <origin rpy="0 0 0" xyz="0 0 0"/>
373 <origin rpy="0 1 0" xyz="0 0.1 0"/>
379 <link name="link/with/slash" />
380 <joint name="joint_link_with_slash" type="fixed">
381 <parent link="base_link"/>
382 <child link="link/with/slash"/>
383 <origin rpy="0 0 0" xyz="0 0 0"/>
387 static const std::string SMODEL2 = R
"(
388 <?xml version="1.0" ?>
389 <robot name="one_robot">
390 <virtual_joint name="base_joint" child_link="base_link" parent_frame="odom_combined" type="planar"/>
391 <group name="base_from_joints">
392 <joint name="base_joint"/>
393 <joint name="joint_a"/>
394 <joint name="joint_c"/>
396 <group name="mim_joints">
397 <joint name="joint_f"/>
398 <joint name="mim_f"/>
400 <group name="base_with_subgroups">
401 <group name="base_from_base_to_tip"/>
402 <joint name="joint_c"/>
404 <group name="base_from_base_to_tip">
405 <chain base_link="base_link" tip_link="link_b"/>
406 <joint name="base_joint"/>
408 <group name="base_from_base_to_e">
409 <chain base_link="base_link" tip_link="link_e"/>
410 <joint name="base_joint"/>
412 <group name="base_with_bad_subgroups">
413 <group name="error"/>
418 urdf::ModelInterfaceSharedPtr urdf_model = urdf::parseURDF(MODEL2);
420 srdf_model->initString(*urdf_model, SMODEL2);
421 robot_model_ = std::make_shared<moveit::core::RobotModel>(urdf_model, srdf_model);
434 moveit::core::RobotModelConstPtr model = robot_model_;
443 ASSERT_TRUE(g_one !=
nullptr);
444 ASSERT_TRUE(g_two !=
nullptr);
445 ASSERT_TRUE(g_three !=
nullptr);
446 ASSERT_TRUE(g_four ==
nullptr);
448 EXPECT_THAT(g_one->
getJointModelNames(), ::testing::ElementsAreArray({
"base_joint",
"joint_a",
"joint_c" }));
449 EXPECT_THAT(g_two->
getJointModelNames(), ::testing::ElementsAreArray({
"base_joint",
"joint_a",
"joint_b" }));
451 ::testing::ElementsAreArray({
"base_joint",
"joint_a",
"joint_b",
"joint_c" }));
452 EXPECT_THAT(g_mim->
getJointModelNames(), ::testing::ElementsAreArray({
"mim_f",
"joint_f" }));
454 EXPECT_THAT(g_one->
getLinkModelNames(), ::testing::ElementsAreArray({
"base_link",
"link_a",
"link_c" }));
455 EXPECT_THAT(g_two->
getLinkModelNames(), ::testing::ElementsAreArray({
"base_link",
"link_a",
"link_b" }));
456 EXPECT_THAT(g_three->
getLinkModelNames(), ::testing::ElementsAreArray({
"base_link",
"link_a",
"link_b",
"link_c" }));
459 auto updated_link_model_names = {
"base_link",
"link_a",
"link_b",
"link_c",
"link_d",
"link_e",
"link/with/slash" };
470 std::map<std::string, double> joint_values;
471 joint_values[
"base_joint/x"] = 1.0;
472 joint_values[
"base_joint/y"] = 1.0;
473 joint_values[
"base_joint/theta"] = 0.5;
474 joint_values[
"joint_a"] = -0.5;
475 joint_values[
"joint_c"] = 0.08;
504 std::map<std::string, double> upd_a;
505 upd_a[
"joint_a"] = 0.2;
512 upd_a[
"joint_a"] = 3.2;
565 ASSERT_TRUE(joint_model_group);
569 std::cout <<
"\nVisual inspection should show NO joints out of bounds:" << std::endl;
572 std::cout <<
"\nVisual inspection should show ONE joint out of bounds:" << std::endl;
573 std::vector<double> single_joint(1);
574 single_joint[0] = -1.0;
578 std::cout <<
"\nVisual inspection should show TWO joint out of bounds:" << std::endl;
579 single_joint[0] = 1.0;
583 std::cout <<
"\nVisual inspection should show ONE joint out of bounds:" << std::endl;
584 single_joint[0] = 0.19;
597 for (
size_t i = 0; i <= 10; ++i)
599 state_a.
interpolate(state_b,
static_cast<double>(i) / 10., interpolated_state,
602 <<
"Interpolation between identical states yielded a different state.";
604 for (
const auto& link_name : robot_model_->getLinkModelNames())
607 <<
"Interpolation between identical states yielded NaN value.";
612 std::map<std::string, double> joint_values;
613 joint_values[
"base_joint/x"] = 1.0;
614 joint_values[
"base_joint/y"] = 1.0;
616 joint_values[
"base_joint/x"] = 0.0;
617 joint_values[
"base_joint/y"] = 2.0;
623 <<
"Simple interpolation of base_joint failed.";
625 <<
"Simple interpolation of base_joint failed.";
627 <<
"Simple interpolation of base_joint failed.";
630 <<
"Simple interpolation of base_joint failed.";
632 <<
"Simple interpolation of base_joint failed.";
635 joint_values[
"base_joint/x"] = 0.0;
636 joint_values[
"base_joint/y"] = 20.0;
637 joint_values[
"base_joint/theta"] = 3 *
M_PI / 4;
638 joint_values[
"joint_a"] = -4 *
M_PI / 5;
639 joint_values[
"joint_c"] = 0.0;
640 joint_values[
"joint_f"] = 1.0;
643 joint_values[
"base_joint/x"] = 10.0;
644 joint_values[
"base_joint/y"] = 0.0;
645 joint_values[
"base_joint/theta"] = -3 *
M_PI / 4;
646 joint_values[
"joint_a"] = 4 *
M_PI / 5;
647 joint_values[
"joint_c"] = 0.07;
648 joint_values[
"joint_f"] = 0.0;
651 for (
size_t i = 0; i <= 5; ++i)
653 double t =
static_cast<double>(i) / 5.;
656 <<
"Base joint interpolation failed.";
658 <<
"Base joint interpolation failed.";
662 <<
"Base joint theta interpolation failed.";
664 <<
"Continuous joint interpolation failed.";
670 <<
"Base joint theta interpolation failed.";
672 <<
"Continuous joint interpolation failed.";
675 <<
"Interpolation of joint_c failed.";
677 <<
"Interpolation of joint_f failed.";
679 <<
"Interpolation of mimic joint mim_f failed.";
682 bool nan_exception =
false;
685 const double infty = std::numeric_limits<double>::infinity();
688 catch (std::exception& e)
690 std::cout <<
"Caught expected exception: " << e.what() << std::endl;
691 nan_exception =
true;
693 EXPECT_TRUE(nan_exception) <<
"NaN interpolation parameter did not create expected exception.";
700 EXPECT_EQ(robot_model_->getRigidlyConnectedParentLinkModel(link_e), link_e);
705 EXPECT_EQ(robot_model_->getRigidlyConnectedParentLinkModel(link_b), link_a);
710 Eigen::Isometry3d a_to_b;
713 EXPECT_NEAR_TRACED(a_to_b.translation(), Eigen::Translation3d(0, 0.5, 0).translation());
716 state.
attachBody(std::make_unique<moveit::core::AttachedBody>(
717 link_b,
"object", Eigen::Isometry3d(Eigen::Translation3d(1, 0, 0)), std::vector<shapes::ShapeConstPtr>{},
740 ASSERT_TRUE(rigid_parent_of_link_with_slash);
744 state.
attachBody(std::make_unique<moveit::core::AttachedBody>(
745 link_with_slash,
"object/with/slash", Eigen::Isometry3d(Eigen::Translation3d(1, 0, 0)),
747 trajectory_msgs::JointTrajectory{},
751 ASSERT_TRUE(rigid_parent_of_object);
752 EXPECT_EQ(rigid_parent_of_link_with_slash, rigid_parent_of_object);
755 int main(
int argc,
char** argv)
757 testing::InitGoogleTest(&argc, argv);
758 return RUN_ALL_TESTS();