A class which will construct and sequentially call Nodelets according to xml This is the primary way in which users are expected to interact with Nodelets. More...
#include <loader.h>
Classes | |
| struct | Impl |
Public Member Functions | |
| bool | clear () |
| Clear all nodelets from this loader. More... | |
| std::vector< std::string > | listLoadedNodelets () |
| List the names of all loaded nodelets. More... | |
| bool | load (const std::string &name, const std::string &type, const M_string &remappings, const V_string &my_argv) |
| Load a nodelet. More... | |
| Loader (bool provide_ros_api=true) | |
| Construct the nodelet loader with optional ros API at default location of NodeHandle("~") More... | |
| Loader (const boost::function< boost::shared_ptr< Nodelet >(const std::string &lookup_name)> &create_instance) | |
| Construct the nodelet loader without ros API, using non-standard factory function to create nodelet instances. More... | |
| Loader (const ros::NodeHandle &server_nh) | |
| Construct the nodelet loader with optional ros API in namespace of passed NodeHandle. More... | |
| bool | unload (const std::string &name) |
| Unload a nodelet. More... | |
| ~Loader () | |
Private Attributes | |
| boost::scoped_ptr< Impl > | impl_ |
| boost::mutex | lock_ |
| ! Public methods must lock this to preserve internal integrity. More... | |
A class which will construct and sequentially call Nodelets according to xml This is the primary way in which users are expected to interact with Nodelets.
| nodelet::Loader::Loader | ( | bool | provide_ros_api = true | ) |
Construct the nodelet loader with optional ros API at default location of NodeHandle("~")
Definition at line 240 of file loader.cpp.
| nodelet::Loader::Loader | ( | const ros::NodeHandle & | server_nh | ) |
Construct the nodelet loader with optional ros API in namespace of passed NodeHandle.
Definition at line 249 of file loader.cpp.
| nodelet::Loader::Loader | ( | const boost::function< boost::shared_ptr< Nodelet >(const std::string &lookup_name)> & | create_instance | ) |
Construct the nodelet loader without ros API, using non-standard factory function to create nodelet instances.
Definition at line 255 of file loader.cpp.
| nodelet::Loader::~Loader | ( | ) |
Definition at line 261 of file loader.cpp.
| bool nodelet::Loader::clear | ( | ) |
Clear all nodelets from this loader.
Definition at line 345 of file loader.cpp.
| std::vector< std::string > nodelet::Loader::listLoadedNodelets | ( | ) |
List the names of all loaded nodelets.
Definition at line 352 of file loader.cpp.
| bool nodelet::Loader::load | ( | const std::string & | name, |
| const std::string & | type, | ||
| const M_string & | remappings, | ||
| const V_string & | my_argv | ||
| ) |
Load a nodelet.
Definition at line 265 of file loader.cpp.
| bool nodelet::Loader::unload | ( | const std::string & | name | ) |
Unload a nodelet.
Definition at line 331 of file loader.cpp.
|
private |