idl2srv.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 from __future__ import print_function
4 
5 from optparse import OptionParser
6 import os, os.path, sys, string, re
7 
8 if sys.version_info[0] >= 3:
9  from functools import reduce # python3
10 
11 # resolve library path, copied from omniidl (ubuntu 11.10)
12 # Try a path based on the installation prefix, customised for Debian
13 sppath = "/usr/lib/omniidl"
14 if os.path.isdir(sppath):
15  sys.path.append(sppath)
16 
17 from omniidl import idlast, idlvisitor, idlutil, idltype
18 from omniidl_be import cxx
19 import _omniidl
20 
21 # TODO
22 # not generate unused msgs
23 # how to manipulate namespace -> under score concat
24 
25 TypeNameMap = { # for ROS msg/srv
26  idltype.tk_boolean: 'bool',
27  idltype.tk_char: 'int8',
28  idltype.tk_octet: 'uint8',
29  idltype.tk_wchar: 'int16',
30  idltype.tk_short: 'int16',
31  idltype.tk_ushort: 'uint16',
32  idltype.tk_long: 'int32',
33  idltype.tk_ulong: 'uint32',
34  idltype.tk_longlong: 'int64',
35  idltype.tk_ulonglong: 'uint64',
36  idltype.tk_float: 'float32',
37  idltype.tk_double: 'float64',
38  idltype.tk_string: 'string',
39  idltype.tk_wstring: 'string',
40  idltype.tk_any: 'string', # ??
41  idltype.tk_TypeCode: 'uint64', # ??
42  idltype.tk_enum: 'uint64'}
43 
44 MultiArrayTypeNameMap = { # for ROS msg/srv
45  idltype.tk_char: 'std_msgs/Int8MultiArray',
46  idltype.tk_octet: 'std_msgs/Uint8MultiArray',
47  idltype.tk_wchar: 'std_msgs/Int16MultiArray',
48  idltype.tk_short: 'std_msgs/Int16MultiArray',
49  idltype.tk_ushort: 'std_msgs/Uint16MultiArray',
50  idltype.tk_long: 'std_msgs/Int32MultiArray',
51  idltype.tk_ulong: 'std_msgs/Uint32MultiArray',
52  idltype.tk_longlong: 'std_msgs/Int64MultiArray',
53  idltype.tk_ulonglong:'std_msgs/Uint64MultiArray',
54  idltype.tk_float: 'std_msgs/Float32MultiArray',
55  idltype.tk_double: 'std_msgs/Float64MultiArray',
56  idltype.tk_string: 'openrtm_ros_bridge/StringMultiArray'}
57 
58 # convert functions for IDL/ROS
59 # _CORBA_String_element type is env depend ??
60 convert_functions = """\n
61 template<typename T,typename S>
62 void genseq(S& s, int size, _CORBA_Unbounded_Sequence<T>* p){
63  s = S(size,size,S::allocbuf(size), 1);}
64 template<typename T,typename S,int n>
65 void genseq(S& s, int size, _CORBA_Bounded_Sequence<T,n>* p){
66  s = S(size,S::allocbuf(size), 1);}
67 template<class T1, class T2> inline
68 void convert(T1& in, T2& out){ out = static_cast<T2>(in); }
69 template<typename T>
70 void convert(T& in, std::string& out){ out = std::string(in); }
71 template<typename T>
72 void convert(std::string& in, T& out){ out = static_cast<T>(in.c_str()); }
73 void convert(_CORBA_String_element in, std::string& out){ out = std::string(in); }
74 void convert(std::string& in, _CORBA_String_element out){ out = (const char*)in.c_str(); }
75 template<class S,class T>
76 void convert(S& s, std::vector<T>& v){
77  int size = s.length();
78  v = std::vector<T>(s.length());
79  for(int i=0; i<size; i++) convert(s[i],v[i]);}
80 template<class S,class T>
81 void convert(std::vector<T>& v, S& s){
82  int size = v.size();
83  s = S(size, size, S::allocbuf(size), 1);
84  for(int i=0; i<size; i++) convert(v[i],s[i]);}
85 template<class S,class T,std::size_t n>
86 void convert(S& s, boost::array<T,n>& v){
87  for(std::size_t i=0; i<n; i++) convert(s[i],v[i]);}
88 template<class S,class T,std::size_t n>
89 void convert(boost::array<T,n>& v, S& s){
90  s = S(n, S::allocbuf(n), 1);
91  for(std::size_t i=0; i<n; i++) convert(v[i],s[i]);}
92 template<typename S,class T,std::size_t n>
93 void convert(boost::array<T,n>& v, S (&s)[n]){
94  for(std::size_t i=0; i<n; i++) convert(v[i],s[i]);}
95 
96 // special case for RTC::LightweightRTObject_var
97 template<class T> void convert(T& in, RTC::LightweightRTObject_var out){ std::cerr << "convert from RTC::LightweightRTObject_var is not supported" << std::endl; }
98 """
99 
100 multiarray_conversion = """
101 template<class S> // convert multi-dimensional array
102 void convert(S& s, %s& v){
103  if(v.layout.dim.size()==0 || v.layout.dim[v.layout.dim.size()-1].size==0) {
104  int level = v.layout.dim.size();
105  v.layout.dim.push_back(std_msgs::MultiArrayDimension());
106  v.layout.dim[level].stride = 1;
107  for(uint i=0; i<s.length(); i++){
108  convert(s[i], v);
109  if(i==0) v.layout.dim[level].size = s.length(); // initialized flag
110  }
111  for(uint i=level; i<v.layout.dim.size(); i++)
112  v.layout.dim[level].stride *= v.layout.dim[level].size;
113  } else {
114  for(uint i=0; i<s.length(); i++){ convert(s[i], v); }
115  }
116 }
117 template<>
118 void convert(%s& s, %s& v){ v.data.push_back(s); }
119 template<class S>
120 void convert(%s& v, S& s){
121  int level, size;
122  for(level=0; (size=v.layout.dim[level].size)==0; level++);
123  genseq(s, size, &s);
124  v.layout.dim[level].size = 0;
125  for(uint i=0; i<s.length(); i++)
126  convert(v, s[i]);
127  v.layout.dim[level].size = size;
128 }
129 template<>
130 void convert(%s& v, %s& s){ convert(v.data[v.layout.data_offset++], s); }
131 """ # % (std_msgs::Float64MultiArray, double, std_msgs::Float64MultiArray) + (std_msgs::Float64MultiArray, std_msgs::Float64MultiArray, double)
132 
133 # symbol type constant
134 NOT_FULL = 0
135 ROS_FULL = 1
136 CPP_FULL = 2
137 
138 # visitor for generate msg/srv/cpp/h for bridge compornents
139 class ServiceVisitor (idlvisitor.AstVisitor):
140 
141  def __init__(self):
142  self.generated_msgs = [] # type objects
143 
144  def visitAST(self, node):
145  for n in node.declarations():
146  n.accept(self)
147  def visitModule(self, node):
148  for n in node.definitions():
149  n.accept(self)
150  def visitInterface(self, node):
151  self.outputMsg(node)
152  for c in node.contents():
153  c.accept(self)
154  if node.mainFile():
155  self.genBridgeComponent(node)
156 
157  def visitOperation(self, node):
158  if node.mainFile():
159  self.outputSrv(node)
160  for n in node.parameters():
161  self.outputMsg(n.paramType())
162  n.accept(self)
163  self.outputMsg(node.returnType())
164 
167  def getCppTypeText(self, typ, out=False, full=NOT_FULL):
168  if isinstance(typ, idltype.Base):
169  return cxx.types.basic_map[typ.kind()]
170  if isinstance(typ, idltype.String):
171  return ('char*' if out else 'const char*') # ??
172  if isinstance(typ, idltype.Declared):
173  postfix = ('*' if out and cxx.types.variableDecl(typ.decl()) else '')
174  return self.getCppTypeText(typ.decl(), False, full) + postfix
175 
176  if isinstance(typ, idlast.Struct):
177  if full == CPP_FULL:
178  name = idlutil.ccolonName(typ.scopedName())
179  elif full == ROS_FULL:
180  return '_'.join(typ.scopedName()) # return
181  else:
182  name = typ.identifier()
183  return name + ('*' if out and cxx.types.variableDecl(typ) else '')
184  if isinstance(typ, idlast.Enum) or \
185  isinstance(typ, idlast.Interface) or \
186  isinstance(typ, idlast.Operation):
187  if full == CPP_FULL:
188  if ( idlutil.ccolonName(typ.scopedName()) == "RTC::LightweightRTObject") :
189  return idlutil.ccolonName(typ.scopedName())+"_var"
190  else:
191  return idlutil.ccolonName(typ.scopedName())
192  elif full == ROS_FULL:
193  return '_'.join(typ.scopedName())
194  else:
195  return typ.identifier()
196  if isinstance(typ, idlast.Typedef):
197  if full == CPP_FULL:
198  return idlutil.ccolonName(typ.declarators()[0].scopedName())
199  elif full == ROS_FULL:
200  return '_'.join(typ.declarators()[0].scopedName())
201  else:
202  return typ.declarators()[0].identifier()
203  if isinstance(typ, idlast.Declarator):
204  return self.getCppTypeText(typ.alias(), out, full)
205 
206  return 'undefined'
207 
208 
209  def getROSTypeText(self, typ):
210  if isinstance(typ, idltype.Base):
211  return TypeNameMap[typ.kind()]
212  if isinstance(typ, idltype.String) or isinstance(typ, idltype.WString):
213  return 'string' # ??
214  if isinstance(typ, idltype.Sequence):
215  etype = typ.seqType() # n-dimensional array -> 1-dimensional
216  size = typ.bound()
217  dim = 1
218  while not (isinstance(etype, idltype.Base) or isinstance(etype, idltype.String) or isinstance(etype, idltype.WString) or isinstance(etype, idlast.Struct) or isinstance(etype, idlast.Interface) or isinstance(etype, idlast.Enum) or isinstance(etype, idlast.Forward)):
219  if isinstance(etype, idltype.Declared):
220  etype = etype.decl()
221  elif isinstance(etype, idltype.Sequence):
222  dim += 1
223  size *= etype.bound()
224  etype = etype.seqType()
225  elif isinstance(etype, idlast.Typedef):
226  arrsize = [size] + etype.declarators()[0].sizes()
227  if(len(arrsize) != 1): dim += 1
228  size = reduce(lambda a,b: a*b, arrsize)
229  etype = etype.aliasType()
230  elif isinstance(etype, idlast.Declarator):
231  etype = etype.alias()
232 # elif isinstance(etype, idlast.Forward):
233 # etype = etype.fullDecl()
234  else:
235  return 'undefined'
236  if( 1 < dim ):
237  return MultiArrayTypeNameMap[etype.kind()]
238  return self.getROSTypeText(etype) + ('[]' if size==0 else '[%d]' % size)
239  if isinstance(typ, idltype.Declared):
240  return self.getROSTypeText(typ.decl())
241 
242  if isinstance(typ, idlast.Interface):
243  return '_'.join(typ.scopedName())
244  if isinstance(typ, idlast.Struct):
245  return '_'.join(typ.scopedName())
246  if isinstance(typ, idlast.Const):
247  return TypeNameMap[typ.constKind()]
248  if isinstance(typ, idlast.Enum):
249  return TypeNameMap[idltype.tk_longlong] # enum is int64 ??
250  if isinstance(typ, idlast.Union):
251  return TypeNameMap[idltype.tk_double] # union is not in ROS
252  if isinstance(typ, idlast.Typedef):
253  arraysize = typ.declarators()[0].sizes()
254  if 0 < len(arraysize):
255  return self.getROSTypeText(typ.aliasType()) + ('[%d]' % reduce(lambda a,b: a*b, arraysize))
256  return self.getROSTypeText(typ.aliasType())
257  if isinstance(typ, idlast.Declarator):
258  return self.getROSTypeText(typ.alias())
259  if isinstance(typ, idlast.Forward):
260  return self.getROSTypeText(typ.fullDecl())
261 
262  return 'undefined'
263 
264  # output .msg file defined in .idl
265  def outputMsg(self, typ):
266  if typ in self.generated_msgs:
267  return
268  elif isinstance(typ, idlast.Struct):
269  for mem in typ.members():
270  self.outputMsg(mem.memberType())
271  self.generated_msgs += [typ]
272  elif isinstance(typ, idlast.Enum) or \
273  isinstance(typ, idlast.Interface):
274  self.generated_msgs += [typ]
275  elif isinstance(typ, idltype.Sequence):
276  return self.outputMsg(typ.seqType())
277  elif isinstance(typ, idltype.Declared):
278  return self.outputMsg(typ.decl())
279  elif isinstance(typ, idlast.Typedef):
280  return self.outputMsg(typ.aliasType())
281  elif isinstance(typ, idlast.Declarator):
282  return self.outputMsg(typ.alias())
283  elif isinstance(typ, idlast.Forward):
284  return self.outputMsg(typ.fullDecl())
285  else:
286  return
287 
288  msgfile = basedir + "/msg/" + self.getCppTypeText(typ,full=ROS_FULL) + ".msg"
289  if not os.path.exists(basedir):
290  return
291  print(msgfile)
292  if options.filenames:
293  return
294 
295  if os.path.exists(msgfile) and (os.stat(msgfile).st_mtime > os.stat(idlfile).st_mtime) and not options.overwrite:
296  return # do not overwrite
297 
298  os.system('mkdir -p %s/msg' % basedir)
299  print("[idl2srv] writing "+msgfile+"....", file=sys.stderr)
300  fd = open(msgfile, 'w')
301  if isinstance(typ, idlast.Enum):
302  for val in typ.enumerators():
303  fd.write("%s %s=%d\n" % (self.getROSTypeText(typ), val.identifier(), val.value()))
304  elif isinstance(typ, idlast.Struct):
305  for mem in typ.members():
306  fd.write(self.getROSTypeText(mem.memberType()) + " " + mem.declarators()[0].identifier() + "\n")
307  elif isinstance(typ, idlast.Interface):
308  for mem in typ.contents():
309  if isinstance(mem, idlast.Const):
310  fd.write("%s %s=%s\n" % (self.getROSTypeText(mem), mem.identifier(), mem.value()))
311  fd.close()
312 
313  # output .srv file defined in .idl
314  def outputSrv(self, op):
315 
316  srvfile = basedir + "/srv/" + self.getCppTypeText(op,full=ROS_FULL) + ".srv"
317  if not os.path.exists(basedir):
318  return
319  print(srvfile)
320  if options.filenames:
321  return
322 
323  if os.path.exists(srvfile) and (os.stat(srvfile).st_mtime > os.stat(idlfile).st_mtime) and not options.overwrite:
324  return # do not overwrite
325  os.system('mkdir -p %s/srv' % basedir)
326  args = op.parameters()
327 
328  print("[idl2srv] writing "+srvfile+"....", file=sys.stderr)
329  fd = open(srvfile, 'w')
330  for arg in [arg for arg in args if arg.is_in()]:
331  fd.write("%s %s\n" % (self.getROSTypeText(arg.paramType()), arg.identifier()))
332  fd.write("---\n")
333  if not op.oneway() and op.returnType().kind() != idltype.tk_void:
334  fd.write("%s operation_return\n" % self.getROSTypeText(op.returnType()))
335  for arg in [arg for arg in args if arg.is_out()]:
336  fd.write("%s %s\n" % (self.getROSTypeText(arg.paramType()), arg.identifier()))
337  fd.close()
338 
339  def convertFunctionCode(self, interface):
340  visitor = DependencyVisitor()
341  interface.accept(visitor)
342  code = ''
343 
344  for typ in visitor.multiarray:
345  msg = MultiArrayTypeNameMap[typ.kind()].replace('/','::')
346  cpp = cxx.types.basic_map[typ.kind()]
347  code += multiarray_conversion % (msg,cpp,msg,msg,msg,cpp)
348 
349  for typ in visitor.allmsg:
350  if not isinstance(typ, idlast.Struct):
351  continue
352 
353  code += 'template<> void convert(%s& in, %s::%s& out){\n' % (self.getCppTypeText(typ, full=CPP_FULL), pkgname, self.getCppTypeText(typ,full=ROS_FULL))
354  for mem in typ.members():
355  var = mem.declarators()[0].identifier()
356  code += ' convert(in.%s, out.%s);\n' % (var, var)
357  code += '}\n'
358 
359  code += 'template<> void convert(%s::%s& in, %s& out){\n' % (pkgname, self.getCppTypeText(typ,full=ROS_FULL), self.getCppTypeText(typ, full=CPP_FULL))
360  for mem in typ.members():
361  var = mem.declarators()[0].identifier()
362  code += ' convert(in.%s, out.%s);\n' % (var, var)
363  code += '}\n'
364 
365  return code
366 
367  def ServiceBridgeFunction(self, op, ifname, pkgname):
368  code = req_code = res_code = ''
369  params = []
370  for par in op.parameters():
371  is_out = par.is_out()
372  ptype = par.paramType()
373  var = par.identifier()
374  # temporary variables
375  if isinstance(ptype.unalias(), idltype.Base) or \
376  isinstance(ptype.unalias(), idltype.String) or \
377  isinstance(ptype.unalias(), idltype.Sequence) or \
378  isinstance(ptype.unalias(), idltype.Declared):
379  code += ' %s %s;\n' % (self.getCppTypeText(ptype, out=is_out, full=CPP_FULL), var)
380  params += [var]
381  if isinstance(ptype.unalias(), idltype.Base) or \
382  isinstance(ptype.unalias(), idltype.String):
383  if is_out:
384  res_code += ' convert(%s, res.%s);\n' % (var, var)
385  else:
386  req_code += ' convert(req.%s, %s);\n' % (var, var)
387  if isinstance(ptype.unalias(), idltype.Sequence):
388  if is_out:
389  res_code += ' convert(*%s, res.%s);\n' % (var, var)
390  else:
391  req_code += ' convert(req.%s, %s);\n' % (var, var)
392  if isinstance(ptype.unalias(), idltype.Declared):
393  if is_out:
394  ptr = ('*' if cxx.types.variableDecl(ptype.decl()) else '')
395  res_code += ' convert(%s%s, res.%s);\n' % (ptr, var, var)
396  if cxx.types.variableDecl(ptype.decl()):
397  res_code += ' delete %s;\n' % (var)
398 
399  else:
400  req_code += ' convert(req.%s, %s);\n' % (var, var)
401 
402  code += '\n'
403  code += ' ROS_INFO_STREAM("%s::%s() called");\n' % (ifname, op.identifier())
404 
405  code += '\n' + req_code + '\n'
406 
407  code += ' try {\n'
408 
409  params = ', '.join(params)
410 
411  if op.oneway() or op.returnType().kind() == idltype.tk_void:
412  code += ' m_service0->%s(%s);\n' % (op.identifier(), params)
413  elif isinstance(op.returnType().unalias(), idltype.Base):
414  code += ' res.operation_return = m_service0->%s(%s);\n' % (op.identifier(), params)
415  else:
416  rtype = op.returnType()
417  if isinstance(rtype.unalias(), idltype.String):
418  ptr = ''
419  elif isinstance(rtype.unalias(), idltype.Sequence):
420  ptr = '*'
421  elif isinstance(rtype.unalias(), idltype.Declared):
422  ptr = ('*' if cxx.types.variableDecl(rtype.decl()) else '')
423  else: ptr = ''
424  code += ' %s operation_return;\n' % self.getCppTypeText(rtype, out=True, full=CPP_FULL)
425  code += ' operation_return = m_service0->%s(%s);\n' % (op.identifier(), params)
426  code += ' convert(%soperation_return, res.operation_return);\n' % ptr
427  connected_RTC_name = ifname[0:ifname.rindex("ServiceROSBridge")]
428  code += ' } catch(CORBA::COMM_FAILURE& ex) {\n'
429  code += ' ROS_ERROR_STREAM("%s::%s : Caught system exception COMM_FAILURE -- unable to contact the object [minor code = " << ex.minor() << "]. One possibility is IDL version mismatch between %s and %s. So please check IDL versions are consistent. Another possibility is that Service-Port function, %s of %s, called but %s died becase of it. So please check %s is still alive.");\n' % (ifname, op.identifier(), ifname, connected_RTC_name, op.identifier(), connected_RTC_name, connected_RTC_name, connected_RTC_name)
430  code += ' return false;\n'
431  code += ' } catch(CORBA::MARSHAL& ex) {\n'
432  code += ' ROS_ERROR_STREAM("%s::%s : Caught CORBA::SystemException::MARSHAL [minor code = " << ex.minor() << "]. One possibility is IDL version mismatch between %s and %s. So please check IDL versions are consistent.");\n' % (ifname, op.identifier(), ifname, connected_RTC_name)
433  code += ' return false;\n'
434  code += ' } catch(CORBA::BAD_PARAM& ex) {\n'
435  code += ' ROS_ERROR_STREAM("%s::%s : Caught CORBA::SystemException::BAD_PARAM [minor code = " << ex.minor() << "]. One possibility is that Service-Port function, %s of %s, called and some problem has occurred within it and %s keeps alive. So please check %s of %s is correctly finished.");\n' % (ifname, op.identifier(), op.identifier(), connected_RTC_name, connected_RTC_name, op.identifier(), connected_RTC_name)
436  code += ' return false;\n'
437  code += ' } catch(CORBA::OBJECT_NOT_EXIST& ex) {\n'
438  code += ' ROS_ERROR_STREAM("%s::%s : Caught CORBA::SystemException::OBJECT_NOT_EXIST [minor code = " << ex.minor() << "]. One possibility is that %s RTC is not found. So please check %s is still alive.");\n' % (ifname, op.identifier(), connected_RTC_name, connected_RTC_name)
439  code += ' return false;\n'
440  code += ' } catch(CORBA::SystemException& ex) {\n'
441  code += ' ROS_ERROR_STREAM("%s::%s : Caught CORBA::SystemException [minor code = " << ex.minor() << "].");\n' % (ifname, op.identifier())
442  code += ' return false;\n'
443  code += ' } catch(CORBA::Exception&) {\n'
444  code += ' ROS_ERROR_STREAM("%s::%s : Caught CORBA::Exception.");\n' % (ifname, op.identifier())
445  code += ' return false;\n'
446  code += ' } catch(omniORB::fatalException& fe) {\n'
447  code += ' ROS_ERROR_STREAM("%s::%s : Caught omniORB::fatalException:");\n' % (ifname, op.identifier())
448  code += ' ROS_ERROR_STREAM(" file: " << fe.file());\n'
449  code += ' ROS_ERROR_STREAM(" line: " << fe.line());\n'
450  code += ' ROS_ERROR_STREAM(" mesg: " << fe.errmsg());\n'
451  code += ' return false;\n'
452  code += ' }\n'
453  code += ' catch(...) {\n'
454  code += ' ROS_ERROR_STREAM("%s::%s : Caught unknown exception.");\n' % (ifname, op.identifier())
455  code += ' return false;\n'
456  code += ' }\n'
457 
458  code += res_code
459 
460  code += ' ROS_INFO_STREAM("%s::%s() succeeded");\n' % (ifname, op.identifier())
461 
462  return """bool %s::%s(%s::%s::Request &req, %s::%s::Response &res){\n%s\n return true;\n};\n\n""" % (ifname, op.identifier(), pkgname, self.getCppTypeText(op,full=ROS_FULL), pkgname, self.getCppTypeText(op,full=ROS_FULL), code)
463 
464  # generate cpp source to bridge RTM/ROS
465  def genBridgeComponent(self, interface):
466  idlfile = interface.file()
467  module_name = '%sROSBridge' % interface.identifier()
468  #service_name = idlutil.ccolonName(interface.scopedName())
469  service_name = interface.identifier()
470  idl_name = os.path.split(idlfile)[1]
471  wd = basedir + '/src_gen'
472 
473  Comp_cpp = wd + '/' + module_name + 'Comp.cpp'
474  mod_cpp = wd + '/' + module_name + '.cpp'
475  mod_h = wd + '/' + module_name + '.h'
476  print(Comp_cpp)
477  print(mod_cpp)
478  print(mod_h)
479  if options.filenames:
480  return
481 
482  if all([ os.path.exists(x) and os.stat(x).st_mtime > os.stat(idlfile).st_mtime for x in [Comp_cpp, mod_cpp, mod_h]]) and not options.overwrite:
483  return # do not overwrite
484 
485  # check if rtc-template exists under `rospack find openrtm_aist`/bin, otherwise use openrtm_aist_PREFIX/lib/openrtm_aist/bin
486  from subprocess import check_output, Popen, PIPE
487  openrtm_path = Popen(['rospack','find','openrtm_aist'], stdout=PIPE).communicate()[0].rstrip() # use Popen, not check_output, since catkin_make can not found rospack find
488  if not isinstance(openrtm_path, str):
489  openrtm_path = openrtm_path.decode('ascii')
490  if not os.path.exists(os.path.join(openrtm_path, "bin")) :
491  openrtm_prefix = check_output(['pkg-config','openrtm-aist','--variable=prefix']).rstrip()
492  if not isinstance(openrtm_prefix, str):
493  openrtm_prefix = openrtm_prefix.decode('ascii')
494  openrtm_path = os.path.join(openrtm_prefix,"lib/openrtm_aist")
495  command = "PATH=%s/bin:$PATH rtc-template -bcxx --module-name=%s --consumer=%s:service0:'%s' --consumer-idl=%s --idl-include=%s" % (openrtm_path, module_name, service_name, service_name, idlfile, idldir)
496  #command = "rosrun openrtm_aist rtc-template -bcxx --module-name=%s --consumer=%s:service0:'%s' --consumer-idl=%s --idl-include=%s" % (module_name, service_name, service_name, idlfile, idldir)
497  os.system("mkdir -p %s" % tmpdir)
498  os.system("mkdir -p %s" % wd)
499  os.system("cd %s; yes 2> /dev/null | %s > /dev/null" % (tmpdir, command))
500 
501  # TODO: ignore attribute read/write operators
502  operations = [o for o in interface.callables() if isinstance(o, idlast.Operation)]
503 
504  def addline(src, dest, ref):
505  idx = dest.find(ref)
506  idx = dest.find('\n',idx)
507  return dest[0:idx] + '\n' + src + dest[idx:]
508 
509  def replaceline(src, dest, ref):
510  idx1 = dest.find(ref)
511  idx2 = dest.find('\n',idx1)
512  return dest[0:idx1] + src + dest[idx2:]
513 
514  # Comp.cpp
515  # use ros node name as rtm component name
516  # call ros::init in Comp.cpp
517  compsrc = open(tmpdir + '/' + module_name + 'Comp.cpp').read()
518  compsrc = addline(' ros::init(argc, argv, "' + module_name + '", ros::init_options::NoSigintHandler);', compsrc, 'RTC::Manager::init(argc, argv);')
519  compsrc = replaceline(' comp = manager->createComponent(std::string("'+module_name+'?instance_name="+ros::this_node::getName().substr(1)).c_str()); // skip root name space for OpenRTM instance name', compsrc, ' comp = manager->createComponent("'+module_name+'");')
520  open(wd + '/' + module_name + 'Comp.cpp', 'w').write(compsrc)
521 
522  #.cpp
523  # make ROS service in onInitialize
524  # make ROS bridge functions in .cpp
525  compsrc = open(tmpdir + '/' + module_name + '.cpp').read()
526 
527  port_name_src = """ nh = ros::NodeHandle("~");
528  std::string port_name = "service0";
529  nh.getParam("service_port", port_name);"""
530  compsrc = addline(port_name_src, compsrc, 'Set service consumers to Ports')
531  compsrc = compsrc.replace('registerConsumer("service0"','registerConsumer(port_name.c_str()')
532 
533  compsrc += """
534 RTC::ReturnCode_t %s::onExecute(RTC::UniqueId ec_id) {
535  ros::spinOnce();
536  return RTC::RTC_OK;
537 }\n\n""" % module_name
538 
539  compsrc += "RTC::ReturnCode_t %s::onActivated(RTC::UniqueId ec_id) {\n" % module_name
540  for i in range(len(operations)):
541  name = operations[i].identifier()
542  compsrc += ' _srv%d = nh.advertiseService("%s", &%s::%s, this);\n' % (i, name, module_name, name)
543  compsrc +=" return RTC::RTC_OK;\n}\n\n"""
544 
545  compsrc += "RTC::ReturnCode_t %s::onDeactivated(RTC::UniqueId ec_id) {\n" % module_name
546  for i in range(len(operations)):
547  name = operations[i].identifier()
548  srvinst = ' _srv%d.shutdown();' % i
549  compsrc = addline(srvinst, compsrc, 'Unadvertise service')
550  compsrc +=" return RTC::RTC_OK;\n}\n\n"""
551 
552  compsrc += convert_functions + self.convertFunctionCode(interface)
553 
554  for op in operations:
555  compsrc += self.ServiceBridgeFunction(op, module_name, pkgname)
556  open(wd + '/' + module_name + '.cpp', 'w').write(compsrc)
557 
558  #.h
559  # add ros headers, service server functions, uncomment onExecute
560  compsrc = open(tmpdir + '/' + module_name + '.h').read()
561  compsrc = re.sub(basedir+"/idl/(.+).h", pkgname+r'/idl/\1.h', compsrc)
562 
563  compsrc = compsrc.replace('<%s>'%service_name, '<%s>'%idlutil.ccolonName(interface.scopedName()))
564 
565  incs = ['', '// ROS', '#include <ros/ros.h>']
566  incs += ['#include <%s/%s.h>' % (pkgname, self.getCppTypeText(op,full=ROS_FULL)) for op in operations]
567  incs = '\n'.join(incs)
568  compsrc = addline(incs, compsrc, '#define')
569 
570  compsrc = '\n'.join([ (a.replace('//','') if ('RTC::ReturnCode_t onExecute' in a) else a) for a in compsrc.split('\n')])
571  compsrc = '\n'.join([ (a.replace('//','') if ('RTC::ReturnCode_t onActivated' in a) else a) for a in compsrc.split('\n')])
572  compsrc = '\n'.join([ (a.replace('//','') if ('RTC::ReturnCode_t onDeactivated' in a) else a) for a in compsrc.split('\n')])
573 
574  srvfunc = [' bool %s(%s::%s::Request &req, %s::%s::Response &res);' % (op.identifier(), pkgname, self.getCppTypeText(op,full=ROS_FULL), pkgname, self.getCppTypeText(op,full=ROS_FULL)) for op in operations]
575  srvfunc = '\n'.join(srvfunc)
576  compsrc = addline(srvfunc, compsrc, 'public:')
577 
578  defsrv = " ros::NodeHandle nh;\n";
579  defsrv += " ros::ServiceServer " + ', '.join(['_srv%d' % i for i in range(len(operations))]) + ';'
580  compsrc = addline(defsrv, compsrc, 'private:')
581 
582  open(wd + '/' + module_name + '.h', 'w').write(compsrc)
583 
584  # finialize
585  ## os.system("rm -f %s" % tmpdir) remove tmpdir in rtmbuild.cmake
586  return
587 
588 # all types depended by a interface
589 class DependencyVisitor (idlvisitor.AstVisitor):
590  def __init__(self):
591  self.allmsg = []
592  self.multiarray = []
593  self.checked = []
594 
595  def visitInterface(self, node):
596  if node.mainFile():
597  for n in node.callables():
598  n.accept(self)
599 
600  def checkBasicType(self, node):
601  classes = [idltype.Base, idltype.String, idltype.WString]
602  classes += [idlast.Const, idlast.Enum, idlast.Union]
603  if not (any([isinstance(node, cls) for cls in classes]) or node in self.checked):
604  self.checked += [node]
605  node.accept(self)
606 
607  def visitOperation(self, node):
608  types = [p.paramType() for p in node.parameters()]
609  types += [node.returnType()]
610  for n in types:
611  self.checkBasicType(n)
612 
613  def visitStruct(self, node):
614  for mem in node.members():
615  self.checkBasicType(mem.memberType())
616  if not node in self.allmsg: # add self after all members
617  self.allmsg += [node]
618 
619  def visitSequenceType(self, node):
620  etype = node.seqType()
621  dim = 1
622  while not (isinstance(etype, idltype.Base) or isinstance(etype, idltype.String) or isinstance(etype, idltype.WString) or isinstance(etype, idlast.Struct) or isinstance(etype, idlast.Interface) or isinstance(etype, idlast.Enum) or isinstance(etype, idlast.Forward)):
623  if isinstance(etype, idltype.Sequence):
624  dim += 1
625  etype = etype.seqType()
626  elif isinstance(etype, idltype.Declared):
627  etype = etype.decl()
628  elif isinstance(etype, idlast.Typedef):
629  if len(etype.declarators()[0].sizes()) != 0 : dim += 1
630  etype = etype.aliasType()
631  elif isinstance(etype, idlast.Declarator):
632  etype = etype.alias()
633 # elif isinstance(etype, idlast.Forward):
634 # etype = etype.fullDecl()
635  if 1 < dim and isinstance(etype, idltype.Base) and (not etype in self.multiarray) :
636  self.multiarray += [etype]
637  self.checkBasicType(etype)
638  def visitDeclaredType(self, node):
639  self.checkBasicType(node.decl())
640  def visitTypedef(self, node):
641  self.checkBasicType(node.aliasType())
642  def visitDeclarator(self, node):
643  self.checkBasicType(node.alias())
644  def visitForward(self, node):
645  self.checkBasicType(node.fullDecl())
646 
647 
648 # visitor only prints interface names
649 class InterfaceNameVisitor (idlvisitor.AstVisitor):
650  def visitAST(self, node):
651  for n in node.declarations():
652  n.accept(self)
653  def visitModule(self, node):
654  for n in node.definitions():
655  n.accept(self)
656  def visitInterface(self, node):
657  if node.mainFile():
658  print(node.identifier())
659  if options.interfaces:
660  pass
661 
662 
663 if __name__ == '__main__':
664  global options, basedir, pkgname, tmpdir
665 
666  parser = OptionParser()
667  parser.add_option("-i", "--idl", dest="idlfile",
668  help="target idl file", metavar="FILE")
669  parser.add_option("-I", "--include-dirs", dest="idlpath", metavar="PATHLIST",
670  help="list of directories to check idl include")
671  parser.add_option("-o", "--overwrite", action="store_true",
672  dest="overwrite", default=False,
673  help="overwrite all generate files")
674  parser.add_option("--filenames", action="store_true",
675  dest="filenames", default=False,
676  help="print filenames to generate")
677  parser.add_option("--interfaces", action="store_true",
678  dest="interfaces", default=False,
679  help="print interface names")
680  parser.add_option("--package-name", action="store", type="string",
681  dest="package_name", default=False,
682  help="overwrite package name")
683  parser.add_option("--tmpdir", action="store", type="string",
684  dest="tmpdir", default="/tmp/idl2srv",
685  help="tmporary directory")
686  (options, args) = parser.parse_args()
687 
688  idlfile = options.idlfile
689  if not os.path.exists(idlfile):
690  exit
691  tmpdir = options.tmpdir
692  idlfile = os.path.abspath(idlfile)
693  idldir = os.path.split(idlfile)[0]
694  basedir = os.path.split(idldir)[0]
695  if options.package_name:
696  pkgname = options.package_name
697  else:
698  pkgname = os.path.split(basedir)[1] # global var
699 
700  # preproccess and compile idl
701  if options.idlpath:
702  pathlist = options.idlpath.strip('"')
703  option = ' '.join(['-I'+d for d in filter(None, pathlist.split(' '))])
704  else:
705  option = ''
706 
707  fd = os.popen('/usr/bin/omnicpp %s "%s"' % (option, idlfile), 'r')
708  try:
709  tree = _omniidl.compile(fd, idlfile) # newer version API
710  except:
711  tree = _omniidl.compile(fd) # old version API
712 
713  # output msg/srv and bridge component src
714  if options.interfaces:
715  tree.accept(InterfaceNameVisitor())
716  else:
717  tree.accept(ServiceVisitor())
718  tree.accept(InterfaceNameVisitor())
719 
def __init__(self)
Definition: idl2srv.py:141
def visitModule(self, node)
Definition: idl2srv.py:653
def visitInterface(self, node)
Definition: idl2srv.py:150
def visitOperation(self, node)
Definition: idl2srv.py:157
def checkBasicType(self, node)
Definition: idl2srv.py:600
def visitDeclaredType(self, node)
Definition: idl2srv.py:638
def visitAST(self, node)
Definition: idl2srv.py:650
def getCppTypeText(self, typ, out=False, full=NOT_FULL)
Definition: idl2srv.py:167
def convertFunctionCode(self, interface)
Definition: idl2srv.py:339
def visitInterface(self, node)
Definition: idl2srv.py:595
def outputMsg(self, typ)
Definition: idl2srv.py:265
def visitAST(self, node)
Definition: idl2srv.py:144
def visitDeclarator(self, node)
Definition: idl2srv.py:642
def visitOperation(self, node)
Definition: idl2srv.py:607
def genBridgeComponent(self, interface)
Definition: idl2srv.py:465
def visitStruct(self, node)
Definition: idl2srv.py:613
def outputSrv(self, op)
Definition: idl2srv.py:314
def visitTypedef(self, node)
Definition: idl2srv.py:640
def visitForward(self, node)
Definition: idl2srv.py:644
def visitSequenceType(self, node)
Definition: idl2srv.py:619
def visitInterface(self, node)
Definition: idl2srv.py:656
def getROSTypeText(self, typ)
Definition: idl2srv.py:209
def visitModule(self, node)
Definition: idl2srv.py:147
def ServiceBridgeFunction(self, op, ifname, pkgname)
Definition: idl2srv.py:367


rtmbuild
Author(s): Kei Okada , Manabu Saito
autogenerated on Mon May 10 2021 02:31:01