Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
00038 #include <boost/program_options/parsers.hpp>
00039 #include <boost/program_options/variables_map.hpp>
00040
00041 static const std::string ROBOT_DESCRIPTION="robot_description";
00042
00043 void runCollisionDetection(unsigned int id, unsigned int trials, const planning_scene::PlanningScene *scene, const robot_state::RobotState *state)
00044 {
00045 ROS_INFO("Starting thread %u", id);
00046 collision_detection::CollisionRequest req;
00047 ros::WallTime start = ros::WallTime::now();
00048 for (unsigned int i = 0 ; i < trials ; ++i)
00049 {
00050 collision_detection::CollisionResult res;
00051 scene->checkCollision(req, res, *state);
00052 }
00053 double duration = (ros::WallTime::now() - start).toSec();
00054 ROS_INFO("Thread %u performed %lf collision checks per second", id, (double)trials / duration);
00055 }
00056
00057 int main(int argc, char **argv)
00058 {
00059 ros::init(argc, argv, "evaluate_collision_checking_speed");
00060
00061 unsigned int nthreads = 2;
00062 unsigned int trials = 10000;
00063 boost::program_options::options_description desc;
00064 desc.add_options()
00065 ("nthreads", boost::program_options::value<unsigned int>(&nthreads)->default_value(nthreads), "Number of threads to use")
00066 ("trials", boost::program_options::value<unsigned int>(&trials)->default_value(trials), "Number of collision checks to perform with each thread")
00067 ("wait", "Wait for a user command (so the planning scene can be updated in thre background)")
00068 ("help", "this screen");
00069 boost::program_options::variables_map vm;
00070 boost::program_options::parsed_options po = boost::program_options::parse_command_line(argc, argv, desc);
00071 boost::program_options::store(po, vm);
00072 boost::program_options::notify(vm);
00073
00074 if (vm.count("help"))
00075 {
00076 std::cout << desc << std::endl;
00077 return 0;
00078 }
00079
00080 ros::AsyncSpinner spinner(1);
00081 spinner.start();
00082
00083 planning_scene_monitor::PlanningSceneMonitor psm(ROBOT_DESCRIPTION);
00084 if (psm.getPlanningScene())
00085 {
00086 if (vm.count("wait"))
00087 {
00088 psm.startWorldGeometryMonitor();
00089 psm.startSceneMonitor();
00090 std::cout << "Listening to planning scene updates. Press Enter to continue ..." << std::endl;
00091 std::cin.get();
00092 }
00093 else
00094 ros::Duration(0.5).sleep();
00095
00096 std::vector<robot_state::RobotStatePtr> states;
00097 ROS_INFO("Sampling %u valid states...", nthreads);
00098 for (unsigned int i = 0 ; i < nthreads ; ++i)
00099 {
00100
00101 robot_state::RobotState *state = new robot_state::RobotState(psm.getPlanningScene()->getRobotModel());
00102 collision_detection::CollisionRequest req;
00103 do
00104 {
00105 state->setToRandomPositions();
00106 collision_detection::CollisionResult res;
00107 psm.getPlanningScene()->checkCollision(req, res);
00108 if (!res.collision)
00109 break;
00110 } while (true);
00111 states.push_back(robot_state::RobotStatePtr(state));
00112 }
00113
00114 std::vector<boost::thread*> threads;
00115
00116 for (unsigned int i = 0 ; i < states.size() ; ++i)
00117 threads.push_back(new boost::thread(boost::bind(&runCollisionDetection, i, trials, psm.getPlanningScene().get(), states[i].get())));
00118
00119 for (unsigned int i = 0 ; i < states.size() ; ++i)
00120 {
00121 threads[i]->join();
00122 delete threads[i];
00123 }
00124 }
00125 else
00126 ROS_ERROR("Planning scene not configured");
00127
00128 return 0;
00129 }