rtt_actionlib.h
Go to the documentation of this file.
1 #ifndef __RTT_ACTIONLIB_H
2 #define __RTT_ACTIONLIB_H
3 
4 #include <rtt/RTT.hpp>
5 
7 #include <actionlib_msgs/GoalID.h>
8 #include <actionlib_msgs/GoalStatusArray.h>
9 
10 #include <rtt_roscomm/rostopic.h>
11 
12 namespace rtt_actionlib {
13 
14  /* \brief Actionlib RTT bridge used to create and access actionlib RTT data ports
15  */
17  {
18  public:
19 
22  owns_port_pointers_(false), goal_(NULL), cancel_(NULL), status_(NULL), result_(NULL), feedback_(NULL)
23  { }
24 
26  {
28  if(goal_) delete goal_;
29  if(cancel_) delete cancel_;
30  if(status_) delete status_;
31  if(result_) delete result_;
32  if(feedback_) delete feedback_;
33  }
34  }
35 
37  template<class ActionSpec>
39  {
40  // Generates typedefs that make our lives easier
41  ACTION_DEFINITION(ActionSpec);
42 
43  // Make sure it isn't valid or connected
44  if(this->isValid() || this->anyConnected()) {
45  return false;
46  }
47 
48  // Construct server ports
49  goal_ = new RTT::InputPort<ActionGoal>("_action_goal");
50  cancel_ = new RTT::InputPort<actionlib_msgs::GoalID>("_action_cancel");
51  result_ = new RTT::OutputPort<ActionResult>("_action_result");
53  feedback_ = new RTT::OutputPort<ActionFeedback>("_action_feedback");
54 
55  // Set the ownership flag
56  owns_port_pointers_ = true;
57 
58  return this->isValid();
59  }
60 
61  template<class ActionSpec>
63  {
64  // Generates typedefs that make our lives easier
65  ACTION_DEFINITION(ActionSpec);
66 
67  // Make sure it isn't valid or connected
68  if(this->isValid() || this->anyConnected()) {
69  return false;
70  }
71 
72  // Construct server ports
73  goal_ = new RTT::OutputPort<ActionGoal>("_action_goal");
74  cancel_ = new RTT::OutputPort<actionlib_msgs::GoalID>("_action_cancel");
75  result_ = new RTT::InputPort<ActionResult>("_action_result");
77  feedback_ = new RTT::InputPort<ActionFeedback>("_action_feedback");
78 
79  // Set the ownership flag
80  owns_port_pointers_ = true;
81 
82  return this->isValid();
83  }
84 
86  template<class ActionSpec>
93  template<class ActionSpec>
96  template<class ActionSpec>
98 
100  template<class ActionSpec>
107  template<class ActionSpec>
110  template<class ActionSpec>
112 
114  bool setPorts(
116  RTT::base::PortInterface* cancel,
117  RTT::base::PortInterface* status,
118  RTT::base::PortInterface* result,
119  RTT::base::PortInterface* feedback)
120  {
121  // Store the ports
122  goal_ = goal;
123  cancel_ = cancel;
124  status_ = status;
125  result_ = result;
126  feedback_ = feedback;
127 
128  // Set the ownership flag
129  owns_port_pointers_ = false;
130 
131  return this->isValid();
132  }
133 
136  {
137  // Make sure service isn't null
138  if(service.get() == NULL) { return false; }
139 
140  // Get ports
141  goal_ = service->getPort("_action_goal");
142  cancel_ = service->getPort("_action_cancel");
143  status_ = service->getPort("_action_status");
144  result_ = service->getPort("_action_result");
145  feedback_ = service->getPort("_action_feedback");
146 
147  // Set the ownership flag
148  owns_port_pointers_ = false;
149 
150  // Return true if required ports are non-null
151  return this->isValid();
152  }
153 
155  bool isValid() const
156  {
157  return goal_ && cancel_ && status_ && result_ && feedback_;
158  }
159 
161  bool isServer() const
162  {
163  // Make sure the bridge is valid
164  if(!this->isValid()) { return false; }
165 
166  RTT::base::InputPortInterface *goal_in, *cancel_in;
167  RTT::base::OutputPortInterface *status_out, *result_out, *feedback_out;
168 
169  // Get port directions
170  goal_in = dynamic_cast<RTT::base::InputPortInterface*>(goal_);
171  cancel_in = dynamic_cast<RTT::base::InputPortInterface*>(cancel_);
172 
173  status_out = dynamic_cast<RTT::base::OutputPortInterface*>(status_);
174  result_out = dynamic_cast<RTT::base::OutputPortInterface*>(result_);
175  feedback_out = dynamic_cast<RTT::base::OutputPortInterface*>(feedback_);
176 
177  return goal_in && cancel_in && status_out && result_out && feedback_out;
178  }
179 
181  bool isClient() const
182  {
183  // Make sure the bridge is valid
184  if(!this->isValid()) { return false; }
185 
186  // Declare actual port directions
187  RTT::base::InputPortInterface *status_in, *result_in, *feedback_in;
188  RTT::base::OutputPortInterface *goal_out, *cancel_out;
189 
190  // Get port directions
191  goal_out = dynamic_cast<RTT::base::OutputPortInterface*>(goal_);
192  cancel_out = dynamic_cast<RTT::base::OutputPortInterface*>(cancel_);
193 
194  status_in = dynamic_cast<RTT::base::InputPortInterface*>(status_);
195  result_in = dynamic_cast<RTT::base::InputPortInterface*>(result_);
196  feedback_in = dynamic_cast<RTT::base::InputPortInterface*>(feedback_);
197 
198  return goal_out && cancel_out && status_in && result_in && feedback_in;
199  }
200 
202  bool createStream(const std::string action_ns, RTT::ConnPolicy cp_template = RTT::ConnPolicy::data())
203  {
204  // Make sure the bridge is valid
205  if(!this->isValid()) { return false; }
206 
207  // Construct connection policies for each port
209  cp_goal = cp_template,
210  cp_cancel = cp_template,
211  cp_status = cp_template,
212  cp_result = cp_template,
213  cp_feedback = cp_template;
214 
215  // Set the ros connection policies
216  cp_goal.transport = ORO_ROS_PROTOCOL_ID;
217  cp_cancel.transport = ORO_ROS_PROTOCOL_ID;
218  cp_status.transport = ORO_ROS_PROTOCOL_ID;
219  cp_result.transport = ORO_ROS_PROTOCOL_ID;
220  cp_feedback.transport = ORO_ROS_PROTOCOL_ID;
221 
222  // Construct the actionlib topic names
223  cp_goal.name_id = action_ns+"/goal";
224  cp_cancel.name_id = action_ns+"/cancel";
225  cp_status.name_id = action_ns+"/status";
226  cp_result.name_id = action_ns+"/result";
227  cp_feedback.name_id = action_ns+"/feedback";
228 
229  // Connect each stream
230  bool valid = true;
231 
232  valid &= goal_->createStream(cp_goal);
233  valid &= cancel_->createStream(cp_cancel);
234  valid &= status_->createStream(cp_status);
235  valid &= result_->createStream(cp_result);
236  valid &= feedback_->createStream(cp_feedback);
237 
238  return valid;
239  }
240 
242  bool allConnected() const
243  {
244  // Make sure the bridge is valid
245  if(!this->isValid()) { return false; }
246 
247  bool valid = true;
248 
249  valid &= goal_->connected();
250  valid &= cancel_->connected();
251  valid &= status_->connected();
252  valid &= result_->connected();
253  valid &= feedback_->connected();
254 
255  return valid;
256  }
257 
258  bool anyConnected() const
259  {
260  // Make sure the bridge is valid
261  if(!this->isValid()) { return false; }
262 
263  bool valid = false;
264 
265  valid |= goal_->connected();
266  valid |= cancel_->connected();
267  valid |= status_->connected();
268  valid |= result_->connected();
269  valid |= feedback_->connected();
270 
271  return valid;
272  }
273 
274  private:
275 
276  // Ownership of pointers
278 
279  // RTT Ports
285 
286  };
287 
288 }
289 
290 #endif // ifndef __RTT_ACTIONLIB_H
#define ORO_ROS_PROTOCOL_ID
static ConnPolicy data(int lock_policy=LOCK_FREE, bool init_connection=true, bool pull=false)
RTT::OutputPort< typename ActionSpec::_action_goal_type > & goalOutput()
Get the goal output port.
bool isClient() const
True if valid, goal/cancel are outputs, and result/status/feedback are inputs.
RTT::OutputPort< actionlib_msgs::GoalID > & cancelOutput()
Get the cancel output port.
RTT::OutputPort< actionlib_msgs::GoalStatusArray > & statusOutput()
Get the status output port.
bool isValid() const
True if all required ports are not null.
RTT::base::PortInterface * goal_
RTT::InputPort< typename ActionSpec::_action_result_type > & resultInput()
Get the result input port.
Definition: rtt_actionlib.h:94
RTT::base::PortInterface * status_
RTT::InputPort< typename ActionSpec::_action_feedback_type > & feedbackInput()
Get the feedback input port.
Definition: rtt_actionlib.h:97
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
RTT::InputPort< typename ActionSpec::_action_goal_type > & goalInput()
Get the goal input port.
Definition: rtt_actionlib.h:87
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.
RTT::InputPort< actionlib_msgs::GoalStatusArray > & statusInput()
Get the status input port.
Definition: rtt_actionlib.h:91
bool createStream(const std::string action_ns, RTT::ConnPolicy cp_template=RTT::ConnPolicy::data())
Create a stream from this RTT actionlib port interface to the appropriate ROS topic interface...
#define ACTION_DEFINITION(ActionSpec)
RTT::OutputPort< typename ActionSpec::_action_result_type > & resultOutput()
Get the result output port.
bool setPorts(RTT::base::PortInterface *goal, RTT::base::PortInterface *cancel, RTT::base::PortInterface *status, RTT::base::PortInterface *result, RTT::base::PortInterface *feedback)
Store the RTT ports manually.
RTT::OutputPort< typename ActionSpec::_action_feedback_type > & feedbackOutput()
Get the feedback output port.
bool isServer() const
True if valid, goal/cancel are inputs, and result/status/feedback are outputs.
virtual bool createStream(ConnPolicy const &policy)=0
virtual bool connected() const =0
RTT::base::PortInterface * feedback_
std::string name_id
RTT::base::PortInterface * cancel_
RTT::base::PortInterface * result_


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