rtt_action_server.h
Go to the documentation of this file.
1 #ifndef __RTT_ACTION_SERVER_H
2 #define __RTT_ACTION_SERVER_H
3 
4 #include <rtt/RTT.hpp>
5 #include <rtt/os/Timer.hpp>
8 
11 
13 
15 #include <rtt_roscomm/rostopic.h>
16 
17 namespace rtt_actionlib {
18 
19  // Forward declaration
20  template<class ActionSpec>
22 
24  template<class ActionSpec>
26  {
27  public:
28  RTTActionServerStatusTimer(RTTActionServer<ActionSpec> &server, int scheduler = ORO_SCHED_OTHER) :
29  RTT::os::Timer(1,-1),
30  server_(server)
31  {
32  mThread = new RTT::Activity(scheduler, 0, 0.0, this, server.getName()+"_status_timer");
33  mThread->start();
34  }
35 
37 
39  virtual void timeout(RTT::os::Timer::TimerId timer_id) {
40  server_.publishStatus();
41  }
42  private:
45  };
46 
48  template<class ActionSpec>
49  class RTTActionServer : public actionlib::ActionServerBase<ActionSpec>
50  {
51  public:
52  // Generates typedefs that make our lives easier
53  ACTION_DEFINITION(ActionSpec);
54 
56 
58  RTTActionServer(const double status_period = 0.200, const int sched = ORO_SCHED_OTHER);
59  RTTActionServer(const std::string name, const double status_period = 0.200, const int sched = ORO_SCHED_OTHER);
60  virtual ~RTTActionServer();
61 
63  const std::string getName() const { return name_; };
64 
66  bool addPorts(RTT::Service::shared_ptr service,
67  const bool create_topics = false,
68  const std::string &topic_namespace = "");
69 
71  bool ready();
72 
74  virtual void initialize();
75 
77  virtual void publishResult(const actionlib_msgs::GoalStatus& status, const Result& result);
78 
80  virtual void publishFeedback(const actionlib_msgs::GoalStatus& status, const Feedback& feedback);
81 
83  virtual void publishStatus();
84 
86  goal_operation_ = operation;
87  this->registerGoalCallback(boost::bind(&RTTActionServer<ActionSpec>::goalCallbackWrapper, this, _1));
88  }
89 
91  cancel_operation_ = operation;
92  }
93 
94  private:
95 
96  /* \brief Wrapper for action server base goalCallback
97  * This function is called when messages arrive on the goal RTT port. It
98  * then reads the port and calls ActionServerBase::goalCallback, which, in
99  * turn, calls the user supplied goal callback.
100  */
101  void goalCallback(RTT::base::PortInterface* port);
102  void goalCallbackWrapper(GoalHandle gh);
103 
104  /* \brief Wrapper for action server base cancelCallback
105  * This function is called when messages arrive on the goal RTT port. It
106  * then reads the port and calls ActionServerBase::cancelCallback, which, in
107  * turn, calls the user supplied cancel callback.
108  */
109  void cancelCallback(RTT::base::PortInterface* port);
110 
112  std::string name_;
113 
116 
119 
122 
125  };
126 
127  template <class ActionSpec>
128  RTTActionServer<ActionSpec>::RTTActionServer(const double status_period, const int sched) :
129  actionlib::ActionServerBase<ActionSpec>(boost::function<void (GoalHandle)>(), boost::function<void (GoalHandle)>(), false),
130  name_("action_server"),
131  status_period_(status_period),
132  status_timer_(*this,sched)
133  {
134  }
135 
136  template <class ActionSpec>
137  RTTActionServer<ActionSpec>::RTTActionServer(const std::string name, const double status_period, const int sched) :
138  actionlib::ActionServerBase<ActionSpec>(boost::function<void (GoalHandle)>(), boost::function<void (GoalHandle)>(), false),
139  name_(name),
140  status_period_(status_period),
141  status_timer_(*this, sched)
142  {
143 
144  }
145 
146  template <class ActionSpec>
148  {
149 
150  }
151 
152  template <class ActionSpec>
154  {
155  if(this->ready()) {
156  // Start status publish timer
157  if(!status_timer_.startTimer(0,status_period_)) {
158  RTT::log(RTT::Error) << "Failed to initialize RTT Action Server: could not start status publisher timer." << RTT::endlog();
159  }
160  } else {
161  RTT::log(RTT::Error) << "Failed to initialize RTT Action Server: ports not ready." << RTT::endlog();
162  }
163  }
164 
165  template <class ActionSpec>
167  {
168  return action_bridge_.allConnected();
169  }
170 
171  template <class ActionSpec>
173  RTT::Service::shared_ptr service,
174  const bool create_topics,
175  const std::string &topic_namespace)
176  {
177  // Try to get existing ports from service
178  if(!action_bridge_.setPortsFromService(service)) {
179  // Create the ports
180  if(!action_bridge_.createServerPorts<ActionSpec>()) {
181  return false;
182  }
183  }
184 
185  // Add the ports to the service
186  service->addEventPort(
187  action_bridge_.goalInput<ActionSpec>(),
188  boost::bind(&RTTActionServer<ActionSpec>::goalCallback, this, _1))
189  .doc("Actionlib goal port. Do not read from this port directly.");
190 
191  service->addEventPort(
193  boost::bind(&RTTActionServer<ActionSpec>::cancelCallback, this, _1))
194  .doc("Actionlib cancel port. Do not read from this port directly.");
195 
196  service->addPort(action_bridge_.resultOutput<ActionSpec>())
197  .doc("Actionlib result port. Do not write to this port directly.");
198 
199  service->addPort(action_bridge_.statusOutput())
200  .doc("Actionlib result port. Do not write to this port directly.");
201 
202  service->addPort(action_bridge_.feedbackOutput<ActionSpec>())
203  .doc("Actionlib result port. Do not write to this port directly.");
204 
205  // Create ROS topics
206  if(create_topics) {
207  action_bridge_.goalInput<ActionSpec>().createStream(rtt_roscomm::topic(topic_namespace+"goal"));
208  action_bridge_.cancelInput().createStream(rtt_roscomm::topic(topic_namespace+"cancel"));
209  action_bridge_.resultOutput<ActionSpec>().createStream(rtt_roscomm::topic(topic_namespace+"result"));
210  action_bridge_.statusOutput().createStream(rtt_roscomm::topic(topic_namespace+"status"));
211  action_bridge_.feedbackOutput<ActionSpec>().createStream(rtt_roscomm::topic(topic_namespace+"feedback"));
212  }
213 
214  return true;
215  }
216 
217  template <class ActionSpec>
219  {
220  ActionGoal goal;
221  // Read the goal from the RTT port
222  if(action_bridge_.goalInput<ActionSpec>().read(goal) == RTT::NewData) {
223  // The action server base class expects a shared pointer
225  boost::make_shared<const ActionGoal>(goal));
226  }
227  }
228 
229  template <class ActionSpec>
231  {
232  if(goal_operation_.ready()) {
233  goal_operation_(gh);
234  }
235  }
236 
237  template <class ActionSpec>
239  {
240  actionlib_msgs::GoalID goal_id;
241  // Read the goal id from the RTT port
242  if(action_bridge_.cancelInput().read(goal_id) == RTT::NewData) {
243  // The action server base class expects a shared pointer
245  boost::make_shared<const actionlib_msgs::GoalID>(goal_id));
246  }
247  }
248 
249  template <class ActionSpec>
251  const actionlib_msgs::GoalStatus& status,
252  const Result& result)
253  {
254  ACTION_DEFINITION(ActionSpec);
255 
256  boost::recursive_mutex::scoped_lock lock(this->lock_);
257 
258  // Create the action result container
259  ActionResult action_result;
260  action_result.header.stamp = rtt_rosclock::host_now();
261  action_result.status = status;
262  action_result.result = result;
263 
264  //ROS_DEBUG_NAMED("actionlib", "Publishing result for goal with id: %s and stamp: %.2f", status.goal_id.id.c_str(), status.goal_id.stamp.toSec());
265 
266  // Write the result to the RTT data port
267  action_bridge_.resultOutput<ActionSpec>().write(action_result);
268 
269  this->publishStatus();
270  }
271 
272  template <class ActionSpec>
274  const actionlib_msgs::GoalStatus& status,
275  const Feedback& feedback)
276  {
277  ACTION_DEFINITION(ActionSpec);
278 
279  boost::recursive_mutex::scoped_lock lock(this->lock_);
280 
281  // Create the action result container
282  ActionFeedback action_feedback;
283  action_feedback.header.stamp = rtt_rosclock::host_now();
284  action_feedback.status = status;
285  action_feedback.feedback = feedback;
286 
287  //ROS_DEBUG_NAMED("actionlib", "Publishing result for goal with id: %s and stamp: %.2f", status.goal_id.id.c_str(), status.goal_id.stamp.toSec());
288 
289  // Write the feedback to the RTT data port
290  action_bridge_.feedbackOutput<ActionSpec>().write(action_feedback);
291  }
292 
293  template <class ActionSpec>
295  {
296  boost::recursive_mutex::scoped_lock lock(this->lock_);
297 
298  // Build a status array
299  actionlib_msgs::GoalStatusArray status_array;
300 
301  status_array.header.stamp = rtt_rosclock::host_now();
302 
303  status_array.status_list.resize(this->status_list_.size());
304 
305  unsigned int i = 0;
306  for(typename std::list<actionlib::StatusTracker<ActionSpec> >::iterator it = this->status_list_.begin();
307  it != this->status_list_.end();
308  ++i)
309  {
310  status_array.status_list[i] = (*it).status_;
311 
312  // Check if the item is due for deletion from the status list
313  if((*it).handle_destruction_time_ != ros::Time() &&
314  (*it).handle_destruction_time_ + this->status_list_timeout_ < rtt_rosclock::host_now()){
315  it = this->status_list_.erase(it);
316  } else {
317  ++it;
318  }
319  }
320 
321  // Publish the status
322  action_bridge_.statusOutput().write(status_array);
323  }
324 
325 }
326 
327 
328 
329 #endif // ifndef __RTT_ACTION_SERVER_H
void goalCallback(const boost::shared_ptr< const ActionGoal > &goal)
Orocos RTT-Based Action Server.
actionlib::ServerGoalHandle< ActionSpec > GoalHandle
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.
virtual void publishFeedback(const actionlib_msgs::GoalStatus &status, const Feedback &feedback)
Publishes feedback for a given goal.
void goalCallback(RTT::base::PortInterface *port)
void registerGoalOperation(RTT::OperationInterfacePart *operation)
rtt_actionlib::ActionBridge action_bridge_
Action bridge container for RTT ports corresponding to the action interface.
void cancelCallback(RTT::base::PortInterface *port)
RTT::OutputPort< actionlib_msgs::GoalStatusArray > & statusOutput()
Get the status output port.
base::ActivityInterface * mThread
void registerCancelOperation(RTT::OperationInterfacePart *operation)
RTTActionServerStatusTimer(RTTActionServer< ActionSpec > &server, int scheduler=ORO_SCHED_OTHER)
virtual void publishResult(const actionlib_msgs::GoalStatus &status, const Result &result)
Publishes a result for a given goal.
RTTActionServer(const double status_period=0.200, const int sched=ORO_SCHED_OTHER)
Constructor.
RTT::ConnPolicy topic(const std::string &name)
boost::recursive_mutex lock_
RTT::InputPort< actionlib_msgs::GoalID > & cancelInput()
Get the cancel input port.
Definition: rtt_actionlib.h:89
bool createServerPorts()
Add actionlib ports to a given rtt service.
Definition: rtt_actionlib.h:38
ros::Duration status_list_timeout_
virtual void timeout(RTT::os::Timer::TimerId timer_id)
Publish the action server status.
RTT::InputPort< typename ActionSpec::_action_goal_type > & goalInput()
Get the goal input port.
Definition: rtt_actionlib.h:87
RTT::OperationCaller< void(GoalHandle)> cancel_operation_
RTT::OperationCaller< void(GoalHandle)> goal_operation_
bool setPortsFromService(RTT::Service::shared_ptr service)
Store the required RTT ports from a given RTT service.
bool allConnected() const
True if all existing ports are connected.
std::list< StatusTracker< ActionSpec > > status_list_
bool ready()
Check if the server is ready to be started.
virtual void publishStatus()
Explicitly publish status.
ActionServerBase(boost::function< void(GoalHandle)> goal_cb, boost::function< void(GoalHandle)> cancel_cb, bool auto_start=false)
double status_period_
Period (Hz) at which the status should be published.
#define ACTION_DEFINITION(ActionSpec)
RTT::OutputPort< typename ActionSpec::_action_result_type > & resultOutput()
Get the result output port.
virtual void initialize()
Set up status publishing timers.
RTT::OutputPort< typename ActionSpec::_action_feedback_type > & feedbackOutput()
Get the feedback output port.
const ros::Time host_now()
RTTActionServer< ActionSpec > & server_
A reference to the owning action server.
std::string name_
Server name (used for naming timers and other resources)
void cancelCallback(const boost::shared_ptr< const actionlib_msgs::GoalID > &goal_id)
const std::string getName() const
Get the name.
static Logger & log()
Timer to trigger status publications.
static Logger::LogFunction endlog()
void goalCallbackWrapper(GoalHandle gh)
RTTActionServerStatusTimer< ActionSpec > status_timer_
RTT Timer for periodic status updates.


rtt_actionlib
Author(s): Jonathan Bohren
autogenerated on Sat Jun 8 2019 18:06:05