moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
test_collision_common_pr2.hpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34
35/* Author: E. Gil Jones */
36
37#pragma once
38
45#include <urdf_parser/urdf_parser.h>
46#include <geometric_shapes/shape_operations.h>
47
48#include <gtest/gtest.h>
49#include <sstream>
50#include <algorithm>
51#include <ctype.h>
52#include <fstream>
53
54template <class CollisionAllocatorType>
55class CollisionDetectorTest : public ::testing::Test
56{
57public:
58 std::shared_ptr<CollisionAllocatorType> value_;
59
60protected:
64
65 void SetUp() override
66 {
67 value_ = std::make_shared<CollisionAllocatorType>();
69 robot_model_ok_ = static_cast<bool>(robot_model_);
70 kinect_dae_resource_ = "package://moveit_resources_pr2_description/urdf/meshes/sensors/kinect_v0/kinect.dae";
71
72 acm_ = std::make_shared<collision_detection::AllowedCollisionMatrix>(robot_model_->getLinkModelNames(), true);
73
74 cenv_ = value_->allocateEnv(robot_model_);
75 }
76
77 void TearDown() override
78 {
79 }
80
82
83 moveit::core::RobotModelPtr robot_model_;
84
85 collision_detection::CollisionEnvPtr cenv_;
86
87 collision_detection::AllowedCollisionMatrixPtr acm_;
88
90};
91
92#ifdef NDEBUG
93#define EXPECT_TIME_LT(EXPR, VAL) EXPECT_LT(EXPR, VAL)
94#else // Don't perform timing checks in Debug mode (but evaluate expression)
95#define EXPECT_TIME_LT(EXPR, VAL) static_cast<void>(EXPR)
96#endif
97
99
101{
102 ASSERT_TRUE(this->robot_model_ok_);
103}
104
105TYPED_TEST_P(CollisionDetectorTest, DefaultNotInCollision)
106{
107 moveit::core::RobotState robot_state(this->robot_model_);
108 robot_state.setToDefaultValues();
109 robot_state.update();
110
113 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
114 ASSERT_FALSE(res.collision);
115}
116
118{
123 // req.contacts = true;
124 // req.max_contacts = 100;
125
126 moveit::core::RobotState robot_state(this->robot_model_);
127 robot_state.setToDefaultValues();
128 robot_state.update();
129
130 Eigen::Isometry3d offset = Eigen::Isometry3d::Identity();
131 offset.translation().x() = .01;
132
133 // robot_state.getLinkState("base_link")->updateGivenGlobalLinkTransform(Eigen::Isometry3d::Identity());
134 // robot_state.getLinkState("base_bellow_link")->updateGivenGlobalLinkTransform(offset);
135 robot_state.updateStateWithLinkAt("base_link", Eigen::Isometry3d::Identity());
136 robot_state.updateStateWithLinkAt("base_bellow_link", offset);
137 robot_state.update();
138
139 this->acm_->setEntry("base_link", "base_bellow_link", false);
140 this->cenv_->checkSelfCollision(req, res1, robot_state, *this->acm_);
141 ASSERT_TRUE(res1.collision);
142
143 this->acm_->setEntry("base_link", "base_bellow_link", true);
144 this->cenv_->checkSelfCollision(req, res2, robot_state, *this->acm_);
145 ASSERT_FALSE(res2.collision);
146
147 // req.verbose = true;
148 // robot_state.getLinkState("r_gripper_palm_link")->updateGivenGlobalLinkTransform(Eigen::Isometry3d::Identity());
149 // robot_state.getLinkState("l_gripper_palm_link")->updateGivenGlobalLinkTransform(offset);
150 robot_state.updateStateWithLinkAt("r_gripper_palm_link", Eigen::Isometry3d::Identity());
151 robot_state.updateStateWithLinkAt("l_gripper_palm_link", offset);
152 robot_state.update();
153
154 this->acm_->setEntry("r_gripper_palm_link", "l_gripper_palm_link", false);
155 this->cenv_->checkSelfCollision(req, res3, robot_state, *this->acm_);
156 ASSERT_TRUE(res3.collision);
157}
158
160{
162 req.contacts = true;
163 req.max_contacts = 1;
164
165 moveit::core::RobotState robot_state(this->robot_model_);
166 robot_state.setToDefaultValues();
167 robot_state.update();
168
169 Eigen::Isometry3d offset = Eigen::Isometry3d::Identity();
170 offset.translation().x() = .01;
171
172 // robot_state.getLinkState("base_link")->updateGivenGlobalLinkTransform(Eigen::Isometry3d::Identity());
173 // robot_state.getLinkState("base_bellow_link")->updateGivenGlobalLinkTransform(offset);
174 // robot_state.getLinkState("r_gripper_palm_link")->updateGivenGlobalLinkTransform(Eigen::Isometry3d::Identity());
175 // robot_state.getLinkState("l_gripper_palm_link")->updateGivenGlobalLinkTransform(offset);
176
177 robot_state.updateStateWithLinkAt("base_link", Eigen::Isometry3d::Identity());
178 robot_state.updateStateWithLinkAt("base_bellow_link", offset);
179 robot_state.updateStateWithLinkAt("r_gripper_palm_link", Eigen::Isometry3d::Identity());
180 robot_state.updateStateWithLinkAt("l_gripper_palm_link", offset);
181 robot_state.update();
182
183 this->acm_->setEntry("base_link", "base_bellow_link", false);
184 this->acm_->setEntry("r_gripper_palm_link", "l_gripper_palm_link", false);
185
187 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
188 ASSERT_TRUE(res.collision);
189 EXPECT_EQ(res.contacts.size(), 1u);
190 EXPECT_EQ(res.contacts.begin()->second.size(), 1u);
191
192 res.clear();
193 req.max_contacts = 2;
194 req.max_contacts_per_pair = 1;
195 // req.verbose = true;
196 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
197 ASSERT_TRUE(res.collision);
198 EXPECT_EQ(res.contacts.size(), 2u);
199 EXPECT_EQ(res.contacts.begin()->second.size(), 1u);
200
201 res.contacts.clear();
202 res.contact_count = 0;
203
204 req.max_contacts = 10;
205 req.max_contacts_per_pair = 2;
206 this->acm_ =
207 std::make_shared<collision_detection::AllowedCollisionMatrix>(this->robot_model_->getLinkModelNames(), false);
208 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
209 ASSERT_TRUE(res.collision);
210 EXPECT_LE(res.contacts.size(), 10u);
211 EXPECT_LE(res.contact_count, 10u);
212}
213
215{
217 req.contacts = true;
218 req.max_contacts = 1;
219
220 moveit::core::RobotState robot_state(this->robot_model_);
221 robot_state.setToDefaultValues();
222 robot_state.update();
223
224 Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
225 Eigen::Isometry3d pos2 = Eigen::Isometry3d::Identity();
226
227 pos1.translation().x() = 5.0;
228 pos2.translation().x() = 5.01;
229
230 // robot_state.getLinkState("r_gripper_palm_link")->updateGivenGlobalLinkTransform(pos1);
231 // robot_state.getLinkState("l_gripper_palm_link")->updateGivenGlobalLinkTransform(pos2);
232 robot_state.updateStateWithLinkAt("r_gripper_palm_link", pos1);
233 robot_state.updateStateWithLinkAt("l_gripper_palm_link", pos2);
234 robot_state.update();
235
236 this->acm_->setEntry("r_gripper_palm_link", "l_gripper_palm_link", false);
237
239 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
240 ASSERT_TRUE(res.collision);
241 ASSERT_EQ(res.contacts.size(), 1u);
242 ASSERT_EQ(res.contacts.begin()->second.size(), 1u);
243
244 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res.contacts.begin();
245 it != res.contacts.end(); ++it)
246 {
247 EXPECT_NEAR(it->second[0].pos.x(), 5.0, .33);
248 }
249
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));
253 // robot_state.getLinkState("r_gripper_palm_link")->updateGivenGlobalLinkTransform(pos1);
254 // robot_state.getLinkState("l_gripper_palm_link")->updateGivenGlobalLinkTransform(pos2);
255 robot_state.updateStateWithLinkAt("r_gripper_palm_link", pos1);
256 robot_state.updateStateWithLinkAt("l_gripper_palm_link", pos2);
257 robot_state.update();
258
260 this->cenv_->checkSelfCollision(req, res2, robot_state, *this->acm_);
261 ASSERT_TRUE(res2.collision);
262 ASSERT_EQ(res2.contacts.size(), 1u);
263 ASSERT_EQ(res2.contacts.begin()->second.size(), 1u);
264
265 for (collision_detection::CollisionResult::ContactMap::const_iterator it = res2.contacts.begin();
266 it != res2.contacts.end(); ++it)
267 {
268 EXPECT_NEAR(it->second[0].pos.x(), 3.0, 0.33);
269 }
270
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());
274 // robot_state.getLinkState("r_gripper_palm_link")->updateGivenGlobalLinkTransform(pos1);
275 // robot_state.getLinkState("l_gripper_palm_link")->updateGivenGlobalLinkTransform(pos2);
276 robot_state.updateStateWithLinkAt("r_gripper_palm_link", pos1);
277 robot_state.updateStateWithLinkAt("l_gripper_palm_link", pos2);
278 robot_state.update();
279
281 this->cenv_->checkSelfCollision(req, res2, robot_state, *this->acm_);
282 ASSERT_FALSE(res3.collision);
283}
284
286{
289
290 this->acm_ =
291 std::make_shared<collision_detection::AllowedCollisionMatrix>(this->robot_model_->getLinkModelNames(), true);
292
293 moveit::core::RobotState robot_state(this->robot_model_);
294 robot_state.setToDefaultValues();
295 robot_state.update();
296
297 Eigen::Isometry3d pos1 = Eigen::Isometry3d::Identity();
298 pos1.translation().x() = 5.0;
299
300 // robot_state.getLinkState("r_gripper_palm_link")->updateGivenGlobalLinkTransform(pos1);
301 robot_state.updateStateWithLinkAt("r_gripper_palm_link", pos1);
302 robot_state.update();
303 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
304 ASSERT_FALSE(res.collision);
305
306 shapes::Shape* shape = new shapes::Box(.1, .1, .1);
307 this->cenv_->getWorld()->addToObject("box", pos1, shapes::ShapeConstPtr(shape), Eigen::Isometry3d::Identity());
308
310 this->cenv_->checkRobotCollision(req, res, robot_state, *this->acm_);
311 ASSERT_TRUE(res.collision);
312
313 // deletes shape
314 this->cenv_->getWorld()->removeObject("box");
315
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");
323
325 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
326 ASSERT_TRUE(res.collision);
327
328 // deletes shape
329 robot_state.clearAttachedBody("box");
330
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");
335 robot_state.update();
336
338 this->cenv_->checkSelfCollision(req, res, robot_state, *this->acm_);
339 ASSERT_FALSE(res.collision);
340
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_);
346 ASSERT_TRUE(res.collision);
347
348 this->acm_->setEntry("coll", "r_gripper_palm_link", true);
350 this->cenv_->checkRobotCollision(req, res, robot_state, *this->acm_);
351 ASSERT_TRUE(res.collision);
352}
353
355{
356 moveit::core::RobotState robot_state(this->robot_model_);
357 robot_state.setToDefaultValues();
358 robot_state.update();
359
362
363 collision_detection::CollisionEnvPtr new_cenv = this->value_->allocateEnv(this->cenv_, this->cenv_->getWorld());
364
365 auto before = std::chrono::system_clock::now();
366 new_cenv->checkSelfCollision(req, res, robot_state);
367 double first_check =
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();
373
374 EXPECT_TIME_LT(fabs(first_check - second_check), .05);
375
376 std::vector<shapes::ShapeConstPtr> shapes;
377 shapes.resize(1);
378
379 shapes[0].reset(shapes::createMeshFromResource(this->kinect_dae_resource_));
380
381 EigenSTL::vector_Isometry3d poses;
382 poses.push_back(Eigen::Isometry3d::Identity());
383
384 std::vector<std::string> touch_links;
385 robot_state.attachBody("kinect", poses[0], shapes, poses, touch_links, "r_gripper_palm_link");
386
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();
393
394 // the first check is going to take a while, as data must be constructed
395 EXPECT_TIME_LT(second_check, .1);
396
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();
404
405 EXPECT_TIME_LT(fabs(first_check - second_check), .05);
406}
407
408TYPED_TEST_P(CollisionDetectorTest, ConvertObjectToAttached)
409{
412
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;
417
418 this->cenv_->getWorld()->addToObject("kinect", pos1, shape, Eigen::Isometry3d::Identity());
419
420 moveit::core::RobotState robot_state(this->robot_model_);
421 robot_state.setToDefaultValues();
422 robot_state.update();
423
424 auto before = std::chrono::system_clock::now();
425 this->cenv_->checkRobotCollision(req, res, robot_state);
426 double first_check =
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();
432
433 EXPECT_TIME_LT(second_check, .05);
434
435 collision_detection::CollisionEnv::ObjectConstPtr object = this->cenv_->getWorld()->getObject("kinect");
436 this->cenv_->getWorld()->removeObject("kinect");
437
438 moveit::core::RobotState robot_state1(this->robot_model_);
439 moveit::core::RobotState robot_state2(this->robot_model_);
440 robot_state1.setToDefaultValues();
441 robot_state2.setToDefaultValues();
442 robot_state1.update();
443 robot_state2.update();
444
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");
449
450 EigenSTL::vector_Isometry3d other_poses;
451 other_poses.push_back(pos2);
452
453 // This creates a new set of constant properties for the attached body, which happens to be the same as the one above;
454 robot_state2.attachBody("kinect", identity_transform, object->shapes_, object->shape_poses_, touch_links,
455 "r_gripper_palm_link");
456
457 // going to take a while, but that's fine
459 this->cenv_->checkSelfCollision(req, res, robot_state1);
460
461 EXPECT_TRUE(res.collision);
462
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();
467 req.verbose = true;
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();
471
472 EXPECT_TIME_LT(first_check, .05);
473 EXPECT_TIME_LT(fabs(first_check - second_check), .1);
474}
475
476TYPED_TEST_P(CollisionDetectorTest, TestCollisionMapAdditionSpeed)
477{
478 EigenSTL::vector_Isometry3d poses;
479 std::vector<shapes::ShapeConstPtr> shapes;
480 for (unsigned int i = 0; i < 10000; ++i)
481 {
482 poses.push_back(Eigen::Isometry3d::Identity());
483 shapes.push_back(std::make_shared<shapes::Box>(.01, .01, .01));
484 }
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();
488 // TODO (j-petit): investigate why bullet collision checking is considerably slower here
489 EXPECT_TIME_LT(t, 5.0);
490 // this is not really a failure; it is just that slow;
491 // looking into doing collision checking with a voxel grid.
492 RCLCPP_INFO(rclcpp::get_logger("moveit.core.collision_detection.bullet"), "Adding boxes took %g", t);
493}
494
496{
497 moveit::core::RobotState robot_state1(this->robot_model_);
498 robot_state1.setToDefaultValues();
499 robot_state1.update();
500
501 Eigen::Isometry3d kinect_pose;
502 kinect_pose.setIdentity();
503 shapes::ShapePtr kinect_shape;
504 kinect_shape.reset(shapes::createMeshFromResource(this->kinect_dae_resource_));
505
506 this->cenv_->getWorld()->addToObject("kinect", kinect_shape, kinect_pose);
507
508 Eigen::Isometry3d np;
509 for (unsigned int i = 0; i < 5; ++i)
510 {
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_);
516 }
517}
518
519TYPED_TEST_P(CollisionDetectorTest, TestChangingShapeSize)
520{
521 moveit::core::RobotState robot_state1(this->robot_model_);
522 robot_state1.setToDefaultValues();
523 robot_state1.update();
524
527
528 ASSERT_FALSE(res1.collision);
529
530 EigenSTL::vector_Isometry3d poses;
531 std::vector<shapes::ShapeConstPtr> shapes;
532 for (unsigned int i = 0; i < 5; ++i)
533 {
534 this->cenv_->getWorld()->removeObject("shape");
535 shapes.clear();
536 poses.clear();
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_);
543 ASSERT_TRUE(res.collision);
544 }
545
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_);
553 ASSERT_TRUE(res2.collision);
554 for (unsigned int i = 0; i < 5; ++i)
555 {
556 this->cenv_->getWorld()->removeObject("shape");
557 shapes.clear();
558 poses.clear();
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_);
565 ASSERT_TRUE(res.collision);
566 }
567}
568
569REGISTER_TYPED_TEST_SUITE_P(CollisionDetectorTest, InitOK, DefaultNotInCollision, LinksInCollision, ContactReporting,
570 ContactPositions, AttachedBodyTester, DiffSceneTester, ConvertObjectToAttached,
571 TestCollisionMapAdditionSpeed, MoveMesh, TestChangingShapeSize);
collision_detection::CollisionEnvPtr cenv_
moveit::core::RobotModelPtr robot_model_
std::shared_ptr< CollisionAllocatorType > value_
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)