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. | |
std::vector< std::string > | listLoadedNodelets () |
List the names of all loaded nodelets. | |
bool | load (const std::string &name, const std::string &type, const M_string &remappings, const V_string &my_argv) |
Load a nodelet. | |
Loader (bool provide_ros_api=true) | |
Construct the nodelet loader with optional ros API at default location of NodeHandle("~") | |
Loader (const ros::NodeHandle &server_nh) | |
Construct the nodelet loader with optional ros API in namespace of passed NodeHandle. | |
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. | |
bool | unload (const std::string &name) |
Unload a nodelet. | |
~Loader () | |
Private Attributes | |
boost::scoped_ptr< Impl > | impl_ |
boost::mutex | lock_ |
! Public methods must lock this to preserve internal integrity. |
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 218 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 227 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 233 of file loader.cpp.
Definition at line 239 of file loader.cpp.
bool nodelet::Loader::clear | ( | ) |
Clear all nodelets from this loader.
Definition at line 290 of file loader.cpp.
std::vector< std::string > nodelet::Loader::listLoadedNodelets | ( | ) |
List the names of all loaded nodelets.
Definition at line 297 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 243 of file loader.cpp.
bool nodelet::Loader::unload | ( | const std::string & | name | ) |
Unload a nodelet.
Definition at line 276 of file loader.cpp.
boost::scoped_ptr<Impl> nodelet::Loader::impl_ [private] |
boost::mutex nodelet::Loader::lock_ [private] |