|
| 1 | +#!/usr/bin/env python |
| 2 | +# -*- coding: utf-8 -*- |
| 3 | + |
| 4 | +import sys |
| 5 | +from importlib import import_module |
| 6 | + |
| 7 | +import roslib.message |
| 8 | +import rospy |
| 9 | +import std_msgs.msg |
| 10 | + |
| 11 | + |
| 12 | +def expr_eval(expr, modules): |
| 13 | + def eval_fn(topic, m, t): |
| 14 | + return eval(expr, modules, {'m': m}) |
| 15 | + return eval_fn |
| 16 | + |
| 17 | + |
| 18 | +class FilteredRelay(object): |
| 19 | + |
| 20 | + def __init__(self): |
| 21 | + import_list = rospy.get_param('~import', []) |
| 22 | + self.modules = {} |
| 23 | + for module in import_list: |
| 24 | + try: |
| 25 | + mod = import_module(module) |
| 26 | + except ImportError: |
| 27 | + rospy.logerr('Failed to import module: %s' % module, file=sys.stderr) |
| 28 | + else: |
| 29 | + self.modules[module] = mod |
| 30 | + |
| 31 | + self.filter_expression = rospy.get_param('~filter', None) |
| 32 | + if self.filter_expression is not None: |
| 33 | + self.filter_expression = expr_eval(self.filter_expression, self.modules) |
| 34 | + |
| 35 | + self.output_type = rospy.get_param('~output_type') |
| 36 | + self.output_class = roslib.message.get_message_class(self.output_type) |
| 37 | + |
| 38 | + self.transform_expression = rospy.get_param('~transform', 'm') |
| 39 | + self.pub_transform = rospy.Publisher( |
| 40 | + '~output', |
| 41 | + self.output_class, queue_size=1) |
| 42 | + |
| 43 | + self.topic_name = rospy.resolve_name('~input') |
| 44 | + self.sub = rospy.Subscriber( |
| 45 | + self.topic_name, |
| 46 | + rospy.AnyMsg, |
| 47 | + callback=lambda msg, tn=self.topic_name: self.callback(tn, msg), |
| 48 | + queue_size=1) |
| 49 | + |
| 50 | + def publish(self, m): |
| 51 | + if self.output_type == 'std_msgs/Empty': |
| 52 | + self.pub_transform.publish() |
| 53 | + return |
| 54 | + if self.transform_expression is not None: |
| 55 | + try: |
| 56 | + res = eval(self.transform_expression, self.modules, {'m': m}) |
| 57 | + except NameError as e: |
| 58 | + rospy.logerr("Expression using variables other than 'm': %s" |
| 59 | + % e.message, file=sys.stderr) |
| 60 | + except UnboundLocalError as e: |
| 61 | + rospy.logerr('Wrong expression:%s' % e.message, |
| 62 | + file=sys.stderr) |
| 63 | + except Exception as e: |
| 64 | + rospy.logerr(str(e)) |
| 65 | + else: |
| 66 | + if not isinstance(res, (list, tuple)): |
| 67 | + res = [res] |
| 68 | + self.pub_transform.publish(*res) |
| 69 | + else: |
| 70 | + self.pub_transform.publish(m) |
| 71 | + |
| 72 | + def callback(self, topic_name, msg): |
| 73 | + if isinstance(msg, rospy.msg.AnyMsg): |
| 74 | + package, msg_type = msg._connection_header['type'].split('/') |
| 75 | + ros_pkg = package + '.msg' |
| 76 | + msg_class = getattr(import_module(ros_pkg), msg_type) |
| 77 | + self.sub.unregister() |
| 78 | + deserialized_sub = rospy.Subscriber( |
| 79 | + topic_name, msg_class, |
| 80 | + lambda msg, tn=topic_name: self.callback(tn, msg)) |
| 81 | + self.sub = deserialized_sub |
| 82 | + msg = msg_class().deserialize(msg._buff) |
| 83 | + if self.filter_expression is not None: |
| 84 | + if self.filter_expression(topic_name, msg, rospy.Time.now()): |
| 85 | + self.publish(msg) |
| 86 | + else: |
| 87 | + self.publish(msg) |
| 88 | + |
| 89 | + |
| 90 | +if __name__ == '__main__': |
| 91 | + rospy.init_node('filtered_relay') |
| 92 | + node = FilteredRelay() |
| 93 | + rospy.spin() |
0 commit comments