42 int main(
int argc,
char** argv)
44 ros::init(argc, argv,
"list_planning_adapter_plugins");
46 std::unique_ptr<pluginlib::ClassLoader<planning_request_adapter::PlanningRequestAdapter>> loader;
49 loader = std::make_unique<pluginlib::ClassLoader<planning_request_adapter::PlanningRequestAdapter>>(
50 "moveit_core",
"planning_request_adapter::PlanningRequestAdapter");
54 std::cout <<
"Exception while creating class loader " << ex.what() << std::endl;
57 const std::vector<std::string>& classes = loader->getDeclaredClasses();
58 std::cout <<
"Available planning request adapter plugins:" << std::endl;
59 for (
const std::string& adapter_plugin_name : classes)
61 std::cout <<
" \t " << adapter_plugin_name << std::endl;
62 planning_request_adapter::PlanningRequestAdapterConstPtr ad;
65 ad = loader->createUniqueInstance(adapter_plugin_name);
69 std::cout <<
" \t\t Exception while planning adapter plugin '" << adapter_plugin_name <<
"': " << ex.what()
73 std::cout <<
" \t\t " << ad->getDescription() << std::endl;
74 std::cout << std::endl << std::endl;