Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
bwi_interruptable_action_server::InterruptableActionServer< ActionSpec > Class Template Reference

#include <interruptable_action_server.h>

List of all members.

Public Types

typedef
actionlib::ActionServer
< ActionSpec >::GoalHandle 
GoalHandle
typedef boost::function< void(const
GoalConstPtr &)> 
NewGoalCallback
typedef boost::function< void(const
ResultConstPtr &, const
actionlib::SimpleClientGoalState
&, int)> 
ResultCallback

Public Member Functions

 ACTION_DEFINITION (ActionSpec)
 InterruptableActionServer (ros::NodeHandle n, std::string name, int max_attempts=1, NewGoalCallback new_goal_callback=0, ResultCallback result_callback=0)
void spin ()
 ~InterruptableActionServer ()

Protected Member Functions

void cancelCallback (GoalHandle preempt)
void goalCallback (GoalHandle goal)
bool pause (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
void publishFeedback (const FeedbackConstPtr &feedback)
bool resume (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)

Protected Attributes

boost::shared_ptr
< actionlib::SimpleActionClient
< ActionSpec > > 
ac_
boost::shared_ptr
< actionlib::ActionServer
< ActionSpec > > 
as_
int current_attempts_
GoalHandle current_goal_
std::string interruptable_server_name_
boost::recursive_mutex lock_
int max_attempts_
ros::NodeHandle n_
NewGoalCallback new_goal_callback_
GoalHandle next_goal_
bool next_goal_available_
GoalHandle original_goal_
bool original_goal_available_
ros::ServiceServer pause_server_
bool pursue_current_goal_
bool pursuing_current_goal_
ResultCallback result_callback_
ros::ServiceServer resume_server_
bool switch_to_original_goal_

Detailed Description

template<class ActionSpec>
class bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >

Definition at line 47 of file interruptable_action_server.h.


Member Typedef Documentation

template<class ActionSpec>
typedef actionlib::ActionServer<ActionSpec>::GoalHandle bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::GoalHandle

Definition at line 52 of file interruptable_action_server.h.

template<class ActionSpec>
typedef boost::function<void(const GoalConstPtr&)> bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::NewGoalCallback

Definition at line 54 of file interruptable_action_server.h.

template<class ActionSpec>
typedef boost::function<void(const ResultConstPtr&, const actionlib::SimpleClientGoalState&, int)> bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::ResultCallback

Definition at line 53 of file interruptable_action_server.h.


Constructor & Destructor Documentation

template<class ActionSpec >
bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::InterruptableActionServer ( ros::NodeHandle  n,
std::string  name,
int  max_attempts = 1,
NewGoalCallback  new_goal_callback = 0,
ResultCallback  result_callback = 0 
)

Definition at line 41 of file interruptable_action_server_imp.h.

Definition at line 78 of file interruptable_action_server_imp.h.


Member Function Documentation

template<class ActionSpec>
bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::ACTION_DEFINITION ( ActionSpec  )
template<class ActionSpec >
void bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::cancelCallback ( GoalHandle  preempt) [protected]

Definition at line 148 of file interruptable_action_server_imp.h.

template<class ActionSpec >
void bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::goalCallback ( GoalHandle  goal) [protected]

Definition at line 125 of file interruptable_action_server_imp.h.

template<class ActionSpec >
bool bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::pause ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [protected]

Definition at line 93 of file interruptable_action_server_imp.h.

template<class ActionSpec >
void bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::publishFeedback ( const FeedbackConstPtr &  feedback) [protected]

Definition at line 264 of file interruptable_action_server_imp.h.

template<class ActionSpec >
bool bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::resume ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
) [protected]

Definition at line 111 of file interruptable_action_server_imp.h.

template<class ActionSpec >
void bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::spin ( )

Definition at line 169 of file interruptable_action_server_imp.h.


Member Data Documentation

template<class ActionSpec>
boost::shared_ptr<actionlib::SimpleActionClient<ActionSpec> > bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::ac_ [protected]

Definition at line 80 of file interruptable_action_server.h.

template<class ActionSpec>
boost::shared_ptr<actionlib::ActionServer<ActionSpec> > bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::as_ [protected]

Definition at line 79 of file interruptable_action_server.h.

template<class ActionSpec>
int bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::current_attempts_ [protected]

Definition at line 95 of file interruptable_action_server.h.

template<class ActionSpec>
GoalHandle bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::current_goal_ [protected]

Definition at line 86 of file interruptable_action_server.h.

template<class ActionSpec>
std::string bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::interruptable_server_name_ [protected]

Definition at line 84 of file interruptable_action_server.h.

template<class ActionSpec>
boost::recursive_mutex bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::lock_ [protected]

Definition at line 82 of file interruptable_action_server.h.

template<class ActionSpec>
int bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::max_attempts_ [protected]

Definition at line 94 of file interruptable_action_server.h.

template<class ActionSpec>
ros::NodeHandle bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::n_ [protected]

Definition at line 74 of file interruptable_action_server.h.

Definition at line 98 of file interruptable_action_server.h.

template<class ActionSpec>
GoalHandle bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::next_goal_ [protected]

Definition at line 86 of file interruptable_action_server.h.

template<class ActionSpec>
bool bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::next_goal_available_ [protected]

Definition at line 90 of file interruptable_action_server.h.

template<class ActionSpec>
GoalHandle bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::original_goal_ [protected]

Definition at line 86 of file interruptable_action_server.h.

template<class ActionSpec>
bool bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::original_goal_available_ [protected]

Definition at line 88 of file interruptable_action_server.h.

Definition at line 76 of file interruptable_action_server.h.

template<class ActionSpec>
bool bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::pursue_current_goal_ [protected]

Definition at line 91 of file interruptable_action_server.h.

template<class ActionSpec>
bool bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::pursuing_current_goal_ [protected]

Definition at line 92 of file interruptable_action_server.h.

Definition at line 96 of file interruptable_action_server.h.

Definition at line 77 of file interruptable_action_server.h.

template<class ActionSpec>
bool bwi_interruptable_action_server::InterruptableActionServer< ActionSpec >::switch_to_original_goal_ [protected]

Definition at line 89 of file interruptable_action_server.h.


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


bwi_interruptable_action_server
Author(s):
autogenerated on Thu Jun 6 2019 17:57:17