38 #include <boost/program_options/parsers.hpp>
39 #include <boost/program_options/variables_map.hpp>
40 #include <boost/thread.hpp>
50 for (
unsigned int i = 0; i < trials; ++i)
56 ROS_INFO(
"Thread %u performed %lf collision checks per second",
id, (
double)trials /
duration);
59 int main(
int argc,
char** argv)
61 ros::init(argc, argv,
"evaluate_collision_checking_speed");
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);
79 std::cout << desc << std::endl;
93 std::cout <<
"Listening to planning scene updates. Press Enter to continue ..." << std::endl;
99 std::vector<moveit::core::RobotStatePtr> states;
100 ROS_INFO(
"Sampling %u valid states...", nthreads);
101 for (
unsigned int i = 0; i < nthreads; ++i)
115 states.push_back(moveit::core::RobotStatePtr(state));
118 std::vector<boost::thread*> threads;
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);
125 for (
unsigned int i = 0; i < states.size(); ++i)
132 ROS_ERROR(
"Planning scene not configured");