Orocos RTT-Based Action Server. More...
#include <rtt_action_server.h>
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) | |
virtual | ~RTTActionServer () |
Public Member Functions inherited from actionlib::ActionServerBase< ActionSpec > | |
ACTION_DEFINITION (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< DestructionGuard > | guard_ |
GoalIDGenerator | id_generator_ |
ros::Time | last_cancel_ |
boost::recursive_mutex | lock_ |
bool | started_ |
std::list< StatusTracker< ActionSpec > > | status_list_ |
ros::Duration | status_list_timeout_ |
Orocos RTT-Based Action Server.
Definition at line 21 of file rtt_action_server.h.
typedef actionlib::ServerGoalHandle<ActionSpec> rtt_actionlib::RTTActionServer< ActionSpec >::GoalHandle |
Definition at line 55 of file rtt_action_server.h.
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.
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.
|
virtual |
Definition at line 147 of file rtt_action_server.h.
rtt_actionlib::RTTActionServer< ActionSpec >::ACTION_DEFINITION | ( | 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.
|
private |
Definition at line 238 of file rtt_action_server.h.
|
inline |
Get the name.
Definition at line 63 of file rtt_action_server.h.
|
private |
Definition at line 218 of file rtt_action_server.h.
|
private |
Definition at line 230 of file rtt_action_server.h.
|
virtual |
Set up status publishing timers.
Implements actionlib::ActionServerBase< ActionSpec >.
Definition at line 153 of file rtt_action_server.h.
|
virtual |
Publishes feedback for a given goal.
Implements actionlib::ActionServerBase< ActionSpec >.
Definition at line 273 of file rtt_action_server.h.
|
virtual |
Publishes a result for a given goal.
Implements actionlib::ActionServerBase< ActionSpec >.
Definition at line 250 of file rtt_action_server.h.
|
virtual |
Explicitly publish status.
Implements actionlib::ActionServerBase< ActionSpec >.
Definition at line 294 of file rtt_action_server.h.
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.
|
inline |
Definition at line 90 of file rtt_action_server.h.
|
inline |
Definition at line 85 of file rtt_action_server.h.
|
private |
Action bridge container for RTT ports corresponding to the action interface.
Definition at line 118 of file rtt_action_server.h.
|
private |
Definition at line 124 of file rtt_action_server.h.
|
private |
Definition at line 123 of file rtt_action_server.h.
|
private |
Server name (used for naming timers and other resources)
Definition at line 112 of file rtt_action_server.h.
|
private |
Period (Hz) at which the status should be published.
Definition at line 115 of file rtt_action_server.h.
|
private |
RTT Timer for periodic status updates.
Definition at line 121 of file rtt_action_server.h.