Classes | Public Member Functions | Private Attributes
nodelet::Loader Class Reference

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>

List of all members.

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< Implimpl_
boost::mutex lock_
 ! Public methods must lock this to preserve internal integrity.

Detailed Description

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 62 of file loader.h.


Constructor & Destructor Documentation

nodelet::Loader::Loader ( bool  provide_ros_api = true)

Construct the nodelet loader with optional ros API at default location of NodeHandle("~")

Todo:
Instance of ROS API-related constructors, just take #threads for the manager

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.

Definition at line 261 of file loader.cpp.


Member Function Documentation

Clear all nodelets from this loader.

Definition at line 351 of file loader.cpp.

std::vector< std::string > nodelet::Loader::listLoadedNodelets ( )

List the names of all loaded nodelets.

Definition at line 358 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 337 of file loader.cpp.


Member Data Documentation

boost::scoped_ptr<Impl> nodelet::Loader::impl_ [private]

Definition at line 92 of file loader.h.

boost::mutex nodelet::Loader::lock_ [private]

! Public methods must lock this to preserve internal integrity.

Definition at line 91 of file loader.h.


The documentation for this class was generated from the following files:


nodelet
Author(s): Tully Foote, Radu Bogdan Rusu
autogenerated on Sun Feb 17 2019 03:43:51