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 <pluginlib/class_loader.h>
00038 #include <moveit/planning_request_adapter/planning_request_adapter.h>
00039 #include <ros/ros.h>
00040
00041 int main(int argc, char **argv)
00042 {
00043 ros::init(argc, argv, "list_planning_adapter_plugins");
00044
00045 boost::scoped_ptr<pluginlib::ClassLoader<planning_request_adapter::PlanningRequestAdapter> > loader;
00046 try
00047 {
00048 loader.reset(new pluginlib::ClassLoader<planning_request_adapter::PlanningRequestAdapter>("moveit_core", "planning_request_adapter::PlanningRequestAdapter"));
00049 }
00050 catch(pluginlib::PluginlibException& ex)
00051 {
00052 std::cout << "Exception while creating class loader " << ex.what() << std::endl;
00053 }
00054
00055 const std::vector<std::string> &classes = loader->getDeclaredClasses();
00056 std::cout << "Available planning request adapter plugins:" << std::endl;
00057 for (std::size_t i = 0 ; i < classes.size() ; ++i)
00058 {
00059 std::cout << " \t " << classes[i] << std::endl;
00060 planning_request_adapter::PlanningRequestAdapterConstPtr ad;
00061 try
00062 {
00063 ad.reset(loader->createUnmanagedInstance(classes[i]));
00064 }
00065 catch (pluginlib::PluginlibException& ex)
00066 {
00067 std::cout << " \t\t Exception while planning adapter plugin '" << classes[i] << "': " << ex.what() << std::endl;
00068 }
00069 if (ad)
00070 std::cout << " \t\t " << ad->getDescription() << std::endl;
00071 std::cout << std::endl << std::endl;
00072 }
00073
00074 return 0;
00075 }