Public Types | Public Member Functions | Private Member Functions | Private Attributes
rtt_actionlib::RTTActionServer< ActionSpec > Class Template Reference

Orocos RTT-Based Action Server. More...

#include <rtt_action_server.h>

Inheritance diagram for rtt_actionlib::RTTActionServer< ActionSpec >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef
actionlib::ServerGoalHandle
< ActionSpec > 
GoalHandle

Public Member Functions

 ACTION_DEFINITION (ActionSpec)
bool addPorts (RTT::Service::shared_ptr service, const bool create_topics=false, const std::string &topic_namespace="")
 Add actionlib ports to a given rtt service.
const std::string getName () const
 Get the name.
virtual void initialize ()
 Set up status publishing timers.
virtual void publishFeedback (const actionlib_msgs::GoalStatus &status, const Feedback &feedback)
 Publishes feedback for a given goal.
virtual void publishResult (const actionlib_msgs::GoalStatus &status, const Result &result)
 Publishes a result for a given goal.
virtual void publishStatus ()
 Explicitly publish status.
bool ready ()
 Check if the server is ready to be started.
void registerCancelOperation (RTT::OperationInterfacePart *operation)
void registerGoalOperation (RTT::OperationInterfacePart *operation)
 RTTActionServer (const double status_period=0.200, const int sched=ORO_SCHED_OTHER)
 Constructor.
 RTTActionServer (const std::string name, const double status_period=0.200, const int sched=ORO_SCHED_OTHER)
virtual ~RTTActionServer ()

Private Member Functions

void cancelCallback (RTT::base::PortInterface *port)
void goalCallback (RTT::base::PortInterface *port)
void goalCallbackWrapper (GoalHandle gh)

Private Attributes

rtt_actionlib::ActionBridge action_bridge_
 Action bridge container for RTT ports corresponding to the action interface.
RTT::OperationCaller< void(GoalHandle)> cancel_operation_
RTT::OperationCaller< void(GoalHandle)> goal_operation_
std::string name_
 Server name (used for naming timers and other resources)
double status_period_
 Period (Hz) at which the status should be published.
RTTActionServerStatusTimer
< ActionSpec > 
status_timer_
 RTT Timer for periodic status updates.

Detailed Description

template<class ActionSpec>
class rtt_actionlib::RTTActionServer< ActionSpec >

Orocos RTT-Based Action Server.

Definition at line 49 of file rtt_action_server.h.


Member Typedef Documentation

template<class ActionSpec>
typedef actionlib::ServerGoalHandle<ActionSpec> rtt_actionlib::RTTActionServer< ActionSpec >::GoalHandle

Reimplemented from actionlib::ActionServerBase< ActionSpec >.

Definition at line 55 of file rtt_action_server.h.


Constructor & Destructor Documentation

template<class ActionSpec >
rtt_actionlib::RTTActionServer< ActionSpec >::RTTActionServer ( const double  status_period = 0.200,
const int  sched = ORO_SCHED_OTHER 
)

Constructor.

Definition at line 128 of file rtt_action_server.h.

template<class ActionSpec >
rtt_actionlib::RTTActionServer< ActionSpec >::RTTActionServer ( const std::string  name,
const double  status_period = 0.200,
const int  sched = ORO_SCHED_OTHER 
)

Definition at line 137 of file rtt_action_server.h.

template<class ActionSpec >
rtt_actionlib::RTTActionServer< ActionSpec >::~RTTActionServer ( ) [virtual]

Definition at line 147 of file rtt_action_server.h.


Member Function Documentation

template<class ActionSpec>
rtt_actionlib::RTTActionServer< ActionSpec >::ACTION_DEFINITION ( ActionSpec  )
template<class ActionSpec >
bool rtt_actionlib::RTTActionServer< ActionSpec >::addPorts ( RTT::Service::shared_ptr  service,
const bool  create_topics = false,
const std::string &  topic_namespace = "" 
)

Add actionlib ports to a given rtt service.

Definition at line 172 of file rtt_action_server.h.

template<class ActionSpec >
void rtt_actionlib::RTTActionServer< ActionSpec >::cancelCallback ( RTT::base::PortInterface port) [private]

