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 #include "planning_interface/planning_interface.h"
00036 #include <planning_scene_monitor/planning_scene_monitor.h>
00037 #include <pluginlib/class_loader.h>
00038 #include <ros/ros.h>
00039 #include <tf/transform_listener.h>
00040
00041 #include <gtest/gtest.h>
00042
00043 static planning_scene_monitor::PlanningSceneMonitor *g_psm = NULL;
00044
00045 TEST(PlanningInterfaceTester, loadAllPlanners)
00046 {
00047 pluginlib::ClassLoader<planning_interface::Planner>* planner_loader;
00048 try
00049 {
00050 planner_loader = new pluginlib::ClassLoader<planning_interface::Planner>("planning_interface", "planning_interface::Planner");
00051 }
00052 catch(pluginlib::PluginlibException& ex)
00053 {
00054 FAIL() << "Exception while creating class loader " << ex.what();
00055 }
00056
00057 std::vector<std::string> classes;
00058 std::vector<boost::shared_ptr<planning_interface::Planner> > planners;
00059 planning_scene::PlanningSceneConstPtr scene = g_psm->getPlanningScene();
00060 planning_models::RobotModelConstPtr model = scene->getRobotModel();
00061
00062 classes = planner_loader->getDeclaredClasses();
00063
00064 ASSERT_GT(classes.size(), 0);
00065 printf("Loading classes:\n");
00066 for(std::vector<std::string>::const_iterator it = classes.begin();
00067 it != classes.end();
00068 ++it)
00069 printf(" %s\n", it->c_str());
00070 fflush(stdout);
00071 return;
00072
00073 for(std::vector<std::string>::const_iterator it = classes.begin();
00074 it != classes.end();
00075 ++it)
00076 {
00077 try
00078 {
00079 boost::shared_ptr<planning_interface::Planner> p(planner_loader->createUnmanagedInstance(*it));
00080 p->init(model);
00081 planners.push_back(p);
00082 }
00083 catch(pluginlib::PluginlibException& ex)
00084 {
00085
00086 ADD_FAILURE() << "Exception while loading planner: " << *it << ": " << ex.what();
00087 }
00088 }
00089
00090 for(std::vector<boost::shared_ptr<planning_interface::Planner> >::const_iterator it = planners.begin();
00091 it != planners.end();
00092 ++it)
00093 {
00094
00095
00096 moveit_msgs::GetMotionPlan::Request req;
00097 planning_interface::PlannerCapability capabilities;
00098 bool can_service = (*it)->canServiceRequest(req, capabilities);
00099 EXPECT_TRUE(can_service);
00100
00101
00102 moveit_msgs::GetMotionPlan::Response res;
00103 bool solved = (*it)->solve(scene, req, res);
00104 EXPECT_FALSE(solved);
00105 }
00106 }
00107
00108 static const std::string ROBOT_DESCRIPTION="robot_description";
00109
00110
00111 int main(int argc, char** argv)
00112 {
00113 testing::InitGoogleTest(&argc, argv);
00114
00115 ros::init(argc, argv, "planner_loader");
00116
00117 g_psm = new planning_scene_monitor::PlanningSceneMonitor(ROBOT_DESCRIPTION);
00118 if(g_psm->getPlanningScene() && g_psm->getPlanningScene()->isConfigured())
00119 {
00120 g_psm->startWorldGeometryMonitor();
00121 g_psm->startSceneMonitor();
00122 g_psm->startStateMonitor();
00123 int r = RUN_ALL_TESTS();
00124 delete g_psm;
00125 return r;
00126 }
00127 else
00128 {
00129 ROS_ERROR("Planning scene not configured");
00130 delete g_psm;
00131
00132 return 1;
00133 }
00134 }