6 from collections
import Iterable
8 from mir_driver
import rosbridge
9 from rospy_message_converter
import message_converter
11 from actionlib_msgs.msg
import GoalID, GoalStatusArray
12 from diagnostic_msgs.msg
import DiagnosticArray, DiagnosticStatus
13 from dynamic_reconfigure.msg
import Config, ConfigDescription
14 from geometry_msgs.msg
import PolygonStamped, Pose, PoseArray, PoseStamped, PoseWithCovarianceStamped, Twist
17 from move_base_msgs.msg
import MoveBaseActionFeedback, MoveBaseActionGoal, MoveBaseActionResult, MoveBaseFeedback, MoveBaseResult
18 from nav_msgs.msg
import GridCells, MapMetaData, OccupancyGrid, Odometry, Path
19 from rosgraph_msgs.msg
import Log
20 from sensor_msgs.msg
import Imu, LaserScan, PointCloud2, Range
21 from std_msgs.msg
import Float64, String
22 from tf.msg
import tfMessage
23 from visualization_msgs.msg
import Marker, MarkerArray
28 def __init__(self, topic, topic_type, latch=False, dict_filter=None):
38 filtered_msg_dict = copy.deepcopy(msg_dict)
39 filtered_msg_dict[
'feedback'] = {key: msg_dict[
'feedback'][key]
for key
in MoveBaseFeedback.__slots__}
40 return filtered_msg_dict
43 filtered_msg_dict = copy.deepcopy(msg_dict)
44 filtered_msg_dict[
'result'] = {key: msg_dict[
'result'][key]
for key
in MoveBaseResult.__slots__}
45 return filtered_msg_dict
48 filtered_msg_dict = copy.deepcopy(msg_dict)
49 for transform
in filtered_msg_dict[
'transforms']:
50 transform[
'child_frame_id'] = tf_prefix +
'/' + transform[
'child_frame_id'].strip(
'/')
51 return filtered_msg_dict
55 if not isinstance(msg_dict, dict):
57 for (key, value)
in msg_dict.iteritems():
61 frame_id = value[
'frame_id'].strip(
'/')
62 if (frame_id !=
'map'):
64 value[
'frame_id'] = (tf_prefix +
'/' + frame_id).strip(
'/')
66 value[
'frame_id'] = frame_id
72 elif isinstance(value, dict):
74 elif isinstance(value, Iterable):
81 if not isinstance(msg_dict, dict):
83 for (key, value)
in msg_dict.iteritems():
87 s = value[
'frame_id'].strip(
'/')
88 if s.find(tf_prefix) == 0:
89 value[
'frame_id'] = (s[len(tf_prefix):]).strip(
'/')
94 elif isinstance(value, dict):
96 elif isinstance(value, Iterable):
106 TopicConfig(
'MissionController/CheckArea/visualization_marker', Marker),
107 TopicConfig(
'SickPLC/parameter_descriptions', ConfigDescription),
109 TopicConfig(
'amcl_pose', PoseWithCovarianceStamped),
112 TopicConfig(
'camera_floor/background', PointCloud2),
113 TopicConfig(
'camera_floor/depth/parameter_descriptions', ConfigDescription),
114 TopicConfig(
'camera_floor/depth/parameter_updates', Config),
115 TopicConfig(
'camera_floor/depth/points', PointCloud2),
116 TopicConfig(
'camera_floor/filter/parameter_descriptions', ConfigDescription),
117 TopicConfig(
'camera_floor/filter/parameter_updates', Config),
119 TopicConfig(
'camera_floor/obstacles', PointCloud2),
120 TopicConfig(
'camera_floor/transform/parameter_descriptions', ConfigDescription),
121 TopicConfig(
'camera_floor/transform/parameter_updates', Config),
125 TopicConfig(
'diagnostics_toplevel_state', DiagnosticStatus),
129 TopicConfig(
'laser_back/driver/parameter_descriptions', ConfigDescription),
130 TopicConfig(
'laser_back/driver/parameter_updates', Config),
131 TopicConfig(
'laser_back/transform/parameter_descriptions', ConfigDescription),
132 TopicConfig(
'laser_back/transform/parameter_updates', Config),
133 TopicConfig(
'laser_front/driver/parameter_descriptions', ConfigDescription),
134 TopicConfig(
'laser_front/driver/parameter_updates', Config),
135 TopicConfig(
'laser_front/transform/parameter_descriptions', ConfigDescription),
136 TopicConfig(
'laser_front/transform/parameter_updates', Config),
139 TopicConfig(
'mir_amcl/parameter_descriptions', ConfigDescription),
141 TopicConfig(
'mir_amcl/selected_points', PointCloud2),
148 TopicConfig(
'mirwebapp/grid_map_metadata', LocalMapStat),
149 TopicConfig(
'mirwebapp/laser_map_metadata', LocalMapStat),
152 TopicConfig(
'move_base/feedback', MoveBaseActionFeedback, dict_filter=_move_base_feedback_dict_filter),
153 TopicConfig(
'move_base/result', MoveBaseActionResult, dict_filter=_move_base_result_dict_filter),
158 TopicConfig(
'move_base_node/MIRPlannerROS/local_plan', Path),
161 TopicConfig(
'move_base_node/SBPLLatticePlanner/plan', Path),
163 TopicConfig(
'move_base_node/current_goal', PoseStamped),
173 TopicConfig(
'move_base_node/local_costmap/inflated_obstacles', GridCells),
174 TopicConfig(
'move_base_node/local_costmap/obstacles', GridCells),
177 TopicConfig(
'move_base_node/local_costmap/robot_footprint', PolygonStamped),
185 TopicConfig(
'relative_move_action/feedback', RelativeMoveActionFeedback),
186 TopicConfig(
'relative_move_action/result', RelativeMoveActionResult),
187 TopicConfig(
'relative_move_action/status', GoalStatusArray),
188 TopicConfig(
'relative_move_node/parameter_descriptions', ConfigDescription),
189 TopicConfig(
'relative_move_node/parameter_updates', Config),
190 TopicConfig(
'relative_move_node/time_to_coll', Float64),
191 TopicConfig(
'relative_move_node/visualization_marker', Marker),
198 TopicConfig(
'scan_filter/visualization_marker', Marker),
199 TopicConfig(
'tf', tfMessage, dict_filter=_tf_dict_filter),
200 TopicConfig(
'transform_footprint/parameter_descriptions', ConfigDescription),
201 TopicConfig(
'transform_footprint/parameter_updates', Config),
202 TopicConfig(
'transform_imu/parameter_descriptions', ConfigDescription),
203 TopicConfig(
'transform_imu/parameter_updates', Config)]
207 TopicConfig(
'initialpose', PoseWithCovarianceStamped),
214 TopicConfig(
'relative_move_action/cancel', GoalID),
215 TopicConfig(
'relative_move_action/goal', RelativeMoveActionGoal)]
222 self.
pub = rospy.Publisher(name=topic_config.topic,
223 data_class=topic_config.topic_type,
224 subscriber_listener=self,
225 latch=topic_config.latch,
227 rospy.loginfo(
"[%s] publishing topic '%s' [%s]",
228 rospy.get_name(), topic_config.topic, topic_config.topic_type._type)
230 if topic_config.latch:
235 if (self.pub.get_num_connections() == 1
and not self.
connected)
or self.topic_config.latch:
236 rospy.loginfo(
"[%s] starting to stream messages on topic '%s'", rospy.get_name(), self.topic_config.topic)
237 self.robot.subscribe(topic=(
'/' + self.topic_config.topic), callback=self.callback)
248 if self.topic_config.dict_filter
is not None:
249 msg_dict = self.topic_config.dict_filter(msg_dict)
250 msg = message_converter.convert_dictionary_to_ros_message(self.topic_config.topic_type._type, msg_dict)
251 self.pub.publish(msg)
257 self.
sub = rospy.Subscriber(name=topic_config.topic,
258 data_class=topic_config.topic_type,
261 rospy.loginfo(
"[%s] subscribing to topic '%s' [%s]",
262 rospy.get_name(), topic_config.topic, topic_config.topic_type._type)
265 msg_dict = message_converter.convert_ros_message_to_dictionary(msg)
267 if self.topic_config.dict_filter
is not None:
268 msg_dict = self.topic_config.dict_filter(msg_dict)
269 self.robot.publish(
'/' + self.topic_config.topic, msg_dict)
274 hostname = rospy.get_param(
'~hostname')
276 rospy.logfatal(
'[%s] parameter "hostname" is not set!', rospy.get_name())
278 port = rospy.get_param(
'~port', 9090)
281 tf_prefix = rospy.get_param(
'~tf_prefix',
'').strip(
'/')
283 rospy.loginfo(
'[%s] trying to connect to %s:%i...', rospy.get_name(), hostname, port)
284 self.
robot = rosbridge.RosbridgeSetup(hostname, port)
288 while not self.robot.is_connected():
289 if rospy.is_shutdown():
291 if self.robot.is_errored():
292 rospy.logfatal(
'[%s] connection error to %s:%i, giving up!', rospy.get_name(), hostname, port)
295 rospy.logwarn(
'[%s] still waiting for connection to %s:%i...', rospy.get_name(), hostname, port)
299 rospy.loginfo(
'[%s] ... connected.', rospy.get_name())
302 published_topics = [topic_name
for (topic_name, _, has_publishers, _)
in topics
if has_publishers]
303 subscribed_topics = [topic_name
for (topic_name, _, _, has_subscribers)
in topics
if has_subscribers]
305 for pub_topic
in PUB_TOPICS:
307 if (
'/' + pub_topic.topic)
not in published_topics:
308 rospy.logwarn(
"[%s] topic '%s' is not published by the MiR!", rospy.get_name(), pub_topic.topic)
310 for sub_topic
in SUB_TOPICS:
312 if (
'/' + sub_topic.topic)
not in subscribed_topics:
313 rospy.logwarn(
"[%s] topic '%s' is not yet subscribed to by the MiR!", rospy.get_name(), sub_topic.topic)
316 srv_response = self.robot.callService(
'/rosapi/topics', msg={})
317 topic_names = sorted(srv_response[
'topics'])
320 for topic_name
in topic_names:
321 srv_response = self.robot.callService(
"/rosapi/topic_type", msg={
'topic': topic_name})
322 topic_type = srv_response[
'type']
324 srv_response = self.robot.callService(
"/rosapi/publishers", msg={
'topic': topic_name})
325 has_publishers =
True if len(srv_response[
'publishers']) > 0
else False 327 srv_response = self.robot.callService(
"/rosapi/subscribers", msg={
'topic': topic_name})
328 has_subscribers =
True if len(srv_response[
'subscribers']) > 0
else False 330 topics.append([topic_name, topic_type, has_publishers, has_subscribers])
333 for (topic_name, topic_type, has_publishers, has_subscribers)
in topics:
335 print ' * %s [%s]' % (topic_name, topic_type)
337 print '\nSubscribers:' 338 for (topic_name, topic_type, has_publishers, has_subscribers)
in topics:
340 print ' * %s [%s]' % (topic_name, topic_type)
346 rospy.init_node(
'mir_bridge')
350 if __name__ ==
'__main__':
353 except rospy.ROSInterruptException:
def peer_subscribe(self, topic_name, topic_publish, peer_publish)
def _move_base_feedback_dict_filter(msg_dict)
def __init__(self, topic_config, robot)
def __init__(self, topic_config, robot)
def __init__(self, topic, topic_type, latch=False, dict_filter=None)
def peer_unsubscribe(self, topic_name, num_peers)
def callback(self, msg_dict)
doesn't work: once ubsubscribed, robot doesn't let us subscribe again if self.pub.get_num_connections() == 0: rospy.loginfo("[%s] stopping to stream messages on topic '%s'", rospy.get_name(), self.topic_config.topic) self.robot.unsubscribe(topic=('/' + self.topic_config.topic))
def _prepend_tf_prefix_dict_filter(msg_dict)
def _tf_dict_filter(msg_dict)
def _move_base_result_dict_filter(msg_dict)
def _remove_tf_prefix_dict_filter(msg_dict)