Public Member Functions | Private Types | Private Attributes
object_manipulator::MultiArmActionWrapper< ActionDataType > Class Template Reference

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

#include <service_action_wrappers.h>

List of all members.

Public Member Functions

actionlib::SimpleActionClient
< ActionDataType > & 
client (std::string arm_name, ros::Duration timeout=ros::Duration(5.0))
 Returns a action client for the requested arm.
 MultiArmActionWrapper (std::string prefix, std::string suffix, bool spin_thread, bool resolve_names)
 Sets the node handle, prefix and suffix.
void setInterruptFunction (boost::function< bool()> f)
 Sets the interrupt function.
bool waitForResult (std::string arm_name, const ros::Duration &timeout=ros::Duration(0, 0))
 The action client for the requested arm waits for result.
 ~MultiArmActionWrapper ()

Private Types

typedef std::map< std::string,
actionlib::SimpleActionClient
< ActionDataType > * > 
map_type

Private Attributes

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

Detailed Description

template<class ActionDataType>
class object_manipulator::MultiArmActionWrapper< ActionDataType >

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

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

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

For each arm, it also performs "wait on first use". When the action for a given arm name is first requested, it will wait for the action, 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 343 of file service_action_wrappers.h.


Member Typedef Documentation

template<class ActionDataType>
typedef std::map<std::string, actionlib::SimpleActionClient<ActionDataType>* > object_manipulator::MultiArmActionWrapper< ActionDataType >::map_type [private]

It seems the SimpleActionClient is non-copyable, so I could not store them directly in the map.

Definition at line 359 of file service_action_wrappers.h.


Constructor & Destructor Documentation

template<class ActionDataType>
object_manipulator::MultiArmActionWrapper< ActionDataType >::MultiArmActionWrapper ( std::string  prefix,
std::string  suffix,
bool  spin_thread,
bool  resolve_names 
) [inline]

Sets the node handle, prefix and suffix.

Definition at line 373 of file service_action_wrappers.h.

template<class ActionDataType>
object_manipulator::MultiArmActionWrapper< ActionDataType >::~MultiArmActionWrapper ( ) [inline]

Definition at line 380 of file service_action_wrappers.h.


Member Function Documentation

template<class ActionDataType>
actionlib::SimpleActionClient<ActionDataType>& object_manipulator::MultiArmActionWrapper< ActionDataType >::client ( std::string  arm_name,
ros::Duration  timeout = ros::Duration(5.0) 
) [inline]

Returns a action client for the requested arm.

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

Definition at line 393 of file service_action_wrappers.h.

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

Sets the interrupt function.

Definition at line 378 of file service_action_wrappers.h.

template<class ActionDataType>
bool object_manipulator::MultiArmActionWrapper< ActionDataType >::waitForResult ( std::string  arm_name,
const ros::Duration timeout = ros::Duration(0,0) 
) [inline]

The action client for the requested arm waits for result.

Definition at line 438 of file service_action_wrappers.h.


Member Data Documentation

template<class ActionDataType>
map_type object_manipulator::MultiArmActionWrapper< ActionDataType >::clients_ [private]

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

Definition at line 362 of file service_action_wrappers.h.

template<class ActionDataType>
boost::function<bool()> object_manipulator::MultiArmActionWrapper< ActionDataType >::interrupt_function_ [private]

Function used to check for interrupts.

Definition at line 369 of file service_action_wrappers.h.

template<class ActionDataType>
ros::NodeHandle object_manipulator::MultiArmActionWrapper< ActionDataType >::nh_ [private]

The node handle used to create actions.

Definition at line 347 of file service_action_wrappers.h.

template<class ActionDataType>
std::string object_manipulator::MultiArmActionWrapper< ActionDataType >::prefix_ [private]

Prefix attached to arm name to get action name.

Definition at line 350 of file service_action_wrappers.h.

template<class ActionDataType>
bool object_manipulator::MultiArmActionWrapper< ActionDataType >::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 366 of file service_action_wrappers.h.

template<class ActionDataType>
bool object_manipulator::MultiArmActionWrapper< ActionDataType >::spin_thread_ [private]

Parameter to be passed on to the action client.

Definition at line 356 of file service_action_wrappers.h.

template<class ActionDataType>
std::string object_manipulator::MultiArmActionWrapper< ActionDataType >::suffix_ [private]

Suffix attached to arm name to get action name.

Definition at line 353 of file service_action_wrappers.h.


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


object_manipulator
Author(s): Matei Ciocarlie and Kaijen Hsiao
autogenerated on Mon Oct 6 2014 02:59:51