evaluate_collision_checking_speed.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, 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: Ioan Sucan, Sachin Chitta */
36 
38 #include <boost/program_options/parsers.hpp>
39 #include <boost/program_options/variables_map.hpp>
40 #include <boost/thread.hpp>
41 
42 static const std::string ROBOT_DESCRIPTION = "robot_description";
43 
44 void runCollisionDetection(unsigned int id, unsigned int trials, const planning_scene::PlanningScene& scene,
45  const moveit::core::RobotState& state)
46 {
47  ROS_INFO("Starting thread %u", id);
50  for (unsigned int i = 0; i < trials; ++i)
51  {
53  scene.checkCollision(req, res, state);
54  }
55  double duration = (ros::WallTime::now() - start).toSec();
56  ROS_INFO("Thread %u performed %lf collision checks per second", id, (double)trials / duration);
57 }
58 
59 int main(int argc, char** argv)
60 {
61  ros::init(argc, argv, "evaluate_collision_checking_speed");
62 
63  unsigned int nthreads = 2;
64  unsigned int trials = 10000;
65  boost::program_options::options_description desc;
66  desc.add_options()("nthreads", boost::program_options::value<unsigned int>(&nthreads)->default_value(nthreads),
67  "Number of threads to use")(
68  "trials", boost::program_options::value<unsigned int>(&trials)->default_value(trials),
69  "Number of collision checks to perform with each thread")("wait",
70  "Wait for a user command (so the planning scene can be "
71  "updated in thre background)")("help", "this screen");
72  boost::program_options::variables_map vm;
73  boost::program_options::parsed_options po = boost::program_options::parse_command_line(argc, argv, desc);
74  boost::program_options::store(po, vm);
75  boost::program_options::notify(vm);
76 
77  if (vm.count("help"))
78  {
79  std::cout << desc << std::endl;
80  return 0;
81  }
82 
84  spinner.start();
85 
87  if (psm.getPlanningScene())
88  {
89  if (vm.count("wait"))
90  {
92  psm.startSceneMonitor();
93  std::cout << "Listening to planning scene updates. Press Enter to continue ..." << std::endl;
94  std::cin.get();
95  }
96  else
97  ros::Duration(0.5).sleep();
98 
99  std::vector<moveit::core::RobotStatePtr> states;
100  ROS_INFO("Sampling %u valid states...", nthreads);
101  for (unsigned int i = 0; i < nthreads; ++i)
102  {
103  // sample a valid state
104  moveit::core::RobotState* state = new moveit::core::RobotState(psm.getPlanningScene()->getRobotModel());
106  do
107  {
108  state->setToRandomPositions();
109  state->update();
111  psm.getPlanningScene()->checkCollision(req, res);
112  if (!res.collision)
113  break;
114  } while (true);
115  states.push_back(moveit::core::RobotStatePtr(state));
116  }
117 
118  std::vector<boost::thread*> threads;
119 
120  for (unsigned int i = 0; i < states.size(); ++i)
121  threads.push_back(new boost::thread([i, trials, &scene = *psm.getPlanningScene(), &state = *states[i]] {
122  return runCollisionDetection(i, trials, scene, state);
123  }));
124 
125  for (unsigned int i = 0; i < states.size(); ++i)
126  {
127  threads[i]->join();
128  delete threads[i];
129  }
130  }
131  else
132  ROS_ERROR("Planning scene not configured");
133 
134  return 0;
135 }
duration
std::chrono::system_clock::duration duration
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
runCollisionDetection
void runCollisionDetection(unsigned int id, unsigned int trials, const planning_scene::PlanningScene &scene, const moveit::core::RobotState &state)
Definition: evaluate_collision_checking_speed.cpp:44
main
int main(int argc, char **argv)
Definition: evaluate_collision_checking_speed.cpp:59
planning_scene::PlanningScene
ros::AsyncSpinner
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
moveit::core::RobotState
moveit::core::RobotState::setToRandomPositions
void setToRandomPositions()
collision_detection::CollisionRequest
spinner
void spinner()
moveit::core::RobotState::update
void update(bool force=false)
planning_scene::PlanningScene::checkCollision
void checkCollision(const collision_detection::CollisionRequest &req, collision_detection::CollisionResult &res)
collision_detection::CollisionResult
ros::WallTime::now
static WallTime now()
ROS_ERROR
#define ROS_ERROR(...)
planning_scene_monitor.h
ros::WallTime
planning_scene_monitor::PlanningSceneMonitor
PlanningSceneMonitor Subscribes to the topic planning_scene.
Definition: planning_scene_monitor.h:93
planning_scene_monitor::PlanningSceneMonitor::startWorldGeometryMonitor
void startWorldGeometryMonitor(const std::string &collision_objects_topic=DEFAULT_COLLISION_OBJECT_TOPIC, const std::string &planning_scene_world_topic=DEFAULT_PLANNING_SCENE_WORLD_TOPIC, const bool load_octomap_monitor=true)
Start the OccupancyMapMonitor and listening for:
Definition: planning_scene_monitor.cpp:1111
start
ROSCPP_DECL void start()
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:1033
collision_detection::CollisionResult::collision
bool collision
ros::Duration::sleep
bool sleep() const
ROBOT_DESCRIPTION
static const std::string ROBOT_DESCRIPTION
Definition: evaluate_collision_checking_speed.cpp:42
ROS_INFO
#define ROS_INFO(...)
ros::Duration


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Jan 9 2025 03:24:37