action_relay.h
Go to the documentation of this file.
1 
25 #ifndef MESSAGE_RELAY_RELAY_ACTION_RELAY_H
26 #define MESSAGE_RELAY_RELAY_ACTION_RELAY_H
27 
30 
31 #include "ros/callback_queue.h"
32 #include "ros/ros.h"
33 
34 #include <string>
35 #include <vector>
36 
37 namespace message_relay
38 {
39 
41 {
42  std::string type;
43  std::string action;
51 
53  : queue_size(100)
54  { }
55 };
56 
58 {
59 public:
61 
62  virtual ~ActionRelay()
63  { }
64 
65 protected:
67  { }
68 };
69 
71 {
73 
74 private:
75  explicit ActionRelayImpl(const ActionRelayParams &params)
76  {
77  message_relay::TopicRelayParams status_params;
78  status_params.queue_size = params.queue_size;
79  status_params.callback_queue = params.callback_queue;
80  status_params.origin = params.origin;
81  status_params.target = params.target;
82  status_params.frame_id_processor = params.frame_id_processor;
83  status_params.time_processor = params.time_processor;
84  status_params.type = "actionlib_msgs/GoalStatusArray";
85  status_params.topic = params.action + "/status";
86  relays_.push_back(message_relay::createTopicRelay(status_params));
87 
88  message_relay::TopicRelayParams feedback_params;
89  feedback_params.throttle_frequency = params.feedback_throttle_frequency;
90  feedback_params.queue_size = params.queue_size;
91  feedback_params.callback_queue = params.callback_queue;
92  feedback_params.origin = params.origin;
93  feedback_params.target = params.target;
94  feedback_params.frame_id_processor = params.frame_id_processor;
95  status_params.time_processor = params.time_processor;
96  feedback_params.type = params.type + "Feedback";
97  feedback_params.topic = params.action + "/feedback";
98  relays_.push_back(message_relay::createTopicRelay(feedback_params));
99 
100  message_relay::TopicRelayParams result_params;
101  result_params.queue_size = params.queue_size;
102  result_params.callback_queue = params.callback_queue;
103  result_params.origin = params.origin;
104  result_params.target = params.target;
105  result_params.frame_id_processor = params.frame_id_processor;
106  status_params.time_processor = params.time_processor;
107  result_params.type = params.type + "Result";
108  result_params.topic = params.action + "/result";
109  relays_.push_back(message_relay::createTopicRelay(result_params));
110 
112  goal_params.queue_size = params.queue_size;
113  goal_params.callback_queue = params.callback_queue;
114  goal_params.origin = params.target;
115  goal_params.target = params.origin;
117  status_params.time_processor = TimeProcessor::inverse(params.time_processor);
118  goal_params.type = params.type + "Goal";
119  goal_params.topic = params.action + "/goal";
120  relays_.push_back(message_relay::createTopicRelay(goal_params));
121 
122  message_relay::TopicRelayParams cancel_params;
123  cancel_params.queue_size = params.queue_size;
124  cancel_params.callback_queue = params.callback_queue;
125  cancel_params.origin = params.target;
126  cancel_params.target = params.origin;
128  status_params.time_processor = TimeProcessor::inverse(params.time_processor);
129  cancel_params.type = "actionlib_msgs/GoalID";
130  cancel_params.topic = params.action + "/cancel";
131  relays_.push_back(message_relay::createTopicRelay(cancel_params));
132  }
133 
134  std::vector<message_relay::TopicRelay::Ptr> relays_;
135 };
136 
137 } // namespace message_relay
138 
139 #endif // MESSAGE_RELAY_RELAY_ACTION_RELAY_H
boost::shared_ptr< ros::CallbackQueue > callback_queue
Definition: topic_relay.h:49
ActionRelayImpl(const ActionRelayParams &params)
Definition: action_relay.h:75
boost::shared_ptr< ros::NodeHandle > target
Definition: topic_relay.h:43
TimeProcessor::ConstPtr time_processor
Definition: topic_relay.h:45
ActionRelay::Ptr createActionRelay(const ActionRelayParams &params)
static ConstPtr inverse(const ConstPtr &processor)
static ConstPtr inverse(const ConstPtr &processor)
TimeProcessor::ConstPtr time_processor
Definition: action_relay.h:47
FrameIdProcessor::ConstPtr frame_id_processor
Definition: topic_relay.h:44
std::vector< message_relay::TopicRelay::Ptr > relays_
Definition: action_relay.h:134
boost::shared_ptr< ros::CallbackQueue > callback_queue
Definition: action_relay.h:50
TopicRelay::Ptr createTopicRelay(const TopicRelayParams &params)
boost::shared_ptr< ActionRelay > Ptr
Definition: action_relay.h:60
boost::shared_ptr< ros::NodeHandle > origin
Definition: action_relay.h:44
boost::shared_ptr< ros::NodeHandle > target
Definition: action_relay.h:45
FrameIdProcessor::ConstPtr frame_id_processor
Definition: action_relay.h:46
boost::shared_ptr< ros::NodeHandle > origin
Definition: topic_relay.h:42


message_relay
Author(s):
autogenerated on Wed Jul 17 2019 03:27:53