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  void shutdown();
75 
77  virtual void initialize();
78 
80  virtual void publishResult(const actionlib_msgs::GoalStatus& status, const Result& result);
81 
83  virtual void publishFeedback(const actionlib_msgs::GoalStatus& status, const Feedback& feedback);
84 
86  virtual void publishStatus();
87 
89  goal_operation_ = operation;
90  this->registerGoalCallback(boost::bind(&RTTActionServer<ActionSpec>::goalCallbackWrapper, this, _1));
91  }
92 
94  cancel_operation_ = operation;
95  }
96 
97  private:
98 
99  /* \brief Wrapper for action server base goalCallback
100  * This function is called when messages arrive on the goal RTT port. It
101  * then reads the port and calls ActionServerBase::goalCallback, which, in
102  * turn, calls the user supplied goal callback.
103  */
104  void goalCallback(RTT::base::PortInterface* port);
105  void goalCallbackWrapper(GoalHandle gh);
106 
107  /* \brief Wrapper for action server base cancelCallback
108  * This function is called when messages arrive on the goal RTT port. It
109  * then reads the port and calls ActionServerBase::cancelCallback, which, in
110  * turn, calls the user supplied cancel callback.
111  */
112  void cancelCallback(RTT::base::PortInterface* port);
113 
115  std::string name_;
116 
119 
122 
125 
128  };
129 
130  template <class ActionSpec>
131  RTTActionServer<ActionSpec>::RTTActionServer(const double status_period, const int sched) :
132  actionlib::ActionServerBase<ActionSpec>(boost::function<void (GoalHandle)>(), boost::function<void (GoalHandle)>(), false),
133  name_("action_server"),
134  status_period_(status_period),
135  status_timer_(*this,sched)
136  {
137  }
138 
139  template <class ActionSpec>
140  RTTActionServer<ActionSpec>::RTTActionServer(const std::string name, const double status_period, const int sched) :
141  actionlib::ActionServerBase<ActionSpec>(boost::function<void (GoalHandle)>(), boost::function<void (GoalHandle)>(), false),
142  name_(name),
143  status_period_(status_period),
144  status_timer_(*this, sched)
145  {
146 
147  }
148 
149  template <class ActionSpec>
151  {
152 
153  }
154 
155  template <class ActionSpec>
157  {
158  if(this->ready()) {
159  // Start status publish timer
160  if(!status_timer_.startTimer(0,status_period_)) {
161  RTT::log(RTT::Error) << "Failed to initialize RTT Action Server: could not start status publisher timer." << RTT::endlog();
162  }
163  } else {
164  RTT::log(RTT::Error) << "Failed to initialize RTT Action Server: ports not ready." << RTT::endlog();
165  }
166  }
167 
168  template <class ActionSpec>
170  {
171  return action_bridge_.allConnected();
172  }
173 
174  template <class ActionSpec>
176  {
177  status_timer_.killTimer(0);
178  }
179 
180  template <class ActionSpec>
182  RTT::Service::shared_ptr service,
183  const bool create_topics,
184  const std::string &topic_namespace)
185  {
186  // Try to get existing ports from service
187  if(!action_bridge_.setPortsFromService(service)) {
188  // Create the ports
189  if(!action_bridge_.createServerPorts<ActionSpec>()) {
190  return false;
191  }
192  }
193 
194  // Add the ports to the service
195  service->addEventPort(
196  action_bridge_.goalInput<ActionSpec>(),
197  boost::bind(&RTTActionServer<ActionSpec>::goalCallback, this, _1))
198  .doc("Actionlib goal port. Do not read from this port directly.");
199 
200  service->addEventPort(
202  boost::bind(&RTTActionServer<ActionSpec>::cancelCallback, this, _1))
203  .doc("Actionlib cancel port. Do not read from this port directly.");
204 
205  service->addPort(action_bridge_.resultOutput<ActionSpec>())
206  .doc("Actionlib result port. Do not write to this port directly.");
207 
208  service->addPort(action_bridge_.statusOutput())
209  .doc("Actionlib result port. Do not write to this port directly.");
210 
211  service->addPort(action_bridge_.feedbackOutput<ActionSpec>())
212  .doc("Actionlib result port. Do not write to this port directly.");
213 
214  // Create ROS topics
215  if(create_topics) {
216  action_bridge_.goalInput<ActionSpec>().createStream(rtt_roscomm::topic(topic_namespace+"goal"));
217  action_bridge_.cancelInput().createStream(rtt_roscomm::topic(topic_namespace+"cancel"));
218  action_bridge_.resultOutput<ActionSpec>().createStream(rtt_roscomm::topic(topic_namespace+"result"));
219  action_bridge_.statusOutput().createStream(rtt_roscomm::topic(topic_namespace+"status"));
220  action_bridge_.feedbackOutput<ActionSpec>().createStream(rtt_roscomm::topic(topic_namespace+"feedback"));
221  }
222 
223  return true;
224  }
225 
226  template <class ActionSpec>
228  {
229  ActionGoal goal;
230  // Read the goal from the RTT port
231  if(action_bridge_.goalInput<ActionSpec>().read(goal) == RTT::NewData) {
232  // The action server base class expects a shared pointer
234  boost::make_shared<const ActionGoal>(goal));
235  }
236  }
237 
238  template <class ActionSpec>
240  {
241  if(goal_operation_.ready()) {
242  goal_operation_(gh);
243  }
244  }
245 
246  template <class ActionSpec>
248  {
249  actionlib_msgs::GoalID goal_id;
250  // Read the goal id from the RTT port
251  if(action_bridge_.cancelInput().read(goal_id) == RTT::NewData) {
252  // The action server base class expects a shared pointer
254  boost::make_shared<const actionlib_msgs::GoalID>(goal_id));
255  }
256  }
257 
258  template <class ActionSpec>
260  const actionlib_msgs::GoalStatus& status,
261  const Result& result)
262  {
263  ACTION_DEFINITION(ActionSpec);
264 
265  boost::recursive_mutex::scoped_lock lock(this->lock_);
266 
267  // Create the action result container
268  ActionResult action_result;
269  action_result.header.stamp = rtt_rosclock::host_now();
270  action_result.status = status;
271  action_result.result = result;
272 
273  //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());
274 
275  // Write the result to the RTT data port
276  action_bridge_.resultOutput<ActionSpec>().write(action_result);
277 
278  this->publishStatus();
279  }
280 
281  template <class ActionSpec>
283  const actionlib_msgs::GoalStatus& status,
284  const Feedback& feedback)
285  {
286  ACTION_DEFINITION(ActionSpec);
287 
288  boost::recursive_mutex::scoped_lock lock(this->lock_);
289 
290  // Create the action result container
291  ActionFeedback action_feedback;
292  action_feedback.header.stamp = rtt_rosclock::host_now();
293  action_feedback.status = status;
294  action_feedback.feedback = feedback;
295 
296  //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());
297 
298  // Write the feedback to the RTT data port
299  action_bridge_.feedbackOutput<ActionSpec>().write(action_feedback);
300  }
301 
302  template <class ActionSpec>
304  {
305  boost::recursive_mutex::scoped_lock lock(this->lock_);
306 
307  // Build a status array
308  actionlib_msgs::GoalStatusArray status_array;
309 
310  status_array.header.stamp = rtt_rosclock::host_now();
311 
312  status_array.status_list.resize(this->status_list_.size());
313 
314  unsigned int i = 0;
315  for(typename std::list<actionlib::StatusTracker<ActionSpec> >::iterator it = this->status_list_.begin();
316  it != this->status_list_.end();
317  ++i)
318  {
319  status_array.status_list[i] = (*it).status_;
320 
321  // Check if the item is due for deletion from the status list
322  if((*it).handle_destruction_time_ != ros::Time() &&
323  (*it).handle_destruction_time_ + this->status_list_timeout_ < rtt_rosclock::host_now()){
324  it = this->status_list_.erase(it);
325  } else {
326  ++it;
327  }
328  }
329 
330  // Publish the status
331  action_bridge_.statusOutput().write(status_array);
332  }
333 
334 }
335 
336 
337 
338 #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.
void shutdown()
Shutdown internal timer.
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.
ROSCONSOLE_DECL void shutdown()
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 Mon May 10 2021 02:45:37