43 #include <urdf_parser/urdf_parser.h>
46 #include <gtest/gtest.h>
52 template <
class CollisionAllocatorType>
56 std::shared_ptr<CollisionAllocatorType>
value_;
65 value_ = std::make_shared<CollisionAllocatorType>();
68 kinect_dae_resource_ =
"package://moveit_resources_pr2_description/urdf/meshes/sensors/kinect_v0/kinect.dae";
70 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(
robot_model_->getLinkModelNames(),
true);
83 collision_detection::CollisionEnvPtr
cenv_;
85 collision_detection::AllowedCollisionMatrixPtr
acm_;
91 #define EXPECT_TIME_LT(EXPR, VAL) EXPECT_LT(EXPR, VAL)
92 #else // Don't perform timing checks in Debug mode (but evaluate expression)
93 #define EXPECT_TIME_LT(EXPR, VAL) (void)(EXPR)
100 ASSERT_TRUE(this->robot_model_ok_);
111 this->cenv_->checkSelfCollision(req, res,
robot_state, *this->acm_);
128 Eigen::Isometry3d offset = Eigen::Isometry3d::Identity();
129 offset.translation().x() = .01;
133 robot_state.updateStateWithLinkAt(
"base_link", Eigen::Isometry3d::Identity());
134 robot_state.updateStateWithLinkAt(
"base_bellow_link", offset);
137 this->acm_->setEntry(
"base_link",
"base_bellow_link",
false);
138 this->cenv_->checkSelfCollision(req, res1,
robot_state, *this->acm_);
141 this->acm_->setEntry(
"base_link",
"base_bellow_link",
true);
142 this->cenv_->checkSelfCollision(req, res2,
robot_state, *this->acm_);
148 robot_state.updateStateWithLinkAt(
"r_gripper_palm_link", Eigen::Isometry3d::Identity());
149 robot_state.updateStateWithLinkAt(
"l_gripper_palm_link", offset);
152 this->acm_->setEntry(
"r_gripper_palm_link",
"l_gripper_palm_link",
false);
153 this->cenv_->checkSelfCollision(req, res3,
robot_state, *this->acm_);
167 Eigen::Isometry3d offset = Eigen::Isometry3d::Identity();
168 offset.translation().x() = .01;
175 robot_state.updateStateWithLinkAt(
"base_link", Eigen::Isometry3d::Identity());
176 robot_state.updateStateWithLinkAt(
"base_bellow_link", offset);
177 robot_state.updateStateWithLinkAt(
"r_gripper_palm_link", Eigen::Isometry3d::Identity());
178 robot_state.updateStateWithLinkAt(
"l_gripper_palm_link", offset);
181 this->acm_->setEntry(
"base_link",
"base_bellow_link",
false);
182 this->acm_->setEntry(
"r_gripper_palm_link",
"l_gripper_palm_link",
false);
185 this->cenv_->checkSelfCollision(req, res,
robot_state, *this->acm_);
194 this->cenv_->checkSelfCollision(req, res,
robot_state, *this->acm_);
205 std::make_shared<collision_detection::AllowedCollisionMatrix>(this->robot_model_->getLinkModelNames(),
false);
206 this->cenv_->checkSelfCollision(req, res,
robot_state, *this->acm_);
208 EXPECT_LE(res.
contacts.size(), 10u);
222 Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
223 Eigen::Isometry3d pos2 = Eigen::Isometry3d::Identity();
225 pos1.translation().x() = 5.0;
226 pos2.translation().x() = 5.01;
230 robot_state.updateStateWithLinkAt(
"r_gripper_palm_link", pos1);
231 robot_state.updateStateWithLinkAt(
"l_gripper_palm_link", pos2);
234 this->acm_->setEntry(
"r_gripper_palm_link",
"l_gripper_palm_link",
false);
237 this->cenv_->checkSelfCollision(req, res,
robot_state, *this->acm_);
240 ASSERT_EQ(res.
contacts.begin()->second.size(), 1u);
242 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.
contacts.begin();
248 pos1 = Eigen::Isometry3d(Eigen::Translation3d(3.0, 0.0, 0.0) * Eigen::Quaterniond::Identity());
249 pos2 = Eigen::Isometry3d(Eigen::Translation3d(3.0, 0.0, 0.0) *
250 Eigen::Quaterniond(sqrt(1 - pow(0.258, 2)), 0.0, 0.258, 0.0));
253 robot_state.updateStateWithLinkAt(
"r_gripper_palm_link", pos1);
254 robot_state.updateStateWithLinkAt(
"l_gripper_palm_link", pos2);
258 this->cenv_->checkSelfCollision(req, res2,
robot_state, *this->acm_);
260 ASSERT_EQ(res2.
contacts.size(), 1u);
261 ASSERT_EQ(res2.
contacts.begin()->second.size(), 1u);
263 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res2.
contacts.begin();
269 pos1 = Eigen::Isometry3d(Eigen::Translation3d(3.0, 0.0, 0.0) * Eigen::Quaterniond::Identity());
270 pos2 = Eigen::Isometry3d(Eigen::Translation3d(3.0, 0.0, 0.0) *
271 Eigen::Quaterniond(
M_PI / 4.0, 0.0,
M_PI / 4.0, 0.0).normalized());
274 robot_state.updateStateWithLinkAt(
"r_gripper_palm_link", pos1);
275 robot_state.updateStateWithLinkAt(
"l_gripper_palm_link", pos2);
279 this->cenv_->checkSelfCollision(req, res2,
robot_state, *this->acm_);
289 std::make_shared<collision_detection::AllowedCollisionMatrix>(this->robot_model_->getLinkModelNames(),
true);
295 Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
296 pos1.translation().x() = 5.0;
299 robot_state.updateStateWithLinkAt(
"r_gripper_palm_link", pos1);
301 this->cenv_->checkSelfCollision(req, res,
robot_state, *this->acm_);
305 this->cenv_->getWorld()->addToObject(
"box", pos1,
shapes::ShapeConstPtr(shape), Eigen::Isometry3d::Identity());
308 this->cenv_->checkRobotCollision(req, res,
robot_state, *this->acm_);
312 this->cenv_->getWorld()->removeObject(
"box");
315 std::vector<shapes::ShapeConstPtr>
shapes;
318 poses.push_back(Eigen::Isometry3d::Identity());
319 std::vector<std::string> touch_links;
320 robot_state.attachBody(
"box", poses[0],
shapes, poses, touch_links,
"r_gripper_palm_link");
323 this->cenv_->checkSelfCollision(req, res,
robot_state, *this->acm_);
329 touch_links.push_back(
"r_gripper_palm_link");
330 touch_links.push_back(
"r_gripper_motor_accelerometer_link");
331 shapes[0] = std::make_shared<shapes::Box>(.1, .1, .1);
332 robot_state.attachBody(
"box", poses[0],
shapes, poses, touch_links,
"r_gripper_palm_link");
336 this->cenv_->checkSelfCollision(req, res,
robot_state, *this->acm_);
339 pos1.translation().x() = 5.01;
341 this->cenv_->getWorld()->addToObject(
"coll", pos1,
shapes::ShapeConstPtr(coll), Eigen::Isometry3d::Identity());
343 this->cenv_->checkRobotCollision(req, res,
robot_state, *this->acm_);
346 this->acm_->setEntry(
"coll",
"r_gripper_palm_link",
true);
348 this->cenv_->checkRobotCollision(req, res,
robot_state, *this->acm_);
361 collision_detection::CollisionEnvPtr new_cenv = this->value_->allocateEnv(this->cenv_, this->cenv_->getWorld());
364 new_cenv->checkSelfCollision(req, res,
robot_state);
367 new_cenv->checkSelfCollision(req, res,
robot_state);
372 std::vector<shapes::ShapeConstPtr>
shapes;
378 poses.push_back(Eigen::Isometry3d::Identity());
380 std::vector<std::string> touch_links;
381 robot_state.attachBody(
"kinect", poses[0],
shapes, poses, touch_links,
"r_gripper_palm_link");
384 new_cenv->checkSelfCollision(req, res,
robot_state);
387 new_cenv->checkSelfCollision(req, res,
robot_state);
393 collision_detection::CollisionEnvPtr other_new_cenv = this->value_->allocateEnv(this->cenv_, this->cenv_->getWorld());
395 new_cenv->checkSelfCollision(req, res,
robot_state);
398 new_cenv->checkSelfCollision(req, res,
robot_state);
410 Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
411 Eigen::Isometry3d pos2 = Eigen::Isometry3d::Identity();
412 pos2.translation().x() = 10.0;
414 this->cenv_->getWorld()->addToObject(
"kinect", pos1, shape, Eigen::Isometry3d::Identity());
421 this->cenv_->checkRobotCollision(req, res,
robot_state);
424 this->cenv_->checkRobotCollision(req, res,
robot_state);
430 this->cenv_->getWorld()->removeObject(
"kinect");
439 std::vector<std::string> touch_links;
440 Eigen::Isometry3d identity_transform{ Eigen::Isometry3d::Identity() };
441 robot_state1.
attachBody(
"kinect", identity_transform, object->shapes_, object->shape_poses_, touch_links,
442 "r_gripper_palm_link");
445 other_poses.push_back(pos2);
448 robot_state2.
attachBody(
"kinect", identity_transform, object->shapes_, object->shape_poses_, touch_links,
449 "r_gripper_palm_link");
453 this->cenv_->checkSelfCollision(req, res, robot_state1);
458 this->cenv_->checkSelfCollision(req, res, robot_state1, *this->acm_);
463 this->cenv_->checkSelfCollision(req, res, robot_state2, *this->acm_);
473 std::vector<shapes::ShapeConstPtr>
shapes;
474 for (
unsigned int i = 0; i < 10000; i++)
476 poses.push_back(Eigen::Isometry3d::Identity());
480 this->cenv_->getWorld()->addToObject(
"map",
shapes, poses);
486 ROS_INFO_NAMED(
"collision_detection.bullet",
"Adding boxes took %g",
t);
495 Eigen::Isometry3d kinect_pose;
496 kinect_pose.setIdentity();
500 this->cenv_->getWorld()->addToObject(
"kinect", kinect_shape, kinect_pose);
502 Eigen::Isometry3d np;
503 for (
unsigned int i = 0; i < 5; i++)
505 np = Eigen::Translation3d(i * .001, i * .001, i * .001) * Eigen::Quaterniond::Identity();
506 this->cenv_->getWorld()->moveShapeInObject(
"kinect", kinect_shape, np);
509 this->cenv_->checkCollision(req, res, robot_state1, *this->acm_);
525 std::vector<shapes::ShapeConstPtr>
shapes;
526 for (
unsigned int i = 0; i < 5; i++)
528 this->cenv_->getWorld()->removeObject(
"shape");
532 poses.push_back(Eigen::Isometry3d::Identity());
533 this->cenv_->getWorld()->addToObject(
"shape",
shapes, poses);
536 this->cenv_->checkCollision(req, res, robot_state1, *this->acm_);
540 Eigen::Isometry3d kinect_pose = Eigen::Isometry3d::Identity();
543 this->cenv_->getWorld()->addToObject(
"kinect", kinect_shape, kinect_pose);
546 this->cenv_->checkCollision(req2, res2, robot_state1, *this->acm_);
548 for (
unsigned int i = 0; i < 5; i++)
550 this->cenv_->getWorld()->removeObject(
"shape");
554 poses.push_back(Eigen::Isometry3d::Identity());
555 this->cenv_->getWorld()->addToObject(
"shape",
shapes, poses);
558 this->cenv_->checkCollision(req, res, robot_state1, *this->acm_);
564 ContactPositions, AttachedBodyTester, DiffSceneTester, ConvertObjectToAttached,
565 TestCollisionMapAdditionSpeed, MoveMesh, TestChangingShapeSize);