void add_plugin(std::string pl_name) { boost::shared_ptr<mavplugin::MavRosPlugin> plugin; try { plugin = plugin_loader.createInstance(pl_name); plugin->initialize(mav_uas, node_handle, diag_updater); loaded_plugins.push_back(plugin); std::string repr_name = plugin->get_name(); ROS_INFO_STREAM("Plugin " << repr_name << " [alias " << pl_name << "] loaded and initialized"); std::vector<uint8_t> sup_msgs = plugin->get_supported_messages(); for (auto it = sup_msgs.begin(); it != sup_msgs.end(); ++it) { ROS_DEBUG("Route msgid %d to %s", *it, repr_name.c_str()); message_route_table[*it].connect( boost::bind(&MavRosPlugin::message_rx_cb, plugin.get(), _1, _2, _3)); } } catch (pluginlib::PluginlibException& ex) { ROS_ERROR_STREAM("Plugin load exception: " << ex.what()); } }
bool createHelper(string class_type, Classifier* &c) { try{ c = c_loader.createClassInstance(class_type); } catch(pluginlib::PluginlibException& ex){ ROS_ERROR("Classifer plugin failed to load! Error: %s", ex.what()); } return true; }
RefineAlgorithm* RefineAlgorithm::RefineAlgFactory(XMLTag* tag) { std::string name = tag->GetName(); RefineAlgorithm* alg = NULL; try { alg = s_ref_alg_loader.createClassInstance(name); alg->SetData(tag); } catch(pluginlib::PluginlibException& ex) { //handle the class failing to load printf("RefineAlgorithm: The plugin failed to load for some reason. Error: %s\n", ex.what()); printf("RefineAlgorithm: Tag failed: %s\n", tag->GetName().c_str()); } return alg; }