Public Member Functions | Protected Types | Protected Member Functions | Protected Attributes | List of all members
cras::LoaderROS Class Reference

ROS interface for loading/unloading nodelets (internally using nodelet::Loader to do the work). More...

#include <loader_ros.h>

Public Member Functions

 LoaderROS (::nodelet::Loader *parent, const ::ros::NodeHandle &nh)
 Construct the ROS interface for the given loader. More...
 

Protected Types

typedef ::boost::ptr_map<::std::string, ::bond::BondM_stringToBond
 Type of the map of nodelet name->bond. More...
 

Protected Member Functions

bool serviceList (::nodelet::NodeletList::Request &req, ::nodelet::NodeletList::Response &res)
 List all loaded nodelets. More...
 
bool serviceLoad (::nodelet::NodeletLoad::Request &req, ::nodelet::NodeletLoad::Response &res)
 Load a nodelet. More...
 
bool serviceUnload (::nodelet::NodeletUnload::Request &req, ::nodelet::NodeletUnload::Response &res)
 Unload a nodelet. More...
 
bool unload (const ::std::string &name)
 Unload a nodelet of the given name. More...
 

Protected Attributes

::ros::CallbackQueue bond_callback_queue_
 Callback queue used for the created bonds. More...
 
M_stringToBond bond_map_
 Map of nodelet name->bond. More...
 
::ros::AsyncSpinner bond_spinner_
 Spinner of bond_callback_queue_. More...
 
::ros::ServiceServer list_server_
 Service server for list service. More...
 
::ros::ServiceServer load_server_
 Service server for load_nodelet service. More...
 
::boost::mutex lock_
 Lock protecting access to parent_ and bond_map_. More...
 
::ros::NodeHandle nh_
 The node handle to use for the advertised services. More...
 
::nodelet::Loaderparent_
 The actual nodelet loader to use. More...
 
::ros::ServiceServer unload_server_
 Service server for unload_nodelet service. More...
 

Detailed Description

ROS interface for loading/unloading nodelets (internally using nodelet::Loader to do the work).

Advertised services are:

Definition at line 64 of file loader_ros.h.

Member Typedef Documentation

◆ M_stringToBond

typedef ::boost::ptr_map<::std::string, ::bond::Bond> cras::LoaderROS::M_stringToBond
protected

Type of the map of nodelet name->bond.

Definition at line 131 of file loader_ros.h.

Constructor & Destructor Documentation

◆ LoaderROS()

cras::LoaderROS::LoaderROS ( ::nodelet::Loader parent,
const ::ros::NodeHandle nh 
)

Construct the ROS interface for the given loader.

Parameters
[in]parentThe loader to use for the actual nodelet loading/unloading.
[in]nhThe node handle to use for the advertised services.

Member Function Documentation

◆ serviceList()

bool cras::LoaderROS::serviceList ( ::nodelet::NodeletList::Request &  req,
::nodelet::NodeletList::Response &  res 
)
protected

List all loaded nodelets.

Parameters
[in]reqUnused.
[out]resThe loaded nodelet names.
Returns
True.

◆ serviceLoad()

bool cras::LoaderROS::serviceLoad ( ::nodelet::NodeletLoad::Request &  req,
::nodelet::NodeletLoad::Response &  res 
)
protected

Load a nodelet.

Parameters
[in]reqParameters of the nodelet.
[out]resWhether the loading succeeded.
Returns
res.success.

◆ serviceUnload()

bool cras::LoaderROS::serviceUnload ( ::nodelet::NodeletUnload::Request &  req,
::nodelet::NodeletUnload::Response &  res 
)
protected

Unload a nodelet.

Parameters
[in]reqParameters of the nodelet.
[out]resWhether the unloading succeeded.
Returns
res.success.

◆ unload()

bool cras::LoaderROS::unload ( const ::std::string &  name)
protected

Unload a nodelet of the given name.

Parameters
[in]nameName of the nodelet to unload.
Returns
Whether the unloading succeeded.

Member Data Documentation

◆ bond_callback_queue_

::ros::CallbackQueue cras::LoaderROS::bond_callback_queue_
protected

Callback queue used for the created bonds.

Definition at line 125 of file loader_ros.h.

◆ bond_map_

M_stringToBond cras::LoaderROS::bond_map_
protected

Map of nodelet name->bond.

Definition at line 134 of file loader_ros.h.

◆ bond_spinner_

::ros::AsyncSpinner cras::LoaderROS::bond_spinner_
protected

Spinner of bond_callback_queue_.

Definition at line 128 of file loader_ros.h.

◆ list_server_

::ros::ServiceServer cras::LoaderROS::list_server_
protected

Service server for list service.

Definition at line 119 of file loader_ros.h.

◆ load_server_

::ros::ServiceServer cras::LoaderROS::load_server_
protected

Service server for load_nodelet service.

Definition at line 113 of file loader_ros.h.

◆ lock_

::boost::mutex cras::LoaderROS::lock_
protected

Lock protecting access to parent_ and bond_map_.

Definition at line 122 of file loader_ros.h.

◆ nh_

::ros::NodeHandle cras::LoaderROS::nh_
protected

The node handle to use for the advertised services.

Definition at line 110 of file loader_ros.h.

◆ parent_

::nodelet::Loader* cras::LoaderROS::parent_
protected

The actual nodelet loader to use.

Definition at line 107 of file loader_ros.h.

◆ unload_server_

::ros::ServiceServer cras::LoaderROS::unload_server_
protected

Service server for unload_nodelet service.

Definition at line 116 of file loader_ros.h.


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


cras_cpp_common
Author(s): Martin Pecka
autogenerated on Sat Jun 17 2023 02:32:53