43#include <urdf_parser/urdf_parser.h>
44#include <geometric_shapes/shape_operations.h>
46#include <gtest/gtest.h>
52template <
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)
93#define EXPECT_TIME_LT(EXPR, VAL) static_cast<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;
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_);
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;
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_);
188 EXPECT_EQ(res.
contacts.begin()->second.size(), 1u);
194 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
197 EXPECT_EQ(res.
contacts.begin()->second.size(), 1u);
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;
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();
245 EXPECT_NEAR(it->second[0].pos.x(), 5.0, .33);
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));
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();
266 EXPECT_NEAR(it->second[0].pos.x(), 3.0, 0.33);
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());
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;
301 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
304 shapes::Shape* shape =
new shapes::Box(.1, .1, .1);
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");
314 shape =
new shapes::Box(.1, .1, .1);
315 std::vector<shapes::ShapeConstPtr>
shapes;
316 EigenSTL::vector_Isometry3d poses;
317 shapes.push_back(shapes::ShapeConstPtr(shape));
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;
340 shapes::Shape* coll =
new shapes::Box(.1, .1, .1);
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());
363 auto before = std::chrono::system_clock::now();
364 new_cenv->checkSelfCollision(req, res, robot_state);
366 std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
367 before = std::chrono::system_clock::now();
368 new_cenv->checkSelfCollision(req, res, robot_state);
369 double second_check =
370 std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
374 std::vector<shapes::ShapeConstPtr>
shapes;
377 shapes[0].reset(shapes::createMeshFromResource(this->kinect_dae_resource_));
379 EigenSTL::vector_Isometry3d poses;
380 poses.push_back(Eigen::Isometry3d::Identity());
382 std::vector<std::string> touch_links;
383 robot_state.
attachBody(
"kinect", poses[0],
shapes, poses, touch_links,
"r_gripper_palm_link");
385 before = std::chrono::system_clock::now();
386 new_cenv->checkSelfCollision(req, res, robot_state);
387 first_check = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
388 before = std::chrono::system_clock::now();
389 new_cenv->checkSelfCollision(req, res, robot_state);
390 second_check = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
395 collision_detection::CollisionEnvPtr other_new_cenv = this->value_->allocateEnv(this->cenv_, this->cenv_->getWorld());
396 before = std::chrono::system_clock::now();
397 new_cenv->checkSelfCollision(req, res, robot_state);
398 first_check = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
399 before = std::chrono::system_clock::now();
400 new_cenv->checkSelfCollision(req, res, robot_state);
401 second_check = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
411 shapes::ShapeConstPtr shape(shapes::createMeshFromResource(this->kinect_dae_resource_));
412 Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
413 Eigen::Isometry3d pos2 = Eigen::Isometry3d::Identity();
414 pos2.translation().x() = 10.0;
416 this->cenv_->getWorld()->addToObject(
"kinect", pos1, shape, Eigen::Isometry3d::Identity());
422 auto before = std::chrono::system_clock::now();
423 this->cenv_->checkRobotCollision(req, res, robot_state);
425 std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
426 before = std::chrono::system_clock::now();
427 this->cenv_->checkRobotCollision(req, res, robot_state);
428 double second_check =
429 std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
434 this->cenv_->getWorld()->removeObject(
"kinect");
443 std::vector<std::string> touch_links;
444 Eigen::Isometry3d identity_transform{ Eigen::Isometry3d::Identity() };
445 robot_state1.
attachBody(
"kinect", identity_transform, object->shapes_, object->shape_poses_, touch_links,
446 "r_gripper_palm_link");
448 EigenSTL::vector_Isometry3d other_poses;
449 other_poses.push_back(pos2);
452 robot_state2.
attachBody(
"kinect", identity_transform, object->shapes_, object->shape_poses_, touch_links,
453 "r_gripper_palm_link");
457 this->cenv_->checkSelfCollision(req, res, robot_state1);
461 before = std::chrono::system_clock::now();
462 this->cenv_->checkSelfCollision(req, res, robot_state1, *this->acm_);
463 first_check = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
464 before = std::chrono::system_clock::now();
467 this->cenv_->checkSelfCollision(req, res, robot_state2, *this->acm_);
468 second_check = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - before).count();
476 EigenSTL::vector_Isometry3d poses;
477 std::vector<shapes::ShapeConstPtr>
shapes;
478 for (
unsigned int i = 0; i < 10000; ++i)
480 poses.push_back(Eigen::Isometry3d::Identity());
481 shapes.push_back(std::make_shared<shapes::Box>(.01, .01, .01));
483 auto start = std::chrono::system_clock::now();
484 this->cenv_->getWorld()->addToObject(
"map",
shapes, poses);
485 double t = std::chrono::duration_cast<std::chrono::seconds>(std::chrono::system_clock::now() - start).count();
490 RCLCPP_INFO(rclcpp::get_logger(
"moveit.core.collision_detection.bullet"),
"Adding boxes took %g", t);
499 Eigen::Isometry3d kinect_pose;
500 kinect_pose.setIdentity();
501 shapes::ShapePtr kinect_shape;
502 kinect_shape.reset(shapes::createMeshFromResource(this->kinect_dae_resource_));
504 this->cenv_->getWorld()->addToObject(
"kinect", kinect_shape, kinect_pose);
506 Eigen::Isometry3d np;
507 for (
unsigned int i = 0; i < 5; ++i)
509 np = Eigen::Translation3d(i * .001, i * .001, i * .001) * Eigen::Quaterniond::Identity();
510 this->cenv_->getWorld()->moveShapeInObject(
"kinect", kinect_shape, np);
513 this->cenv_->checkCollision(req, res, robot_state1, *this->acm_);
528 EigenSTL::vector_Isometry3d poses;
529 std::vector<shapes::ShapeConstPtr>
shapes;
530 for (
unsigned int i = 0; i < 5; ++i)
532 this->cenv_->getWorld()->removeObject(
"shape");
535 shapes.push_back(std::make_shared<const shapes::Box>(1 + i * .0001, 1 + i * .0001, 1 + i * .0001));
536 poses.push_back(Eigen::Isometry3d::Identity());
537 this->cenv_->getWorld()->addToObject(
"shape",
shapes, poses);
540 this->cenv_->checkCollision(req, res, robot_state1, *this->acm_);
544 Eigen::Isometry3d kinect_pose = Eigen::Isometry3d::Identity();
545 shapes::ShapePtr kinect_shape;
546 kinect_shape.reset(shapes::createMeshFromResource(this->kinect_dae_resource_));
547 this->cenv_->getWorld()->addToObject(
"kinect", kinect_shape, kinect_pose);
550 this->cenv_->checkCollision(req2, res2, robot_state1, *this->acm_);
552 for (
unsigned int i = 0; i < 5; ++i)
554 this->cenv_->getWorld()->removeObject(
"shape");
557 shapes.push_back(std::make_shared<shapes::Box>(1 + i * .0001, 1 + i * .0001, 1 + i * .0001));
558 poses.push_back(Eigen::Isometry3d::Identity());
559 this->cenv_->getWorld()->addToObject(
"shape",
shapes, poses);
562 this->cenv_->checkCollision(req, res, robot_state1, *this->acm_);
568 ContactPositions, AttachedBodyTester, DiffSceneTester, ConvertObjectToAttached,
569 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)