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

Wrapper class for SimpleActionClient that checks server availability on first use. More...

#include <service_action_wrappers.h>

List of all members.

Public Member Functions

 ActionWrapper (std::string action_name, bool spin_thread)
actionlib::SimpleActionClient
< ActionDataType > & 
client (ros::Duration timeout=ros::Duration(5.0))
bool isInitialized () const
void setInterruptFunction (boost::function< bool()> f)
 Sets the interrupt function.
bool waitForResult (const ros::Duration &timeout=ros::Duration(0, 0))

Private Attributes

std::string action_name_
 The name of the action.
actionlib::SimpleActionClient
< ActionDataType > 
client_
 The actual action client.
bool initialized_
 Has the service client been initialized or not.
boost::function< bool()> interrupt_function_
 Function used to check for interrupts.
ros::NodeHandle nh_
 The node handle to be used when initializing services.
std::string remapped_name_
 The remapped name/topic of the action.

Detailed Description

template<class ActionDataType>
class object_manipulator::ActionWrapper< ActionDataType >

Wrapper class for SimpleActionClient that checks server availability on first use.

Definition at line 200 of file service_action_wrappers.h.


Constructor & Destructor Documentation

template<class ActionDataType>
object_manipulator::ActionWrapper< ActionDataType >::ActionWrapper ( std::string  action_name,
bool  spin_thread 
) [inline]

Definition at line 216 of file service_action_wrappers.h.


Member Function Documentation

template<class ActionDataType>
actionlib::SimpleActionClient<ActionDataType>& object_manipulator::ActionWrapper< ActionDataType >::client ( ros::Duration  timeout = ros::Duration(5.0)) [inline]

Definition at line 225 of file service_action_wrappers.h.

template<class ActionDataType>
bool object_manipulator::ActionWrapper< ActionDataType >::isInitialized ( ) const [inline]

Definition at line 267 of file service_action_wrappers.h.

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

Sets the interrupt function.

Definition at line 223 of file service_action_wrappers.h.

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

Definition at line 249 of file service_action_wrappers.h.


Member Data Documentation

template<class ActionDataType>
std::string object_manipulator::ActionWrapper< ActionDataType >::action_name_ [private]

The name of the action.

Definition at line 206 of file service_action_wrappers.h.

template<class ActionDataType>
actionlib::SimpleActionClient<ActionDataType> object_manipulator::ActionWrapper< ActionDataType >::client_ [private]

The actual action client.

Definition at line 212 of file service_action_wrappers.h.

template<class ActionDataType>
bool object_manipulator::ActionWrapper< ActionDataType >::initialized_ [private]

Has the service client been initialized or not.

Definition at line 204 of file service_action_wrappers.h.

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

Function used to check for interrupts.

Definition at line 214 of file service_action_wrappers.h.

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

The node handle to be used when initializing services.

Definition at line 210 of file service_action_wrappers.h.

template<class ActionDataType>
std::string object_manipulator::ActionWrapper< ActionDataType >::remapped_name_ [private]

The remapped name/topic of the action.

Definition at line 208 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