1 #ifndef __RTT_ACTIONLIB_H 2 #define __RTT_ACTIONLIB_H 7 #include <actionlib_msgs/GoalID.h> 8 #include <actionlib_msgs/GoalStatusArray.h> 37 template<
class ActionSpec>
61 template<
class ActionSpec>
86 template<
class ActionSpec>
93 template<
class ActionSpec>
96 template<
class ActionSpec>
100 template<
class ActionSpec>
107 template<
class ActionSpec>
110 template<
class ActionSpec>
138 if(service.get() == NULL) {
return false; }
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");
164 if(!this->
isValid()) {
return false; }
177 return goal_in && cancel_in && status_out && result_out && feedback_out;
184 if(!this->
isValid()) {
return false; }
198 return goal_out && cancel_out && status_in && result_in && feedback_in;
205 if(!this->
isValid()) {
return false; }
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;
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";
245 if(!this->
isValid()) {
return false; }
261 if(!this->
isValid()) {
return false; }
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.
RTT::base::PortInterface * status_
RTT::InputPort< typename ActionSpec::_action_feedback_type > & feedbackInput()
Get the feedback input port.
RTT::InputPort< actionlib_msgs::GoalID > & cancelInput()
Get the cancel input port.
bool createServerPorts()
Add actionlib ports to a given rtt service.
RTT::InputPort< typename ActionSpec::_action_goal_type > & goalInput()
Get the goal input port.
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.
ActionBridge()
Constructor.
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_
bool anyConnected() const
RTT::base::PortInterface * cancel_
RTT::base::PortInterface * result_