Public Types | Public Member Functions | Private Member Functions | Private Attributes | List of all members
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]

Public Types

typedef actionlib::ServerGoalHandle< ActionSpec > GoalHandle
 
- Public Types inherited from actionlib::ActionServerBase< ActionSpec >
typedef 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. More...
 
const std::string getName () const
 Get the name. More...
 
virtual void initialize ()
 Set up status publishing timers. More...
 
virtual void publishFeedback (const actionlib_msgs::GoalStatus &status, const Feedback &feedback)
 Publishes feedback for a given goal. More...
 
virtual void publishResult (const actionlib_msgs::GoalStatus &status, const Result &result)
 Publishes a result for a given goal. More...
 
virtual void publishStatus ()
 Explicitly publish status. More...
 
bool ready ()
 Check if the server is ready to be started. More...
 
void registerCancelOperation (RTT::OperationInterfacePart *operation)
 
void registerGoalOperation (RTT::OperationInterfacePart *operation)
 
 RTTActionServer (const double status_period=0.200, const int sched=ORO_SCHED_OTHER)
 Constructor. More...
 
 RTTActionServer (const std::string name, const double status_period=0.200, const int sched=ORO_SCHED_OTHER)
 
void shutdown ()
 Shutdown internal timer. More...
 
virtual ~RTTActionServer ()
 
- Public Member Functions inherited from actionlib::ActionServerBase< ActionSpec >
 ActionServerBase (boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb, bool auto_start=false)
 
void cancelCallback (const boost::shared_ptr< const actionlib_msgs::GoalID > &goal_id)
 
void goalCallback (const boost::shared_ptr< const ActionGoal > &goal)
 
void registerCancelCallback (boost::function< void(GoalHandle)> cb)
 
void registerGoalCallback (boost::function< void(GoalHandle)> cb)
 
void start ()
 
virtual ~ActionServerBase ()
 

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. More...
 
RTT::OperationCaller< void(GoalHandle)> cancel_operation_
 
RTT::OperationCaller< void(GoalHandle)> goal_operation_
 
std::string name_
 Server name (used for naming timers and other resources) More...
 
double status_period_
 Period (Hz) at which the status should be published. More...
 
RTTActionServerStatusTimer< ActionSpec > status_timer_
 RTT Timer for periodic status updates. More...
 

Additional Inherited Members

- Protected Attributes inherited from actionlib::ActionServerBase< ActionSpec >
boost::function< void(GoalHandle)> cancel_callback_
 
boost::function< void(GoalHandle)> goal_callback_
 
boost::shared_ptr< DestructionGuardguard_
 
GoalIDGenerator id_generator_
 
ros::Time last_cancel_
 
boost::recursive_mutex lock_
 
bool started_
 
std::list< StatusTracker< ActionSpec > > status_list_
 
ros::Duration status_list_timeout_
 

Detailed Description

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

Orocos RTT-Based Action Server.

Definition at line 21 of file rtt_action_server.h.

Member Typedef Documentation

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

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 131 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 140 of file rtt_action_server.h.

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

Definition at line 150 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 181 of file rtt_action_server.h.

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

Definition at line 247 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 227 of file rtt_action_server.h.

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

Definition at line 239 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 156 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 282 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 259 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 303 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 169 of file rtt_action_server.h.

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

Definition at line 93 of file rtt_action_server.h.

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

Definition at line 88 of file rtt_action_server.h.

template<class ActionSpec >
void rtt_actionlib::RTTActionServer< ActionSpec >::shutdown ( )

Shutdown internal timer.

Definition at line 175 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 121 of file rtt_action_server.h.

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

Definition at line 127 of file rtt_action_server.h.

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

Definition at line 126 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 115 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 118 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 124 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 May 10 2021 02:45:37