Definition at line 238 of file rtt_action_server.h.

template<class ActionSpec>
const std::string rtt_actionlib::RTTActionServer< ActionSpec >::getName ( ) const [inline]

Get the name.

Definition at line 63 of file rtt_action_server.h.

template<class ActionSpec >
void rtt_actionlib::RTTActionServer< ActionSpec >::goalCallback ( RTT::base::PortInterface port) [private]

Definition at line 218 of file rtt_action_server.h.

template<class ActionSpec >
void rtt_actionlib::RTTActionServer< ActionSpec >::goalCallbackWrapper ( GoalHandle  gh) [private]

Definition at line 230 of file rtt_action_server.h.

template<class ActionSpec >
void rtt_actionlib::RTTActionServer< ActionSpec >::initialize ( ) [virtual]

Set up status publishing timers.

Implements actionlib::ActionServerBase< ActionSpec >.

Definition at line 153 of file rtt_action_server.h.

template<class ActionSpec >
void rtt_actionlib::RTTActionServer< ActionSpec >::publishFeedback ( const actionlib_msgs::GoalStatus &  status,
const Feedback &  feedback 
) [virtual]

Publishes feedback for a given goal.

Implements actionlib::ActionServerBase< ActionSpec >.

Definition at line 273 of file rtt_action_server.h.

template<class ActionSpec >
void rtt_actionlib::RTTActionServer< ActionSpec >::publishResult ( const actionlib_msgs::GoalStatus &  status,
const Result &  result 
) [virtual]

Publishes a result for a given goal.

Implements actionlib::ActionServerBase< ActionSpec >.

Definition at line 250 of file rtt_action_server.h.

template<class ActionSpec >
void rtt_actionlib::RTTActionServer< ActionSpec >::publishStatus ( ) [virtual]

Explicitly publish status.

Implements actionlib::ActionServerBase< ActionSpec >.

Definition at line 294 of file rtt_action_server.h.

template<class ActionSpec >
bool rtt_actionlib::RTTActionServer< ActionSpec >::ready ( void  )

Check if the server is ready to be started.

Definition at line 166 of file rtt_action_server.h.

template<class ActionSpec>
void rtt_actionlib::RTTActionServer< ActionSpec >::registerCancelOperation ( RTT::OperationInterfacePart operation) [inline]

Definition at line 90 of file rtt_action_server.h.

template<class ActionSpec>
void rtt_actionlib::RTTActionServer< ActionSpec >::registerGoalOperation ( RTT::OperationInterfacePart operation) [inline]

Definition at line 85 of file rtt_action_server.h.


Member Data Documentation

template<class ActionSpec>
rtt_actionlib::ActionBridge rtt_actionlib::RTTActionServer< ActionSpec >::action_bridge_ [private]

Action bridge container for RTT ports corresponding to the action interface.

Definition at line 118 of file rtt_action_server.h.

template<class ActionSpec>
RTT::OperationCaller<void(GoalHandle)> rtt_actionlib::RTTActionServer< ActionSpec >::cancel_operation_ [private]

Definition at line 124 of file rtt_action_server.h.

template<class ActionSpec>
RTT::OperationCaller<void(GoalHandle)> rtt_actionlib::RTTActionServer< ActionSpec >::goal_operation_ [private]

Definition at line 123 of file rtt_action_server.h.

template<class ActionSpec>
std::string rtt_actionlib::RTTActionServer< ActionSpec >::name_ [private]

Server name (used for naming timers and other resources)

Definition at line 112 of file rtt_action_server.h.

template<class ActionSpec>
double rtt_actionlib::RTTActionServer< ActionSpec >::status_period_ [private]

Period (Hz) at which the status should be published.

Definition at line 115 of file rtt_action_server.h.

template<class ActionSpec>
RTTActionServerStatusTimer<ActionSpec> rtt_actionlib::RTTActionServer< ActionSpec >::status_timer_ [private]

RTT Timer for periodic status updates.

Definition at line 121 of file rtt_action_server.h.


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


rtt_actionlib
Author(s): Jonathan Bohren
autogenerated on Mon Apr 3 2017 03:35:31