From 63e7ff3bf7214ca95997e99928756f89250989fc Mon Sep 17 00:00:00 2001 From: AndyZe Date: Wed, 3 Feb 2021 15:16:25 -0600 Subject: [PATCH 1/3] Set Bullet as the exclusive collision detection algorithm. --- .../src/bullet_collision_checker_tutorial.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/doc/bullet_collision_checker/src/bullet_collision_checker_tutorial.cpp b/doc/bullet_collision_checker/src/bullet_collision_checker_tutorial.cpp index 59d8c20c0..beaf34bcf 100644 --- a/doc/bullet_collision_checker/src/bullet_collision_checker_tutorial.cpp +++ b/doc/bullet_collision_checker/src/bullet_collision_checker_tutorial.cpp @@ -163,8 +163,10 @@ int main(int argc, char** argv) // Changing the collision detector to Bullet // ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ // The active collision detector is set from the planning scene using the specific collision detector allocator for - // Bullet. - g_planning_scene->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorBullet::create()); + // Bullet. The second argument indicates that Bullet will be the exclusive collision detection algorithm; the + // default FCL will not be available anymore. Having one exclusive collision detection algorithm helps performance + // a bit and is much more common. + g_planning_scene->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorBullet::create(), true /* exclusive */); // For understanding the interactive interactive_robot, please refer to the Visualizing Collisions tutorial. // CALL_SUB_TUTORIAL CCD // CALL_SUB_TUTORIAL CCD_2 @@ -209,7 +211,7 @@ int main(int argc, char** argv) // again set as the active collision detector. robot_model::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("panda"); auto planning_scene = std::make_shared(robot_model); - planning_scene->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorBullet::create()); + planning_scene->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorBullet::create(), true /* exclusive */); // The box is added and the robot brought into its position. Eigen::Isometry3d box_pose{ Eigen::Isometry3d::Identity() }; From f3da0579de5d34c10afbc9ea7e2031c41598e143 Mon Sep 17 00:00:00 2001 From: AndyZe Date: Fri, 5 Feb 2021 09:50:09 -0600 Subject: [PATCH 2/3] Update comment format Co-authored-by: Felix von Drigalski --- .../src/bullet_collision_checker_tutorial.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/bullet_collision_checker/src/bullet_collision_checker_tutorial.cpp b/doc/bullet_collision_checker/src/bullet_collision_checker_tutorial.cpp index beaf34bcf..b518ec161 100644 --- a/doc/bullet_collision_checker/src/bullet_collision_checker_tutorial.cpp +++ b/doc/bullet_collision_checker/src/bullet_collision_checker_tutorial.cpp @@ -211,7 +211,7 @@ int main(int argc, char** argv) // again set as the active collision detector. robot_model::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("panda"); auto planning_scene = std::make_shared(robot_model); - planning_scene->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorBullet::create(), true /* exclusive */); + planning_scene->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorBullet::create(), /* exclusive = */ true); // The box is added and the robot brought into its position. Eigen::Isometry3d box_pose{ Eigen::Isometry3d::Identity() }; From 5c8894560442f884e7535aae30cca5fafca8bf65 Mon Sep 17 00:00:00 2001 From: AndyZe Date: Wed, 10 Mar 2021 14:04:11 -0600 Subject: [PATCH 3/3] Clang format --- .../src/bullet_collision_checker_tutorial.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/doc/bullet_collision_checker/src/bullet_collision_checker_tutorial.cpp b/doc/bullet_collision_checker/src/bullet_collision_checker_tutorial.cpp index b518ec161..5cc460b9f 100644 --- a/doc/bullet_collision_checker/src/bullet_collision_checker_tutorial.cpp +++ b/doc/bullet_collision_checker/src/bullet_collision_checker_tutorial.cpp @@ -166,7 +166,8 @@ int main(int argc, char** argv) // Bullet. The second argument indicates that Bullet will be the exclusive collision detection algorithm; the // default FCL will not be available anymore. Having one exclusive collision detection algorithm helps performance // a bit and is much more common. - g_planning_scene->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorBullet::create(), true /* exclusive */); + g_planning_scene->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorBullet::create(), + true /* exclusive */); // For understanding the interactive interactive_robot, please refer to the Visualizing Collisions tutorial. // CALL_SUB_TUTORIAL CCD // CALL_SUB_TUTORIAL CCD_2 @@ -211,7 +212,8 @@ int main(int argc, char** argv) // again set as the active collision detector. robot_model::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel("panda"); auto planning_scene = std::make_shared(robot_model); - planning_scene->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorBullet::create(), /* exclusive = */ true); + planning_scene->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorBullet::create(), + /* exclusive = */ true); // The box is added and the robot brought into its position. Eigen::Isometry3d box_pose{ Eigen::Isometry3d::Identity() };