37 #include <pluginlib/class_loader.hpp>
39 #include <rclcpp/node.hpp>
40 #include <rclcpp/utilities.hpp>
43 int main(
int argc,
char** argv)
45 rclcpp::init(argc, argv);
47 auto node = std::make_shared<rclcpp::Node>(
"list_planning_adapter_plugins");
49 std::unique_ptr<pluginlib::ClassLoader<planning_request_adapter::PlanningRequestAdapter>> loader;
52 loader = std::make_unique<pluginlib::ClassLoader<planning_request_adapter::PlanningRequestAdapter>>(
53 "moveit_core",
"planning_request_adapter::PlanningRequestAdapter");
55 catch (pluginlib::PluginlibException& ex)
57 std::cout <<
"Exception while creating class loader " << ex.what() <<
'\n';
60 const std::vector<std::string>& classes = loader->getDeclaredClasses();
61 std::cout <<
"Available planning request adapter plugins:" <<
'\n';
62 for (
const std::string& adapter_plugin_name : classes)
64 std::cout <<
" \t " << adapter_plugin_name <<
'\n';
65 planning_request_adapter::PlanningRequestAdapterConstPtr ad;
68 ad = loader->createUniqueInstance(adapter_plugin_name);
70 catch (pluginlib::PluginlibException& ex)
72 std::cout <<
" \t\t Exception while planning adapter plugin '" << adapter_plugin_name <<
"': " << ex.what()
76 std::cout <<
" \t\t " << ad->getDescription() <<
'\n';
77 std::cout <<
'\n' <<
'\n';
int main(int argc, char **argv)