45#include <urdf_parser/urdf_parser.h>
46#include <geometric_shapes/shape_operations.h>
48#include <gtest/gtest.h>
54template <
class CollisionAllocatorType>
58 std::shared_ptr<CollisionAllocatorType>
value_;
67 value_ = std::make_shared<CollisionAllocatorType>();
70 kinect_dae_resource_ =
"package://moveit_resources_pr2_description/urdf/meshes/sensors/kinect_v0/kinect.dae";
72 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(
robot_model_->getLinkModelNames(),
true);
85 collision_detection::CollisionEnvPtr
cenv_;
87 collision_detection::AllowedCollisionMatrixPtr
acm_;
93#define EXPECT_TIME_LT(EXPR, VAL) EXPECT_LT(EXPR, VAL)
95#define EXPECT_TIME_LT(EXPR, VAL) static_cast<void>(EXPR)
102 ASSERT_TRUE(this->robot_model_ok_);
113 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
130 Eigen::Isometry3d offset = Eigen::Isometry3d::Identity();
131 offset.translation().x() = .01;
139 this->acm_->setEntry(
"base_link",
"base_bellow_link",
false);
140 this->cenv_->checkSelfCollision(req, res1, robot_state, *this->acm_);
143 this->acm_->setEntry(
"base_link",
"base_bellow_link",
true);
144 this->cenv_->checkSelfCollision(req, res2, robot_state, *this->acm_);
154 this->acm_->setEntry(
"r_gripper_palm_link",
"l_gripper_palm_link",
false);
155 this->cenv_->checkSelfCollision(req, res3, robot_state, *this->acm_);
169 Eigen::Isometry3d offset = Eigen::Isometry3d::Identity();
170 offset.translation().x() = .01;
183 this->acm_->setEntry(
"base_link",
"base_bellow_link",
false);
184 this->acm_->setEntry(
"r_gripper_palm_link",
"l_gripper_palm_link",
false);
187 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
190 EXPECT_EQ(res.
contacts.begin()->second.size(), 1u);
196 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
199 EXPECT_EQ(res.
contacts.begin()->second.size(), 1u);
207 std::make_shared<collision_detection::AllowedCollisionMatrix>(this->robot_model_->getLinkModelNames(),
false);
208 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
210 EXPECT_LE(res.
contacts.size(), 10u);
224 Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
225 Eigen::Isometry3d pos2 = Eigen::Isometry3d::Identity();
227 pos1.translation().x() = 5.0;
228 pos2.translation().x() = 5.01;
236 this->acm_->setEntry(
"r_gripper_palm_link",
"l_gripper_palm_link",
false);
239 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
242 ASSERT_EQ(res.
contacts.begin()->second.size(), 1u);
244 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.
contacts.begin();
247 EXPECT_NEAR(it->second[0].pos.x(), 5.0, .33);
250 pos1 = Eigen::Isometry3d(Eigen::Translation3d(3.0, 0.0, 0.0) * Eigen::Quaterniond::Identity());
251 pos2 = Eigen::Isometry3d(Eigen::Translation3d(3.0, 0.0, 0.0) *
252 Eigen::Quaterniond(sqrt(1 - pow(0.258, 2)), 0.0, 0.258, 0.0));
260 this->cenv_->checkSelfCollision(req, res2, robot_state, *this->acm_);
262 ASSERT_EQ(res2.
contacts.size(), 1u);
263 ASSERT_EQ(res2.
contacts.begin()->second.size(), 1u);
265 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res2.
contacts.begin();
268 EXPECT_NEAR(it->second[0].pos.x(), 3.0, 0.33);
271 pos1 = Eigen::Isometry3d(Eigen::Translation3d(3.0, 0.0, 0.0) * Eigen::Quaterniond::Identity());
272 pos2 = Eigen::Isometry3d(Eigen::Translation3d(3.0, 0.0, 0.0) *
273 Eigen::Quaterniond(M_PI / 4.0, 0.0, M_PI / 4.0, 0.0).normalized());
281 this->cenv_->checkSelfCollision(req, res2, robot_state, *this->acm_);
291 std::make_shared<collision_detection::AllowedCollisionMatrix>(this->robot_model_->getLinkModelNames(),
true);
297 Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
298 pos1.translation().x() = 5.0;
303 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
306 shapes::Shape* shape =
new shapes::Box(.1, .1, .1);
307 this->cenv_->getWorld()->addToObject(
"box", pos1, shapes::ShapeConstPtr(shape), Eigen::Isometry3d::Identity());
310 this->cenv_->checkRobotCollision(req, res, robot_state, *this->acm_);
314 this->cenv_->getWorld()->removeObject(
"box");
316 shape =
new shapes::Box(.1, .1, .1);
317 std::vector<shapes::ShapeConstPtr>
shapes;
318 EigenSTL::vector_Isometry3d poses;
319 shapes.push_back(shapes::ShapeConstPtr(shape));
320 poses.push_back(Eigen::Isometry3d::Identity());
321 std::vector<std::string> touch_links;
322 robot_state.
attachBody(
"box", poses[0],
shapes, poses, touch_links,
"r_gripper_palm_link");
325 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
331 touch_links.push_back(
"r_gripper_palm_link");
332 touch_links.push_back(
"r_gripper_motor_accelerometer_link");
333 shapes[0] = std::make_shared<shapes::Box>(.1, .1, .1);
334 robot_state.
attachBody(
"box", poses[0],
shapes, poses, touch_links,
"r_gripper_palm_link");
338 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
341 pos1.translation().x() = 5.01;
342 shapes::Shape* coll =
new shapes::Box(.1, .1, .1);
343 this->cenv_->getWorld()->addToObject(
"coll", pos1, shapes::ShapeConstPtr(coll), Eigen::Isometry3d::Identity());
345 this->cenv_->checkRobotCollision(req, res, robot_state, *this->acm_);
348 this->acm_->setEntry(
"coll",
"r_gripper_palm_link",
true);
350 this->cenv_->checkRobotCollision(req, res, robot_state, *this->acm_);
363 collision_detection::CollisionEnvPtr new_cenv = this->value_->allocateEnv(this->cenv_, this->cenv_->getWorld());
365 auto before = std::chrono::system_clock::now();
366 new_cenv->checkSelfCollision(req, res, robot_state);
368 std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
369 before = std::chrono::system_clock::now();
370 new_cenv->checkSelfCollision(req, res, robot_state);
371 double second_check =
372 std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
376 std::vector<shapes::ShapeConstPtr>
shapes;
379 shapes[0].reset(shapes::createMeshFromResource(this->kinect_dae_resource_));
381 EigenSTL::vector_Isometry3d poses;
382 poses.push_back(Eigen::Isometry3d::Identity());
384 std::vector<std::string> touch_links;
385 robot_state.
attachBody(
"kinect", poses[0],
shapes, poses, touch_links,
"r_gripper_palm_link");
387 before = std::chrono::system_clock::now();
388 new_cenv->checkSelfCollision(req, res, robot_state);
389 first_check = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
390 before = std::chrono::system_clock::now();
391 new_cenv->checkSelfCollision(req, res, robot_state);
392 second_check = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
397 collision_detection::CollisionEnvPtr other_new_cenv = this->value_->allocateEnv(this->cenv_, this->cenv_->getWorld());
398 before = std::chrono::system_clock::now();
399 new_cenv->checkSelfCollision(req, res, robot_state);
400 first_check = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
401 before = std::chrono::system_clock::now();
402 new_cenv->checkSelfCollision(req, res, robot_state);
403 second_check = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
413 shapes::ShapeConstPtr shape(shapes::createMeshFromResource(this->kinect_dae_resource_));
414 Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
415 Eigen::Isometry3d pos2 = Eigen::Isometry3d::Identity();
416 pos2.translation().x() = 10.0;
418 this->cenv_->getWorld()->addToObject(
"kinect", pos1, shape, Eigen::Isometry3d::Identity());
424 auto before = std::chrono::system_clock::now();
425 this->cenv_->checkRobotCollision(req, res, robot_state);
427 std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
428 before = std::chrono::system_clock::now();
429 this->cenv_->checkRobotCollision(req, res, robot_state);
430 double second_check =
431 std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
436 this->cenv_->getWorld()->removeObject(
"kinect");
445 std::vector<std::string> touch_links;
446 Eigen::Isometry3d identity_transform{ Eigen::Isometry3d::Identity() };
447 robot_state1.
attachBody(
"kinect", identity_transform, object->shapes_, object->shape_poses_, touch_links,
448 "r_gripper_palm_link");
450 EigenSTL::vector_Isometry3d other_poses;
451 other_poses.push_back(pos2);
454 robot_state2.
attachBody(
"kinect", identity_transform, object->shapes_, object->shape_poses_, touch_links,
455 "r_gripper_palm_link");
459 this->cenv_->checkSelfCollision(req, res, robot_state1);
463 before = std::chrono::system_clock::now();
464 this->cenv_->checkSelfCollision(req, res, robot_state1, *this->acm_);
465 first_check = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
466 before = std::chrono::system_clock::now();
469 this->cenv_->checkSelfCollision(req, res, robot_state2, *this->acm_);
470 second_check = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
478 EigenSTL::vector_Isometry3d poses;
479 std::vector<shapes::ShapeConstPtr>
shapes;
480 for (
unsigned int i = 0; i < 10000; ++i)
482 poses.push_back(Eigen::Isometry3d::Identity());
483 shapes.push_back(std::make_shared<shapes::Box>(.01, .01, .01));
485 auto start = std::chrono::system_clock::now();
486 this->cenv_->getWorld()->addToObject(
"map",
shapes, poses);
487 double t = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - start).count();
492 RCLCPP_INFO(rclcpp::get_logger(
"moveit.core.collision_detection.bullet"),
"Adding boxes took %g", t);
501 Eigen::Isometry3d kinect_pose;
502 kinect_pose.setIdentity();
503 shapes::ShapePtr kinect_shape;
504 kinect_shape.reset(shapes::createMeshFromResource(this->kinect_dae_resource_));
506 this->cenv_->getWorld()->addToObject(
"kinect", kinect_shape, kinect_pose);
508 Eigen::Isometry3d np;
509 for (
unsigned int i = 0; i < 5; ++i)
511 np = Eigen::Translation3d(i * .001, i * .001, i * .001) * Eigen::Quaterniond::Identity();
512 this->cenv_->getWorld()->moveShapeInObject(
"kinect", kinect_shape, np);
515 this->cenv_->checkCollision(req, res, robot_state1, *this->acm_);
530 EigenSTL::vector_Isometry3d poses;
531 std::vector<shapes::ShapeConstPtr>
shapes;
532 for (
unsigned int i = 0; i < 5; ++i)
534 this->cenv_->getWorld()->removeObject(
"shape");
537 shapes.push_back(std::make_shared<const shapes::Box>(1 + i * .0001, 1 + i * .0001, 1 + i * .0001));
538 poses.push_back(Eigen::Isometry3d::Identity());
539 this->cenv_->getWorld()->addToObject(
"shape",
shapes, poses);
542 this->cenv_->checkCollision(req, res, robot_state1, *this->acm_);
546 Eigen::Isometry3d kinect_pose = Eigen::Isometry3d::Identity();
547 shapes::ShapePtr kinect_shape;
548 kinect_shape.reset(shapes::createMeshFromResource(this->kinect_dae_resource_));
549 this->cenv_->getWorld()->addToObject(
"kinect", kinect_shape, kinect_pose);
552 this->cenv_->checkCollision(req2, res2, robot_state1, *this->acm_);
554 for (
unsigned int i = 0; i < 5; ++i)
556 this->cenv_->getWorld()->removeObject(
"shape");
559 shapes.push_back(std::make_shared<shapes::Box>(1 + i * .0001, 1 + i * .0001, 1 + i * .0001));
560 poses.push_back(Eigen::Isometry3d::Identity());
561 this->cenv_->getWorld()->addToObject(
"shape",
shapes, poses);
564 this->cenv_->checkCollision(req, res, robot_state1, *this->acm_);
570 ContactPositions, AttachedBodyTester, DiffSceneTester, ConvertObjectToAttached,
571 TestCollisionMapAdditionSpeed, MoveMesh, TestChangingShapeSize);
collision_detection::CollisionEnvPtr cenv_
moveit::core::RobotModelPtr robot_model_
std::shared_ptr< CollisionAllocatorType > value_
std::string kinect_dae_resource_
collision_detection::AllowedCollisionMatrixPtr acm_
World::ObjectConstPtr ObjectConstPtr
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void attachBody(std::unique_ptr< AttachedBody > attached_body)
Add an attached body to this state.
void updateStateWithLinkAt(const std::string &link_name, const Eigen::Isometry3d &transform, bool backward=false)
Update the state after setting a particular link to the input global transform pose.
bool clearAttachedBody(const std::string &id)
Remove the attached body named id. Return false if the object was not found (and thus not removed)....
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &package_name, const std::string &urdf_relative_path, const std::string &srdf_relative_path)
Loads a robot model given a URDF and SRDF file in a package.
Representation of a collision checking request.
bool verbose
Flag indicating whether information about detected collisions should be reported.
bool contacts
If true, compute contacts. Otherwise only a binary collision yes/no is reported.
std::size_t max_contacts
Overall maximum number of contacts to compute.
std::size_t max_contacts_per_pair
Maximum number of contacts to compute per pair of bodies (multiple bodies may be in contact at differ...
Representation of a collision checking result.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
bool collision
True if collision was found, false otherwise.
std::size_t contact_count
Number of contacts returned.
TYPED_TEST_P(CollisionDetectorTest, InitOK)
TYPED_TEST_CASE_P(CollisionDetectorTest)
REGISTER_TYPED_TEST_SUITE_P(CollisionDetectorTest, InitOK, DefaultNotInCollision, LinksInCollision, ContactReporting, ContactPositions, AttachedBodyTester, DiffSceneTester, ConvertObjectToAttached, TestCollisionMapAdditionSpeed, MoveMesh, TestChangingShapeSize)
#define EXPECT_TIME_LT(EXPR, VAL)