#include <rtt_actionlib.h>
Public Member Functions | |
ActionBridge () | |
Constructor. | |
bool | allConnected () const |
True if all existing ports are connected. | |
bool | anyConnected () const |
RTT::InputPort < actionlib_msgs::GoalID > & | cancelInput () |
Get the cancel input port. | |
RTT::OutputPort < actionlib_msgs::GoalID > & | cancelOutput () |
Get the cancel output port. | |
template<class ActionSpec > | |
bool | createClientPorts () |
template<class ActionSpec > | |
bool | createServerPorts () |
Add actionlib ports to a given rtt service. | |
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. | |
template<class ActionSpec > | |
RTT::InputPort< typename ActionSpec::_action_feedback_type > & | feedbackInput () |
Get the feedback input port. | |
template<class ActionSpec > | |
RTT::OutputPort< typename ActionSpec::_action_feedback_type > & | feedbackOutput () |
Get the feedback output port. | |
template<class ActionSpec > | |
RTT::InputPort< typename ActionSpec::_action_goal_type > & | goalInput () |
Get the goal input port. | |
template<class ActionSpec > | |
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. | |
bool | isServer () const |
True if valid, goal/cancel are inputs, and result/status/feedback are outputs. | |
bool | isValid () const |
True if all required ports are not null. | |
template<class ActionSpec > | |
RTT::InputPort< typename ActionSpec::_action_result_type > & | resultInput () |
Get the result input port. | |
template<class 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. | |
bool | setPortsFromService (RTT::Service::shared_ptr service) |
Store the required RTT ports from a given RTT service. | |
RTT::InputPort < actionlib_msgs::GoalStatusArray > & | statusInput () |
Get the status input port. | |
RTT::OutputPort < actionlib_msgs::GoalStatusArray > & | statusOutput () |
Get the status output port. | |
~ActionBridge () | |
Private Attributes | |
RTT::base::PortInterface * | cancel_ |
RTT::base::PortInterface * | feedback_ |
RTT::base::PortInterface * | goal_ |
bool | owns_port_pointers_ |
RTT::base::PortInterface * | result_ |
RTT::base::PortInterface * | status_ |
Definition at line 16 of file rtt_actionlib.h.
rtt_actionlib::ActionBridge::ActionBridge | ( | ) | [inline] |
Constructor.
Definition at line 21 of file rtt_actionlib.h.
rtt_actionlib::ActionBridge::~ActionBridge | ( | ) | [inline] |
Definition at line 25 of file rtt_actionlib.h.
bool rtt_actionlib::ActionBridge::allConnected | ( | ) | const [inline] |
True if all existing ports are connected.
Definition at line 242 of file rtt_actionlib.h.
bool rtt_actionlib::ActionBridge::anyConnected | ( | ) | const [inline] |
Definition at line 258 of file rtt_actionlib.h.
RTT::InputPort<actionlib_msgs::GoalID>& rtt_actionlib::ActionBridge::cancelInput | ( | ) | [inline] |
Get the cancel input port.
Definition at line 89 of file rtt_actionlib.h.
RTT::OutputPort<actionlib_msgs::GoalID>& rtt_actionlib::ActionBridge::cancelOutput | ( | ) | [inline] |
Get the cancel output port.
Definition at line 103 of file rtt_actionlib.h.
bool rtt_actionlib::ActionBridge::createClientPorts | ( | ) | [inline] |
Definition at line 62 of file rtt_actionlib.h.
bool rtt_actionlib::ActionBridge::createServerPorts | ( | ) | [inline] |
Add actionlib ports to a given rtt service.
Definition at line 38 of file rtt_actionlib.h.
bool rtt_actionlib::ActionBridge::createStream | ( | const std::string | action_ns, |
RTT::ConnPolicy | cp_template = RTT::ConnPolicy::data() |
||
) | [inline] |
Create a stream from this RTT actionlib port interface to the appropriate ROS topic interface.
Definition at line 202 of file rtt_actionlib.h.
RTT::InputPort<typename ActionSpec::_action_feedback_type>& rtt_actionlib::ActionBridge::feedbackInput | ( | ) | [inline] |
Get the feedback input port.
Definition at line 97 of file rtt_actionlib.h.
RTT::OutputPort<typename ActionSpec::_action_feedback_type>& rtt_actionlib::ActionBridge::feedbackOutput | ( | ) | [inline] |
Get the feedback output port.
Definition at line 111 of file rtt_actionlib.h.
RTT::InputPort<typename ActionSpec::_action_goal_type>& rtt_actionlib::ActionBridge::goalInput | ( | ) | [inline] |
Get the goal input port.
Definition at line 87 of file rtt_actionlib.h.
RTT::OutputPort<typename ActionSpec::_action_goal_type>& rtt_actionlib::ActionBridge::goalOutput | ( | ) | [inline] |
Get the goal output port.
Definition at line 101 of file rtt_actionlib.h.
bool rtt_actionlib::ActionBridge::isClient | ( | ) | const [inline] |
True if valid, goal/cancel are outputs, and result/status/feedback are inputs.
Definition at line 181 of file rtt_actionlib.h.
bool rtt_actionlib::ActionBridge::isServer | ( | ) | const [inline] |
True if valid, goal/cancel are inputs, and result/status/feedback are outputs.
Definition at line 161 of file rtt_actionlib.h.
bool rtt_actionlib::ActionBridge::isValid | ( | ) | const [inline] |
True if all required ports are not null.
Definition at line 155 of file rtt_actionlib.h.
RTT::InputPort<typename ActionSpec::_action_result_type>& rtt_actionlib::ActionBridge::resultInput | ( | ) | [inline] |
Get the result input port.
Definition at line 94 of file rtt_actionlib.h.
RTT::OutputPort<typename ActionSpec::_action_result_type>& rtt_actionlib::ActionBridge::resultOutput | ( | ) | [inline] |
Get the result output port.
Definition at line 108 of file rtt_actionlib.h.
bool rtt_actionlib::ActionBridge::setPorts | ( | RTT::base::PortInterface * | goal, |
RTT::base::PortInterface * | cancel, | ||
RTT::base::PortInterface * | status, | ||
RTT::base::PortInterface * | result, | ||
RTT::base::PortInterface * | feedback | ||
) | [inline] |
Store the RTT ports manually.
Definition at line 114 of file rtt_actionlib.h.
bool rtt_actionlib::ActionBridge::setPortsFromService | ( | RTT::Service::shared_ptr | service | ) | [inline] |
Store the required RTT ports from a given RTT service.
Definition at line 135 of file rtt_actionlib.h.
RTT::InputPort<actionlib_msgs::GoalStatusArray>& rtt_actionlib::ActionBridge::statusInput | ( | ) | [inline] |
Get the status input port.
Definition at line 91 of file rtt_actionlib.h.
RTT::OutputPort<actionlib_msgs::GoalStatusArray>& rtt_actionlib::ActionBridge::statusOutput | ( | ) | [inline] |
Get the status output port.
Definition at line 105 of file rtt_actionlib.h.
Definition at line 281 of file rtt_actionlib.h.
Definition at line 284 of file rtt_actionlib.h.
Definition at line 280 of file rtt_actionlib.h.
bool rtt_actionlib::ActionBridge::owns_port_pointers_ [private] |
Definition at line 277 of file rtt_actionlib.h.
Definition at line 283 of file rtt_actionlib.h.
Definition at line 282 of file rtt_actionlib.h.