35 #ifndef NAV_2D_UTILS_PLUGIN_MUX_H
36 #define NAV_2D_UTILS_PLUGIN_MUX_H
40 #include <std_msgs/String.h>
41 #include <nav_2d_msgs/SwitchPlugin.h>
72 PluginMux(
const std::string& plugin_package,
const std::string& plugin_class,
73 const std::string& parameter_name,
const std::string&
default_value,
74 const std::string& ros_name =
"current_plugin",
const std::string& switch_service_name =
"switch_plugin");
81 void addPlugin(
const std::string& plugin_name,
const std::string& plugin_class_name);
92 if (
plugins_.count(name) == 0)
return false;
103 std_msgs::String str_msg;
138 throw std::invalid_argument(
"Plugin not found");
156 std::vector<std::string> names;
159 names.push_back(kv.first);
170 using SwitchCallback = std::function<void(
const std::string&,
const std::string&)>;
186 bool switchPluginService(nav_2d_msgs::SwitchPlugin::Request &req, nav_2d_msgs::SwitchPlugin::Response &resp)
188 std::string name = req.new_plugin;
192 resp.message =
"Loaded plugin namespace " + name +
".";
196 resp.success =
false;
197 resp.message =
"Namespace " + name +
" not configured!";
204 std::map<std::string, boost::shared_ptr<T>>
plugins_;
222 const std::string& parameter_name,
const std::string& default_value,
223 const std::string& ros_name,
const std::string& switch_service_name)
224 : plugin_loader_(plugin_package, plugin_class), private_nh_(
"~"), ros_name_(ros_name), switch_callback_(nullptr)
230 std::string plugin_class_name;
231 std::vector<std::string> plugin_namespaces;
233 if (plugin_namespaces.size() == 0)
237 plugin_namespaces.push_back(plugin_name);
240 for (
const std::string& the_namespace : plugin_namespaces)
244 addPlugin(the_namespace, plugin_class_name);
251 if (plugin_namespaces.size() > 1)
262 plugins_[plugin_name] = plugin_loader_.createInstance(plugin_class_name);
267 "Failed to load the plugin: %s. Exception: %s", plugin_name.c_str(), ex.what());
274 #endif // NAV_2D_UTILS_PLUGIN_MUX_H