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;
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 (std::size_t i = 0; i < classes.size(); ++i)
61 std::cout <<
" \t " << classes[i] << std::endl;
62 planning_request_adapter::PlanningRequestAdapterConstPtr ad;
65 ad.reset(loader->createUnmanagedInstance(classes[i]));
69 std::cout <<
" \t\t Exception while planning adapter plugin '" << classes[i] <<
"': " << ex.what() << std::endl;
72 std::cout <<
" \t\t " << ad->getDescription() << std::endl;
73 std::cout << std::endl << std::endl;
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)