40 #include <urdf_parser/urdf_parser.h>
42 #include <gtest/gtest.h>
43 #include <boost/filesystem/path.hpp>
57 std::string robot_name =
"pr2";
75 ASSERT_EQ(urdf_model_->getName(),
"pr2");
76 ASSERT_EQ(srdf_model_->getName(),
"pr2");
81 auto srdf_model = std::make_shared<srdf::Model>();
87 static const std::string SMODEL1 =
"<?xml version=\"1.0\" ?>"
88 "<robot name=\"pr2\">"
89 "<virtual_joint name=\"base_joint\" child_link=\"base_footprint\" "
90 "parent_frame=\"base_footprint\" type=\"planar\"/>"
92 srdf_model->initString(*urdf_model_, SMODEL1);
98 static const std::string SMODEL2 =
"<?xml version=\"1.0\" ?>"
99 "<robot name=\"pr2\">"
100 "<virtual_joint name=\"world_joint\" child_link=\"base_footprint\" "
101 "parent_frame=\"odom_combined\" type=\"floating\"/>"
103 srdf_model->initString(*urdf_model_, SMODEL2);
112 static const std::string SMODEL1 =
"<?xml version=\"1.0\" ?>"
113 "<robot name=\"pr2\">"
114 "<virtual_joint name=\"base_joint\" child_link=\"base_footprint\" "
115 "parent_frame=\"base_footprint\" type=\"planar\"/>"
116 "<group name=\"left_arm_base_tip\">"
117 "<chain base_link=\"monkey_base\" tip_link=\"monkey_tip\"/>"
119 "<group name=\"left_arm_joints\">"
120 "<joint name=\"l_monkey_pan_joint\"/>"
121 "<joint name=\"l_monkey_fles_joint\"/>"
125 auto srdf_model = std::make_shared<srdf::Model>();
126 srdf_model->initString(*urdf_model_, SMODEL1);
130 ASSERT_TRUE(left_arm_base_tip_group ==
nullptr);
133 ASSERT_TRUE(left_arm_joints_group ==
nullptr);
135 static const std::string SMODEL2 =
"<?xml version=\"1.0\" ?>"
136 "<robot name=\"pr2\">"
137 "<virtual_joint name=\"base_joint\" child_link=\"base_footprint\" "
138 "parent_frame=\"base_footprint\" type=\"planar\"/>"
139 "<group name=\"left_arm_base_tip\">"
140 "<chain base_link=\"torso_lift_link\" tip_link=\"l_wrist_roll_link\"/>"
142 "<group name=\"left_arm_joints\">"
143 "<joint name=\"l_shoulder_pan_joint\"/>"
144 "<joint name=\"l_shoulder_lift_joint\"/>"
145 "<joint name=\"l_upper_arm_roll_joint\"/>"
146 "<joint name=\"l_elbow_flex_joint\"/>"
147 "<joint name=\"l_forearm_roll_joint\"/>"
148 "<joint name=\"l_wrist_flex_joint\"/>"
149 "<joint name=\"l_wrist_roll_joint\"/>"
152 srdf_model->initString(*urdf_model_, SMODEL2);
156 left_arm_base_tip_group = robot_model2->getJointModelGroup(
"left_arm_base_tip");
157 ASSERT_TRUE(left_arm_base_tip_group !=
nullptr);
159 left_arm_joints_group = robot_model2->getJointModelGroup(
"left_arm_joints");
160 ASSERT_TRUE(left_arm_joints_group !=
nullptr);
168 EXPECT_EQ(robot_model2->getVariableNames().size(), robot_model2->getVariableCount());
170 bool found_shoulder_pan_link =
false;
171 bool found_wrist_roll_link =
false;
174 if (link_model->getName() ==
"l_shoulder_pan_link")
177 found_shoulder_pan_link =
true;
179 if (link_model->getName() ==
"l_wrist_roll_link")
182 found_wrist_roll_link =
true;
184 EXPECT_TRUE(link_model->getName() !=
"torso_lift_link");
191 std::map<std::string, double> jv;
192 jv[
"base_joint/x"] = 0.433;
193 jv[
"base_joint/theta"] = -0.5;
224 EXPECT_TRUE(model->getLinkModel(
"r_gripper_palm_link")->getAssociatedFixedTransforms().size() > 1);
237 const auto identity = Eigen::Isometry3d::Identity();
238 std::vector<shapes::ShapeConstPtr>
shapes;
242 poses.push_back(identity);
243 std::set<std::string> touch_links;
245 trajectory_msgs::JointTrajectory empty_state;
247 ks.
attachBody(std::make_unique<moveit::core::AttachedBody>(
robot_model->getLinkModel(
"r_gripper_palm_link"),
"box",
248 identity,
shapes, poses, touch_links, empty_state));
250 std::vector<const moveit::core::AttachedBody*> attached_bodies_1;
252 ASSERT_EQ(attached_bodies_1.size(), 1u);
254 std::vector<const moveit::core::AttachedBody*> attached_bodies_2;
257 ASSERT_EQ(attached_bodies_2.size(), 1u);
260 attached_bodies_1.clear();
262 ASSERT_EQ(attached_bodies_1.size(), 0u);
265 attached_bodies_2.clear();
267 ASSERT_EQ(attached_bodies_2.size(), 0u);
277 std::vector<shapes::ShapeConstPtr>
shapes;
281 poses.push_back(Eigen::Isometry3d::Identity());
282 std::set<std::string> touch_links;
283 Eigen::Isometry3d pose_a = Eigen::Isometry3d::Identity();
284 Eigen::Isometry3d pose_b = Eigen::Isometry3d(Eigen::Translation3d(0, 0, 1));
286 subframes[
"frame1"] = Eigen::Isometry3d(Eigen::Translation3d(0, 0, 1));
288 trajectory_msgs::JointTrajectory empty_state;
289 ks.
attachBody(std::make_unique<moveit::core::AttachedBody>(
robot_model->getLinkModel(
"r_gripper_palm_link"),
"boxA",
290 pose_a,
shapes, poses, touch_links, empty_state,
292 ks.
attachBody(std::make_unique<moveit::core::AttachedBody>(
robot_model->getLinkModel(
"r_gripper_palm_link"),
"boxB",
293 pose_b,
shapes, poses, touch_links, empty_state,
304 Eigen::Isometry3d p2;
311 moveit_msgs::RobotState msg;
317 Eigen::Isometry3d pose_c = Eigen::Isometry3d(Eigen::Translation3d(0.1, 0.2, 0.3)) *
318 Eigen::AngleAxisd(0.1 *
M_TAU, Eigen::Vector3d::UnitX()) *
319 Eigen::AngleAxisd(0.2 *
M_TAU, Eigen::Vector3d::UnitY()) *
320 Eigen::AngleAxisd(0.4 *
M_TAU, Eigen::Vector3d::UnitZ());
321 Eigen::Quaterniond q(pose_c.linear());
322 moveit_msgs::AttachedCollisionObject new_aco = msg.attached_collision_objects[0];
323 new_aco.object.id =
"boxC";
324 new_aco.object.header.frame_id =
"r_shoulder_pan_link";
325 new_aco.object.pose.position.x = pose_c.translation()[0];
326 new_aco.object.pose.position.y = pose_c.translation()[1];
327 new_aco.object.pose.position.z = pose_c.translation()[2];
328 new_aco.object.pose.orientation.x = q.vec()[0];
329 new_aco.object.pose.orientation.y = q.vec()[1];
330 new_aco.object.pose.orientation.z = q.vec()[2];
331 new_aco.object.pose.orientation.w = q.w();
332 msg.attached_collision_objects.push_back(new_aco);
337 Eigen::Isometry3d p_original, p_reconverted;
343 Eigen::Isometry3d p_link, p_header_frame;
347 p = p_header_frame * pose_c;
351 p = p_link.inverse() * p_header_frame * pose_c;
356 int main(
int argc,
char** argv)
358 testing::InitGoogleTest(&argc, argv);
359 return RUN_ALL_TESTS();