compare_collision_speed_checking_fcl_bullet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2019, Jens Petit
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 the copyright holder 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: Jens Petit */
36 
43 
46 
47 static const std::string ROBOT_DESCRIPTION = "robot_description";
48 
50 static const int MAX_SEARCH_FACTOR_CLUTTER = 3;
51 
53 static const int MAX_SEARCH_FACTOR_STATES = 30;
54 
57 {
60  RANDOM,
61 };
62 
65 {
66  FCL,
67  BULLET,
68 };
69 
72 {
73  MESH,
74  BOX,
75 };
76 
83 void clutterWorld(const planning_scene::PlanningScenePtr& planning_scene, const size_t num_objects,
85 {
86  ROS_INFO("Cluttering scene...");
87 
89 
90  // allow all robot links to be in collision for world check
92  planning_scene->getRobotModel()->getLinkModelNames(), true) };
93 
94  // set the robot state to home position
95  moveit::core::RobotState& current_state{ planning_scene->getCurrentStateNonConst() };
97  current_state.setToDefaultValues(current_state.getJointModelGroup("panda_arm"), "home");
98  current_state.update();
99 
100  // load panda link5 as world collision object
101  std::string name;
102  shapes::ShapeConstPtr shape;
103  std::string kinect = "package://moveit_resources_panda_description/meshes/collision/link5.stl";
104 
105  Eigen::Quaterniond quat;
106  Eigen::Isometry3d pos{ Eigen::Isometry3d::Identity() };
107 
108  size_t added_objects{ 0 };
109  size_t i{ 0 };
110  // create random objects until as many added as desired or quit if too many attempts
111  while (added_objects < num_objects && i < num_objects * MAX_SEARCH_FACTOR_CLUTTER)
112  {
113  // add with random size and random position
114  pos.translation().x() = num_generator.uniformReal(-1.0, 1.0);
115  pos.translation().y() = num_generator.uniformReal(-1.0, 1.0);
116  pos.translation().z() = num_generator.uniformReal(0.0, 1.0);
117 
118  quat.x() = num_generator.uniformReal(-1.0, 1.0);
119  quat.y() = num_generator.uniformReal(-1.0, 1.0);
120  quat.z() = num_generator.uniformReal(-1.0, 1.0);
121  quat.w() = num_generator.uniformReal(-1.0, 1.0);
122  quat.normalize();
123  pos.rotate(quat);
124 
125  switch (type)
126  {
127  case CollisionObjectType::MESH:
128  {
130  mesh->scale(num_generator.uniformReal(0.3, 1.0));
131  shape.reset(mesh);
132  name = "mesh";
133  break;
134  }
135  case CollisionObjectType::BOX:
136  {
137  shape =
138  std::make_shared<shapes::Box>(num_generator.uniformReal(0.05, 0.2), num_generator.uniformReal(0.05, 0.2),
139  num_generator.uniformReal(0.05, 0.2));
140  name = "box";
141  break;
142  }
143  }
144 
145  name.append(std::to_string(i));
146  planning_scene->getWorldNonConst()->addToObject(name, shape, pos);
147 
148  // try if it isn't in collision if yes, ok, if no remove.
150  planning_scene->checkCollision(req, res, current_state, acm);
151 
152  if (!res.collision)
153  {
154  added_objects++;
155  }
156  else
157  {
158  ROS_DEBUG_STREAM("Object was in collision, remove");
159  planning_scene->getWorldNonConst()->removeObject(name);
160  }
161 
162  i++;
163  }
164  ROS_INFO_STREAM("Cluttered the planning scene with " << added_objects << " objects");
165 }
166 
173 void runCollisionDetection(unsigned int trials, const planning_scene::PlanningScenePtr& scene,
174  const std::vector<moveit::core::RobotState>& states, const CollisionDetector col_detector,
175  bool only_self, bool distance = false)
176 {
178  scene->getRobotModel()->getLinkModelNames(), true) };
179 
180  ROS_INFO_STREAM("Starting detection using " << (col_detector == CollisionDetector::FCL ? "FCL" : "Bullet"));
181 
182  if (col_detector == CollisionDetector::FCL)
183  {
184  scene->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorFCL::create());
185  }
186  else
187  {
188  scene->setActiveCollisionDetector(collision_detection::CollisionDetectorAllocatorBullet::create());
189  }
190 
193 
194  req.distance = distance;
195  // for world collision request detailed information
196  if (!only_self)
197  {
198  req.contacts = true;
199  req.max_contacts = 99;
200  req.max_contacts_per_pair = 10;
201  // If distance is turned on it will slow down the collision checking a lot. Try reducing the
202  // number of contacts consequently.
203  // req.distance = true;
204  }
205 
207  for (unsigned int i = 0; i < trials; ++i)
208  {
209  for (auto& state : states)
210  {
211  res.clear();
212 
213  if (only_self)
214  {
215  scene->checkSelfCollision(req, res);
216  }
217  else
218  {
219  scene->checkCollision(req, res, state);
220  }
221  }
222  }
223  double duration = (ros::WallTime::now() - start).toSec();
224  ROS_INFO("Performed %lf collision checks per second", (double)trials * states.size() / duration);
225  ROS_INFO_STREAM("Total number was " << trials * states.size() << " checks.");
226  ROS_INFO_STREAM("We had " << states.size() << " different robot states which were "
227  << (res.collision ? "in collison " : "not in collision ") << "with " << res.contact_count);
228 
229  // color collided objects red
230  for (auto& contact : res.contacts)
231  {
232  ROS_INFO_STREAM("Between: " << contact.first.first << " and " << contact.first.second);
233  std_msgs::ColorRGBA red;
234  red.a = 0.8;
235  red.r = 1;
236  red.g = 0;
237  red.b = 0;
238  scene->setObjectColor(contact.first.first, red);
239  scene->setObjectColor(contact.first.second, red);
240  }
241 
242  scene->setCurrentState(states.back());
243 }
244 
250 void findStates(const RobotStateSelector desired_states, unsigned int num_states,
251  const planning_scene::PlanningScenePtr& scene, std::vector<moveit::core::RobotState>& robot_states)
252 {
253  moveit::core::RobotState& current_state{ scene->getCurrentStateNonConst() };
255 
256  size_t i{ 0 };
257  while (robot_states.size() < num_states && i < num_states * MAX_SEARCH_FACTOR_STATES)
258  {
259  current_state.setToRandomPositions();
260  current_state.update();
262  scene->checkSelfCollision(req, res);
263  ROS_INFO_STREAM("Found state " << (res.collision ? "in collision" : "not in collision"));
264 
265  switch (desired_states)
266  {
268  if (res.collision)
269  robot_states.push_back(current_state);
270  break;
272  if (!res.collision)
273  robot_states.push_back(current_state);
274  break;
276  robot_states.push_back(current_state);
277  break;
278  }
279  i++;
280  }
281 
282  if (!robot_states.empty())
283  {
284  scene->setCurrentState(robot_states[0]);
285  }
286  else
287  {
288  ROS_ERROR_STREAM("Did not find any correct states.");
289  }
290 }
291 
292 int main(int argc, char** argv)
293 {
294  moveit::core::RobotModelPtr robot_model;
295  ros::init(argc, argv, "compare_collision_checking_speed");
296  ros::NodeHandle node_handle;
297 
298  ros::Publisher planning_scene_diff_publisher = node_handle.advertise<moveit_msgs::PlanningScene>("planning_scene", 1);
299 
300  unsigned int trials = 10000;
301 
303  spinner.start();
304  ros::WallDuration sleep_t(2.5);
305 
306  robot_model = moveit::core::loadTestingRobotModel("panda");
307 
308  planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model));
311  psm.startSceneMonitor();
313 
317  robot_model->getLinkModelNames(), true) };
318  planning_scene->checkCollision(req, res, planning_scene->getCurrentState(), acm);
319 
320  ROS_INFO("Starting...");
321 
322  if (psm.getPlanningScene())
323  {
324  ros::Duration(0.5).sleep();
325 
326  moveit::core::RobotState& current_state{ planning_scene->getCurrentStateNonConst() };
327  current_state.setToDefaultValues(current_state.getJointModelGroup("panda_arm"), "home");
328  current_state.update();
329 
330  std::vector<moveit::core::RobotState> sampled_states;
331  sampled_states.push_back(current_state);
332 
333  ROS_INFO("Starting benchmark: Robot in empty world, only self collision check");
334  runCollisionDetection(trials, planning_scene, sampled_states, CollisionDetector::BULLET, true);
335  runCollisionDetection(trials, planning_scene, sampled_states, CollisionDetector::FCL, true);
336 
338 
339  clutterWorld(planning_scene, 100, CollisionObjectType::MESH);
340 
341  ROS_INFO("Starting benchmark: Robot in cluttered world, no collision with world");
342  runCollisionDetection(trials, planning_scene, sampled_states, CollisionDetector::BULLET, false);
343  runCollisionDetection(trials, planning_scene, sampled_states, CollisionDetector::FCL, false);
344 
345  // bring the robot into a position which collides with the world clutter
346  double joint_2 = 1.5;
347  current_state.setJointPositions("panda_joint2", &joint_2);
348  current_state.update();
349 
350  std::vector<moveit::core::RobotState> sampled_states_2;
351  sampled_states_2.push_back(current_state);
352 
353  ROS_INFO("Starting benchmark: Robot in cluttered world, in collision with world");
354  runCollisionDetection(trials, planning_scene, sampled_states_2, CollisionDetector::BULLET, false);
355  runCollisionDetection(trials, planning_scene, sampled_states_2, CollisionDetector::FCL, false);
356 
357  bool visualize;
358  node_handle.getParam("/compare_collision_checking_speed/visualization", visualize);
359  if (visualize)
360  {
361  // publishes the planning scene to visualize in rviz if possible
362  moveit_msgs::PlanningScene planning_scene_msg;
363  planning_scene->getPlanningSceneMsg(planning_scene_msg);
364  planning_scene_diff_publisher.publish(planning_scene_msg);
365  }
366  }
367  else
368  {
369  ROS_ERROR("Planning scene not configured");
370  }
371 
372  return 0;
373 }
robot_model.h
random_numbers.h
runCollisionDetection
void runCollisionDetection(unsigned int trials, const planning_scene::PlanningScenePtr &scene, const std::vector< moveit::core::RobotState > &states, const CollisionDetector col_detector, bool only_self, bool distance=false)
Runs a collision detection benchmark and measures the time.
Definition: compare_collision_speed_checking_fcl_bullet.cpp:173
RobotStateSelector::IN_COLLISION
@ IN_COLLISION
MAX_SEARCH_FACTOR_STATES
static const int MAX_SEARCH_FACTOR_STATES
Factor to compute the maximum number of trials for random state generation.
Definition: compare_collision_speed_checking_fcl_bullet.cpp:53
main
int main(int argc, char **argv)
Definition: compare_collision_speed_checking_fcl_bullet.cpp:292
ros::Publisher
duration
std::chrono::system_clock::duration duration
CollisionDetector::FCL
@ FCL
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
collision_detector_allocator_fcl.h
RobotStateSelector::RANDOM
@ RANDOM
findStates
void findStates(const RobotStateSelector desired_states, unsigned int num_states, const planning_scene::PlanningScenePtr &scene, std::vector< moveit::core::RobotState > &robot_states)
Samples valid states of the robot which can be in collision if desired.
Definition: compare_collision_speed_checking_fcl_bullet.cpp:250
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
planning_scene::PlanningScene
ros::AsyncSpinner
CollisionObjectType
CollisionObjectType
random_numbers::RandomNumberGenerator::uniformReal
double uniformReal(double lower_bound, double upper_bound)
CollisionDetector
CollisionDetector
Enumerates the available collision detectors.
Definition: compare_collision_speed_checking_fcl_bullet.cpp:64
planning_scene_monitor::PlanningSceneMonitor::getPlanningScene
const planning_scene::PlanningScenePtr & getPlanningScene()
Avoid this function! Returns an unsafe pointer to the current planning scene.
Definition: planning_scene_monitor.h:224
shape_operations.h
moveit::core::RobotState
shapes::Mesh
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
collision_detection::CollisionRequest
MESH
MESH
collision_detection::CollisionRequest::distance
bool distance
spinner
void spinner()
collision_detection::AllowedCollisionMatrix
name
std::string name
ROBOT_DESCRIPTION
static const std::string ROBOT_DESCRIPTION
Definition: compare_collision_speed_checking_fcl_bullet.cpp:47
collision_detection::CollisionResult
ros::WallTime::now
static WallTime now()
collision_detection::CollisionRequest::max_contacts
std::size_t max_contacts
ROS_ERROR
#define ROS_ERROR(...)
shapes::createMeshFromResource
Mesh * createMeshFromResource(const std::string &resource)
planning_scene_monitor.h
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
ros::WallTime
CollisionDetectorAllocatorTemplate< CollisionEnvFCL, CollisionDetectorAllocatorFCL >::create
static CollisionDetectorAllocatorPtr create()
shapes::Mesh::scale
void scale(double scale)
planning_scene_monitor::PlanningSceneMonitor
PlanningSceneMonitor Subscribes to the topic planning_scene.
Definition: planning_scene_monitor.h:93
distance
template void distance(DistanceTraversalNodeBase< double > *node, BVHFrontList *front_list, int qsize)
random_numbers::RandomNumberGenerator
collision_detection::CollisionResult::contacts
ContactMap contacts
start
ROSCPP_DECL void start()
clutterWorld
void clutterWorld(const planning_scene::PlanningScenePtr &planning_scene, const size_t num_objects, CollisionObjectType type)
Clutters the world of the planning scene with random objects in a certain area around the origin....
Definition: compare_collision_speed_checking_fcl_bullet.cpp:83
collision_detector_allocator_bullet.h
RobotStateSelector::NOT_IN_COLLISION
@ NOT_IN_COLLISION
planning_scene_monitor::PlanningSceneMonitor::startSceneMonitor
void startSceneMonitor(const std::string &scene_topic=DEFAULT_PLANNING_SCENE_TOPIC)
Start the scene monitor (ROS topic-based)
Definition: planning_scene_monitor.cpp:1040
CollisionDetector::BULLET
@ BULLET
RobotStateSelector
RobotStateSelector
Defines a random robot state.
Definition: compare_collision_speed_checking_fcl_bullet.cpp:56
collision_detection::CollisionRequest::contacts
bool contacts
shapes::ShapeConstPtr
std::shared_ptr< const Shape > ShapeConstPtr
collision_detection::CollisionResult::collision
bool collision
MAX_SEARCH_FACTOR_CLUTTER
static const int MAX_SEARCH_FACTOR_CLUTTER
Factor to compute the maximum number of trials random clutter generation.
Definition: compare_collision_speed_checking_fcl_bullet.cpp:50
ros::Duration::sleep
bool sleep() const
planning_scene_monitor::PlanningSceneMonitor::UPDATE_SCENE
@ UPDATE_SCENE
The entire scene was updated.
Definition: planning_scene_monitor.h:112
collision_detection::CollisionRequest::max_contacts_per_pair
std::size_t max_contacts_per_pair
ros::WallDuration
ROS_INFO
#define ROS_INFO(...)
planning_scene
robot_model_test_utils.h
collision_detection::CollisionResult::clear
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
planning_scene_monitor::PlanningSceneMonitor::startPublishingPlanningScene
void startPublishingPlanningScene(SceneUpdateType event, const std::string &planning_scene_topic=MONITORED_PLANNING_SCENE_TOPIC)
Start publishing the maintained planning scene. The first message set out is a complete planning scen...
Definition: planning_scene_monitor.cpp:376
collision_detection::CollisionResult::contact_count
std::size_t contact_count
ros::Duration
collision_plugin_loader.h
BOX
BOX
ros::NodeHandle
moveit::core::loadTestingRobotModel
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &robot_name)


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Feb 27 2025 03:27:54