25 #ifndef MESSAGE_RELAY_RELAY_ACTION_RELAY_H 26 #define MESSAGE_RELAY_RELAY_ACTION_RELAY_H 84 status_params.
type =
"actionlib_msgs/GoalStatusArray";
96 feedback_params.
type = params.
type +
"Feedback";
97 feedback_params.
topic = params.
action +
"/feedback";
107 result_params.
type = params.
type +
"Result";
118 goal_params.
type = params.
type +
"Goal";
129 cancel_params.
type =
"actionlib_msgs/GoalID";
134 std::vector<message_relay::TopicRelay::Ptr>
relays_;
139 #endif // MESSAGE_RELAY_RELAY_ACTION_RELAY_H boost::shared_ptr< ros::CallbackQueue > callback_queue
double throttle_frequency
ActionRelayImpl(const ActionRelayParams ¶ms)
boost::shared_ptr< ros::NodeHandle > target
TimeProcessor::ConstPtr time_processor
ActionRelay::Ptr createActionRelay(const ActionRelayParams ¶ms)
static ConstPtr inverse(const ConstPtr &processor)
static ConstPtr inverse(const ConstPtr &processor)
TimeProcessor::ConstPtr time_processor
FrameIdProcessor::ConstPtr frame_id_processor
std::vector< message_relay::TopicRelay::Ptr > relays_
boost::shared_ptr< ros::CallbackQueue > callback_queue
TopicRelay::Ptr createTopicRelay(const TopicRelayParams ¶ms)
boost::shared_ptr< ActionRelay > Ptr
boost::shared_ptr< ros::NodeHandle > origin
boost::shared_ptr< ros::NodeHandle > target
FrameIdProcessor::ConstPtr frame_id_processor
double feedback_throttle_frequency
boost::shared_ptr< ros::NodeHandle > origin