$search

object_manipulator::MultiArmServiceWrapper< ServiceDataType > Class Template Reference

A wrapper for multiple instances of a given service, one for each arm in the system. More...

#include <service_action_wrappers.h>

List of all members.

Public Member Functions

ros::ServiceClientclient (std::string arm_name, ros::Duration timeout=ros::Duration(5.0))
 Returns a service client for the requested arm.
 MultiArmServiceWrapper (std::string prefix, std::string suffix, bool resolve_names)
 Sets the node handle, prefix and suffix.
void setInterruptFunction (boost::function< bool()> f)
 Sets the interrupt function.

Private Types

typedef std::map< std::string,
ros::ServiceClient
map_type

Private Attributes

map_type clients_
 The list of clients already created, mapped to service names.
boost::function< bool()> interrupt_function_
 Function used to check for interrupts.
ros::NodeHandle nh_
 The node handle used to create services.
std::string prefix_
 Prefix attached to arm name to get service name.
bool resolve_names_
 Whether the resulting name should first be resolved using the node handle.
std::string suffix_
 Suffix attached to arm name to get service name.

Detailed Description

template<class ServiceDataType>
class object_manipulator::MultiArmServiceWrapper< ServiceDataType >

A wrapper for multiple instances of a given service, one for each arm in the system.

This function performs mapping from an arm_name to a service for that arm.

It obtains the name of the service by adding a prefix and/or suffix to the name of the arm.

For each arm, it also performs "wait on first use service". When the service for a given arm name is first requested, it will wait for the service, then create the client and return it. It will also remember the client, so that on subsequent calls the client is returned directly without additional waiting.

Definition at line 111 of file service_action_wrappers.h.


Member Typedef Documentation

template<class ServiceDataType>
typedef std::map<std::string, ros::ServiceClient> object_manipulator::MultiArmServiceWrapper< ServiceDataType >::map_type [private]

Definition at line 121 of file service_action_wrappers.h.


Constructor & Destructor Documentation

template<class ServiceDataType>
object_manipulator::MultiArmServiceWrapper< ServiceDataType >::MultiArmServiceWrapper ( std::string  prefix,
std::string  suffix,
bool  resolve_names 
) [inline]

Sets the node handle, prefix and suffix.

Definition at line 134 of file service_action_wrappers.h.


Member Function Documentation

template<class ServiceDataType>
ros::ServiceClient& object_manipulator::MultiArmServiceWrapper< ServiceDataType >::client ( std::string  arm_name,
ros::Duration  timeout = ros::Duration(5.0) 
) [inline]

Returns a service client for the requested arm.

Service name is obtained as prefix + arm_name + suffix. On first request for a given arm, a service client will be initialized, and the service will be waited for. On subsequent calls for the same arm, the service is returned directly.

Definition at line 146 of file service_action_wrappers.h.

template<class ServiceDataType>
void object_manipulator::MultiArmServiceWrapper< ServiceDataType >::setInterruptFunction ( boost::function< bool()>  f  )  [inline]

Sets the interrupt function.

Definition at line 139 of file service_action_wrappers.h.


Member Data Documentation

template<class ServiceDataType>
map_type object_manipulator::MultiArmServiceWrapper< ServiceDataType >::clients_ [private]

The list of clients already created, mapped to service names.

Definition at line 124 of file service_action_wrappers.h.

template<class ServiceDataType>
boost::function<bool()> object_manipulator::MultiArmServiceWrapper< ServiceDataType >::interrupt_function_ [private]

Function used to check for interrupts.

Definition at line 130 of file service_action_wrappers.h.

template<class ServiceDataType>
ros::NodeHandle object_manipulator::MultiArmServiceWrapper< ServiceDataType >::nh_ [private]

The node handle used to create services.

Definition at line 115 of file service_action_wrappers.h.

template<class ServiceDataType>
std::string object_manipulator::MultiArmServiceWrapper< ServiceDataType >::prefix_ [private]

Prefix attached to arm name to get service name.

Definition at line 117 of file service_action_wrappers.h.

template<class ServiceDataType>
bool object_manipulator::MultiArmServiceWrapper< ServiceDataType >::resolve_names_ [private]

Whether the resulting name should first be resolved using the node handle.

Use this if you are remapping service names.

Definition at line 127 of file service_action_wrappers.h.

template<class ServiceDataType>
std::string object_manipulator::MultiArmServiceWrapper< ServiceDataType >::suffix_ [private]

Suffix attached to arm name to get service name.

Definition at line 119 of file service_action_wrappers.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


object_manipulator
Author(s): Matei Ciocarlie and Kaijen Hsiao
autogenerated on Fri Mar 1 18:35:38 2013