Public Types | Public Member Functions | Static Public Member Functions
vigir_footstep_planning::SimpleActionServer< ActionSpec > Class Template Reference

#include <helper.h>

Inheritance diagram for vigir_footstep_planning::SimpleActionServer< ActionSpec >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const SimpleActionServer
< ActionSpec > > 
ConstPtr
typedef boost::function< void()> ExecuteCallback
typedef boost::function< void()> PreemptCallback
typedef boost::shared_ptr
< SimpleActionServer
< ActionSpec > > 
Ptr

Public Member Functions

template<typename S >
void finish (const S &result)
void preempt ()
 SimpleActionServer (ros::NodeHandle nh, std::string name, bool auto_start)

Static Public Member Functions

static Ptr create (ros::NodeHandle nh, std::string name, bool auto_start, ExecuteCallback execute_cb, PreemptCallback preempt_cb=PreemptCallback())

Detailed Description

template<typename ActionSpec>
class vigir_footstep_planning::SimpleActionServer< ActionSpec >

Definition at line 72 of file helper.h.


Member Typedef Documentation

template<typename ActionSpec >
typedef boost::shared_ptr<const SimpleActionServer<ActionSpec> > vigir_footstep_planning::SimpleActionServer< ActionSpec >::ConstPtr

Definition at line 78 of file helper.h.

template<typename ActionSpec >
typedef boost::function<void ()> vigir_footstep_planning::SimpleActionServer< ActionSpec >::ExecuteCallback

Reimplemented from actionlib::SimpleActionServer< ActionSpec >.

Definition at line 79 of file helper.h.

template<typename ActionSpec >
typedef boost::function<void ()> vigir_footstep_planning::SimpleActionServer< ActionSpec >::PreemptCallback

Definition at line 80 of file helper.h.

template<typename ActionSpec >
typedef boost::shared_ptr<SimpleActionServer<ActionSpec> > vigir_footstep_planning::SimpleActionServer< ActionSpec >::Ptr

Definition at line 77 of file helper.h.


Constructor & Destructor Documentation

template<typename ActionSpec >
vigir_footstep_planning::SimpleActionServer< ActionSpec >::SimpleActionServer ( ros::NodeHandle  nh,
std::string  name,
bool  auto_start 
) [inline]

Reimplemented from actionlib::SimpleActionServer< ActionSpec >.

Definition at line 82 of file helper.h.


Member Function Documentation

template<typename ActionSpec >
static Ptr vigir_footstep_planning::SimpleActionServer< ActionSpec >::create ( ros::NodeHandle  nh,
std::string  name,
bool  auto_start,
ExecuteCallback  execute_cb,
PreemptCallback  preempt_cb = PreemptCallback() 
) [inline, static]

Definition at line 100 of file helper.h.

template<typename ActionSpec >
template<typename S >
void vigir_footstep_planning::SimpleActionServer< ActionSpec >::finish ( const S &  result) [inline]

Definition at line 87 of file helper.h.

template<typename ActionSpec >
void vigir_footstep_planning::SimpleActionServer< ActionSpec >::preempt ( ) [inline]

Definition at line 95 of file helper.h.


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


vigir_footstep_planning_lib
Author(s): Alexander Stumpf
autogenerated on Sat Jun 8 2019 19:01:44