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)
   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)
   243     private_nh_.
param(std::string(the_namespace + 
"/plugin_class"), plugin_class_name, default_value);
   244     addPlugin(the_namespace, plugin_class_name);
   251   if (plugin_namespaces.size() > 1)
   267                     "Failed to load the plugin: %s. Exception: %s", plugin_name.c_str(), ex.what());
   274 #endif  // NAV_2D_UTILS_PLUGIN_MUX_H void addPlugin(const std::string &plugin_name, const std::string &plugin_class_name)
Create an instance of the given plugin_class_name and save it with the given plugin_name. 
bool hasPlugin(const std::string &name) const 
Check to see if a plugin exists. 
void publish(const boost::shared_ptr< M > &message) const 
A set of utility functions for Bounds objects interacting with other messages/types. 
pluginlib::ClassLoader< T > plugin_loader_
bool switchPluginService(nav_2d_msgs::SwitchPlugin::Request &req, nav_2d_msgs::SwitchPlugin::Response &resp)
ROS Interface for Switching Plugins. 
ros::NodeHandle private_nh_
ros::Publisher current_plugin_pub_
An organizer for switching between multiple different plugins of the same type. 
T & getCurrentPlugin()
Get the Current Plugin. 
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
T & getPlugin(const std::string &name)
Get the Specified Plugin. 
bool usePlugin(const std::string &name)
C++ Interface for switching to a given plugin. 
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const 
std::string getCurrentPluginName() const 
Get the Current Plugin Name. 
PluginMux(const std::string &plugin_package, const std::string &plugin_class, const std::string ¶meter_name, const std::string &default_value, const std::string &ros_name="current_plugin", const std::string &switch_service_name="switch_plugin")
Main Constructor - Loads plugin(s) and sets up ROS interfaces. 
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void setSwitchCallback(SwitchCallback switch_callback)
Set the callback fired when the plugin switches. 
bool getParam(const std::string &key, std::string &s) const 
ros::ServiceServer switch_plugin_srv_
#define ROS_FATAL_NAMED(name,...)
std::string current_plugin_
std::map< std::string, boost::shared_ptr< T > > plugins_
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const 
SwitchCallback switch_callback_
std::function< void(const std::string &, const std::string &)> SwitchCallback
alias for the function-type of the callback fired when the plugin switches. 
std::vector< std::string > getPluginNames() const 
Get the current list of plugin names.