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>
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, boost::shared_ptr< bond::Bond > bond=boost::shared_ptr< bond::Bond >((bond::Bond *) NULL)) |
Loader (ros::NodeHandle server_nh) | |
Construct the nodelet loader with optional ros API in namespace of passed NodeHandle. | |
Loader (bool provide_ros_api=true) | |
Construct the nodelet loader with optional ros API at defautl location of NodeHandle("~"). | |
bool | unload (const std::string &name) |
~Loader () | |
Private Types | |
typedef boost::shared_ptr < pluginlib::ClassLoader < Nodelet > > | ClassLoaderPtr |
typedef std::map< std::string, NodeletPtr > | M_stringToNodelet |
Private Member Functions | |
void | constructorImplementation (bool provide_ros_api, ros::NodeHandle server_nh) |
Private Attributes | |
detail::CallbackQueueManagerPtr | callback_manager_ |
ClassLoaderPtr | loader_ |
boost::mutex | lock_ |
! A lock to protect internal integrity. Every external method should lock it for safety. | |
M_stringToNodelet | nodelets_ |
! A map of name to pointers of currently constructed nodelets | |
detail::LoaderROSPtr | services_ |
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.
Definition at line 74 of file loader.h.
typedef boost::shared_ptr<pluginlib::ClassLoader<Nodelet> > nodelet::Loader::ClassLoaderPtr [private] |
typedef std::map<std::string, NodeletPtr> nodelet::Loader::M_stringToNodelet [private] |
nodelet::Loader::Loader | ( | bool | provide_ros_api = true |
) |
Construct the nodelet loader with optional ros API at defautl location of NodeHandle("~").
Definition at line 116 of file loader.cpp.
nodelet::Loader::Loader | ( | ros::NodeHandle | server_nh | ) |
Construct the nodelet loader with optional ros API in namespace of passed NodeHandle.
Definition at line 122 of file loader.cpp.
nodelet::Loader::~Loader | ( | ) |
Definition at line 152 of file loader.cpp.
bool nodelet::Loader::clear | ( | ) |
Clear all nodelets from this loader.
Clear all nodelets from this chain.
Definition at line 210 of file loader.cpp.
void nodelet::Loader::constructorImplementation | ( | bool | provide_ros_api, | |
ros::NodeHandle | server_nh | |||
) | [private] |
Definition at line 128 of file loader.cpp.
std::vector< std::string > nodelet::Loader::listLoadedNodelets | ( | ) |
List the names of all loaded nodelets.
Definition at line 218 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, | |||
boost::shared_ptr< bond::Bond > | bond = boost::shared_ptr< bond::Bond >((bond::Bond *) NULL) | |||
) |
bool nodelet::Loader::unload | ( | const std::string & | name | ) |
Definition at line 195 of file loader.cpp.
ClassLoaderPtr nodelet::Loader::loader_ [private] |
boost::mutex nodelet::Loader::lock_ [private] |
M_stringToNodelet nodelet::Loader::nodelets_ [private] |