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