9 from sensor_msgs.msg 
import Joy
 
   23             'abs': 
lambda x: abs(x),
 
   24             'max': 
lambda *x: max(*x),
 
   25             'min': 
lambda *x: min(*x),
 
   29         if isinstance(node, ast.Num):
 
   31         elif isinstance(node, ast.BinOp):
 
   35         elif isinstance(node, ast.UnaryOp):
 
   37             return op(self.
_reval_impl(node.operand, variables))
 
   38         elif isinstance(node, ast.Call) 
and node.func.id 
in self.
functions:
 
   40             args = [self.
_reval_impl(n, variables) 
for n 
in node.args]
 
   42         elif isinstance(node, ast.Name) 
and node.id 
in variables:
 
   43             return variables[node.id]
 
   44         elif isinstance(node, ast.Subscript) 
and node.value.id 
in variables:
 
   45             var = variables[node.value.id]
 
   46             idx = node.slice.value.n
 
   50                 raise IndexError(
"Variable '%s' out of range: %d >= %d" % (node.value.id, idx, len(var)))
 
   52             raise TypeError(
"Unsupported operation: %s" % node)
 
   54     def reval(self, expr, variables):
 
   57             raise ValueError(
"The length of an expression must not be more than 1000 characters")
 
   59             return self.
_reval_impl(ast.parse(expr, mode=
'eval').body, variables)
 
   60         except Exception 
as e:
 
   61             rospy.logerr(traceback.format_exc())
 
   70         self.
pub = rospy.Publisher(
 
   71             "joy_out", Joy, queue_size=1)
 
   73         self.
sub = rospy.Subscriber(
 
   75             queue_size=rospy.get_param(
"~queue_size", 
None))
 
   78         btn_remap = rospy.get_param(ns + 
"/buttons", [])
 
   79         axes_remap = rospy.get_param(ns + 
"/axes", [])
 
   80         rospy.loginfo(
"loaded remapping: %d buttons, %d axes" % (len(btn_remap), len(axes_remap)))
 
   81         return {
"buttons": btn_remap, 
"axes": axes_remap}
 
   84         if name == rospy.remap_name(name):
 
   85             rospy.logwarn(
"topic '%s' is not remapped" % name)
 
   88         out_msg = Joy(header=in_msg.header)
 
   91         out_msg.axes = [0.0] * len(map_axes)
 
   92         out_msg.buttons = [0] * len(map_btns)
 
   93         in_dic = {
"axes": in_msg.axes, 
"buttons": in_msg.buttons}
 
   94         for i, exp 
in enumerate(map_axes):
 
   96                 out_msg.axes[i] = self.
evaluator.reval(exp, in_dic)
 
   97             except NameError 
as e:
 
   98                 rospy.logerr(
"You are using vars other than 'buttons' or 'axes': %s" % e)
 
   99             except UnboundLocalError 
as e:
 
  100                 rospy.logerr(
"Wrong form: %s" % e)
 
  101             except Exception 
as e:
 
  104         for i, exp 
in enumerate(map_btns):
 
  106                 if self.
evaluator.reval(exp, in_dic) > 0:
 
  107                     out_msg.buttons[i] = 1
 
  108             except NameError 
as e:
 
  109                 rospy.logerr(
"You are using vars other than 'buttons' or 'axes': %s" % e)
 
  110             except UnboundLocalError 
as e:
 
  111                 rospy.logerr(
"Wrong form: %s" % e)
 
  112             except Exception 
as e:
 
  115         self.
pub.publish(out_msg)
 
  118 if __name__ == 
'__main__':
 
  119     rospy.init_node(
"joy_remap")