@@ -163,8 +163,11 @@ int main(int argc, char** argv)
163163 // Changing the collision detector to Bullet
164164 // ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
165165 // The active collision detector is set from the planning scene using the specific collision detector allocator for
166- // Bullet.
167- g_planning_scene->setActiveCollisionDetector (collision_detection::CollisionDetectorAllocatorBullet::create ());
166+ // Bullet. The second argument indicates that Bullet will be the exclusive collision detection algorithm; the
167+ // default FCL will not be available anymore. Having one exclusive collision detection algorithm helps performance
168+ // a bit and is much more common.
169+ g_planning_scene->setActiveCollisionDetector (collision_detection::CollisionDetectorAllocatorBullet::create (),
170+ true /* exclusive */ );
168171 // For understanding the interactive interactive_robot, please refer to the Visualizing Collisions tutorial.
169172 // CALL_SUB_TUTORIAL CCD
170173 // CALL_SUB_TUTORIAL CCD_2
@@ -209,7 +212,8 @@ int main(int argc, char** argv)
209212 // again set as the active collision detector.
210213 robot_model::RobotModelPtr robot_model = moveit::core::loadTestingRobotModel (" panda" );
211214 auto planning_scene = std::make_shared<planning_scene::PlanningScene>(robot_model);
212- planning_scene->setActiveCollisionDetector (collision_detection::CollisionDetectorAllocatorBullet::create ());
215+ planning_scene->setActiveCollisionDetector (collision_detection::CollisionDetectorAllocatorBullet::create (),
216+ /* exclusive = */ true );
213217
214218 // The box is added and the robot brought into its position.
215219 Eigen::Isometry3d box_pose{ Eigen::Isometry3d::Identity () };
0 commit comments