planning_interface_tester.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2012, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
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   // Must have some planners
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       // All planners must load
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     // A dumb test: require that the planners return true from
00095     // canServiceRequest
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     // Another dumb test: require that the planners return false from solve
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 }


pr2_planning_interface_tests
Author(s): Brian Gerkey
autogenerated on Mon Oct 6 2014 11:14:48