gen_cpp.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2010, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of Willow Garage, Inc. nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 #
00034 
00035 import roslib; roslib.load_manifest('rve_interface_gen')
00036 import roslib.packages
00037 import rve_interface_gen.msgs as gen
00038 import roslib.msgs as msgs
00039 import roscpp.msg_gen as genmsg_cpp
00040 
00041 from cStringIO import StringIO
00042 
00043 import sys
00044 import os
00045 
00046 def write_header_begin(hs, i, pkg):
00047     print >> hs, '#ifndef INTERFACE_%s_%s_H'%(pkg.upper(), i.name.upper())
00048     print >> hs, '#define INTERFACE_%s_%s_H\n'%(pkg.upper(), i.name.upper())
00049     
00050 def write_header_end(hs, i, pkg):
00051     print >> hs, '#endif // INTERFACE_%s_%s_H'%(pkg.upper(), i.name.upper())
00052     
00053 def write_header_includes(hs, i, pkg):
00054     print >> hs, '#include <rve_interface_gen/interface.h>'
00055     print >> hs, '#include <ros/time.h>'
00056     print >> hs, '#include <ros/message_forward.h>'
00057     print >> hs, '#include <boost/function.hpp>'
00058     print >> hs, '#include <string>'
00059     
00060     headers = []
00061     for m in i.methods:
00062         for f in m.fields + m.return_fields:
00063             (base_type, is_array, array_len) = msgs.parse_type(f[0])
00064             if (is_array):
00065                 raise RuntimeError("Arrays are not supported as parameter or return-values")
00066             
00067             if (not msgs.is_builtin(base_type)):
00068                 resolved = msgs.resolve_type(base_type, pkg)
00069                 headers.append(resolved)
00070                 
00071     headers = set(headers)
00072     for h in headers:
00073         print >> hs, '#include <%s.h>'%(h)
00074     print >> hs
00075 
00076 def msg_to_cpp(type):
00077     if (type == "string"):
00078         return 'std::string'
00079     elif (msgs.is_builtin(type)):
00080         return genmsg_cpp.msg_type_to_cpp(type)
00081     else:
00082         components = type.split('/')
00083         if (len(components) == 1):
00084             return '%s'%(components[0])
00085         else:
00086             ns = components[0]
00087             c = components[1]
00088             return '%s::%s'%(ns, c)
00089     
00090 def write_header_forward_declarations(hs):
00091     print >> hs, 'namespace ros { class NodeHandle; }'
00092     print >> hs, 'namespace ros { template<typename M> class MessageEvent; }'
00093     print >> hs
00094     
00095 def write_header_message_forward_declarations(hs, i):
00096     for m in i.methods:
00097         print >> hs, 'ROS_DECLARE_MESSAGE(%s_%sRequest);'%(i.name, m.name)
00098         print >> hs, 'ROS_DECLARE_MESSAGE(%s_%sResponse);'%(i.name, m.name)
00099         
00100     print >> hs
00101     
00102 def normal_method_args(i, m, include_return_args = True):
00103     cpp_fields = []
00104     for f in m.fields:
00105         (type, _, _) = msgs.parse_type(f[0])
00106         name = f[1]
00107         
00108         cpp_type = msg_to_cpp(type)
00109         if (msgs.is_valid_constant_type(type) and type != "string"):
00110             cpp_fields.append('%s %s'%(cpp_type, name))
00111         else:
00112             cpp_fields.append('const %s& %s'%(cpp_type, name))
00113             
00114     if (include_return_args):
00115         for f in m.return_fields:
00116             (type, _, _) = msgs.parse_type(f[0])
00117             name = f[1]
00118             cpp_type = msg_to_cpp(type)
00119             cpp_fields.append('%s& out_%s'%(cpp_type, name))
00120         
00121     return cpp_fields
00122     
00123 def normal_method_args_string(i, m, include_return_args = True):
00124     return ', '.join(normal_method_args(i, m, include_return_args))
00125 
00126 def write_header_interface_declaration(hs, i, pkg):
00127     print >> hs, 'struct %s : public rve_interface_gen::Interface\n{'%(i.name)
00128     
00129     # Write virtual destructor
00130     print >> hs, '  virtual ~%s() {}'%(i.name)
00131     print >> hs
00132     
00133     for m in i.methods:
00134         print >> hs, '  typedef %s::%s_%sRequest %sRequest;'%(pkg, i.name, m.name, m.name)
00135         print >> hs, '  typedef boost::shared_ptr<%sRequest> %sRequestPtr;'%(m.name, m.name)
00136         print >> hs, '  typedef boost::shared_ptr<%sRequest const> %sRequestConstPtr;'%(m.name, m.name)
00137         print >> hs, '  typedef %s::%s_%sResponse %sResponse;'%(pkg, i.name, m.name, m.name)
00138         print >> hs, '  typedef boost::shared_ptr<%sResponse> %sResponsePtr;'%(m.name, m.name)
00139         print >> hs, '  typedef boost::shared_ptr<%sResponse const> %sResponseConstPtr;'%(m.name, m.name)
00140         print >> hs, '  typedef rve_rpc::CallHandle<%sRequest, %sResponse> %sHandle;'%(m.name, m.name, m.name)
00141         print >> hs, '  typedef rve_rpc::MethodResponse<%sResponse> %sMethodResponse;'%(m.name, m.name)
00142         print >> hs, '  typedef boost::function<void(const %sMethodResponse&)> %sResponseCallback;'%(m.name, m.name)
00143         print >> hs
00144     
00145     print >> hs, '};\n'
00146     
00147 def write_header_proxy_declaration(hs, i, pkg):
00148     print >> hs, 'struct %sProxy : public %s\n{'%(i.name, i.name)
00149     
00150     print >> hs, '  %sProxy(rve_rpc::Client& client);'%(i.name)
00151     
00152     for m in i.methods:
00153         # first way to call, of the form:
00154         # void <name>(arg0, arg1, ..., return_arg0&, return_arg1&, ...)
00155         print >> hs, '  void %s(%s);'%(m.name, normal_method_args_string(i, m))
00156         # second way to call, with asynchronous return of the form:
00157         # void <name>Async(arg0, arg1, ..., <name>ResponseCallback)
00158         print >> hs, '  void %sAsync(%s);'%(m.name, ', '.join(normal_method_args(i, m, False) + ['const %sResponseCallback& cb'%m.name]))
00159         # third way to call, with "fast" call/response, of the form:
00160         # <name>ResponseConstPtr <name>(<name>RequestConstPtr)
00161         print >> hs, '  %sResponseConstPtr %s(const %sRequestConstPtr& in);'%(m.name, m.name, m.name)
00162         # fourth way to call, with "fast" call and asynchronous response, of the form:
00163         # void <name>Async(<name>RequestConstPtr, <name>ResponseCallback)
00164         print >> hs, '  void %sAsync(const %sRequestConstPtr& in, const %sResponseCallback& cb);'%(m.name, m.name, m.name)
00165         
00166         # if there are no return args, provide a fifth and sixth ways to call:
00167         # void <name>Async(arg0, arg1, ...)
00168         # void <name>Async(<name>RequestConstPtr)    
00169         if (len(m.return_fields) == 0):
00170             print >> hs, '  void %sAsync(%s);'%(m.name, normal_method_args_string(i, m))
00171             print >> hs, '  void %sAsync(const %sRequestConstPtr& req);'%(m.name, m.name)
00172         
00173     print >> hs, 'private:'
00174     print >> hs, '  struct Impl;'
00175     print >> hs, '  typedef boost::shared_ptr<Impl> ImplPtr;'
00176     print >> hs, '  ImplPtr impl_;'
00177     
00178     print >> hs, '};\n'
00179     
00180 def write_header_server_declaration(hs, i, pkg):
00181     print >> hs, 'struct %sServer : public %s\n{'%(i.name, i.name)
00182     
00183     print >> hs, '  %sServer(rve_rpc::Server& server);'%(i.name)
00184     
00185     for m in i.methods:
00186         print >> hs, '  virtual void %s(%s) {ROS_BREAK();}'%(m.name, normal_method_args_string(i, m))
00187         print >> hs, '  virtual void %s(%sHandle& handle);'%(m.name, m.name)
00188         
00189     print >> hs, 'private:'
00190     print >> hs, '  struct Impl;'
00191     print >> hs, '  typedef boost::shared_ptr<Impl> ImplPtr;'
00192     print >> hs, '  ImplPtr impl_;'
00193     
00194     print >> hs, '};\n'
00195     
00196     
00197 def write_cpp_includes(cpps, i, pkg):
00198     print >> cpps, '#include <%s/%s.h>'%(pkg, i.name)
00199     print >> cpps, '#include <rve_rpc/client.h>'
00200     print >> cpps, '#include <rve_rpc/server.h>'
00201     
00202     for m in i.methods:
00203         print >> cpps, '#include <%s/%s_%sRequest.h>'%(pkg, i.name, m.name)
00204         print >> cpps, '#include <%s/%s_%sResponse.h>'%(pkg, i.name, m.name)
00205         
00206     print >> cpps
00207     print >> cpps, 'using namespace %s;\n'%(pkg)
00208 
00209 def write_cpp_proxy_methods(cpps, i, m, pkg):
00210     # first way to call, of the form:
00211     # void <name>(arg0, arg1, ..., return_arg0&, return_arg1&, ...)
00212     print >> cpps, 'void %sProxy::%s(%s)\n{'%(i.name, m.name, normal_method_args_string(i, m))
00213     print >> cpps, '  %sRequestPtr req(new %sRequest);'%(m.name, m.name)
00214     for field in m.fields:
00215         print >> cpps, '  req->%s = %s;'%(field[1], field[1])
00216     print >> cpps, '  %sResponseConstPtr res = impl_->%s_method_.call(req);'%(m.name, m.name)
00217     for field in m.return_fields:
00218         print >> cpps, '  out_%s = res->%s;'%(field[1], field[1])
00219     print >> cpps, '}\n'
00220     
00221     # second way to call, with asynchronous return of the form:
00222     # void <name>Async(arg0, arg1, ..., <name>ResponseCallback)
00223     print >> cpps, 'void %sProxy::%sAsync(%s)\n{'%(i.name, m.name, ', '.join(normal_method_args(i, m, False) + ['const %sResponseCallback& cb'%m.name]))
00224     print >> cpps, '  %sRequestPtr req(new %sRequest);'%(m.name, m.name)
00225     for field in m.fields:
00226         print >> cpps, '  req->%s = %s;'%(field[1], field[1])
00227     print >> cpps, '  impl_->%s_method_.callAsync(req, cb);'%(m.name)
00228     print >> cpps, '}\n'
00229     
00230     # third way to call, with "fast" call/response, of the form:
00231     # <name>ResponseConstPtr <name>(<name>RequestConstPtr)
00232     print >> cpps, '%s::%sResponseConstPtr %sProxy::%s(const %sRequestConstPtr& in)\n{'%(i.name, m.name, i.name, m.name, m.name)
00233     print >> cpps, '  return impl_->%s_method_.call(in);'%(m.name)
00234     print >> cpps, '}\n'
00235     
00236     # fourth way to call, with "fast" call and asynchronous response, of the form:
00237     # void <name>Async(<name>RequestConstPtr, <name>ResponseCallback)
00238     print >> cpps, 'void %sProxy::%sAsync(const %sRequestConstPtr& in, const %sResponseCallback& cb)\n{'%(i.name, m.name, m.name, m.name)
00239     print >> cpps, '  impl_->%s_method_.callAsync(in, cb);'%(m.name)
00240     print >> cpps, '}\n'
00241     
00242     # if there are no return args, provide fifth and sixth ways to call:
00243     # void <name>Async(arg0, arg1, ...)
00244     # void <name>Async(<name>RequestConstPtr) 
00245     if (len(m.return_fields) == 0):
00246         print >> cpps, 'void %sProxy::%sAsync(%s)\n{'%(i.name, m.name, normal_method_args_string(i, m))
00247         print >> cpps, '  %sRequestPtr req(new %sRequest);'%(m.name, m.name)
00248         for field in m.fields:
00249             print >> cpps, '  req->%s = %s;'%(field[1], field[1])
00250         print >> cpps, '  impl_->%s_method_.callAsync(req, %sResponseCallback());'%(m.name, m.name)
00251         print >> cpps, '}\n'
00252         
00253         print >> cpps, 'void %sProxy::%sAsync(const %sRequestConstPtr& in)\n{'%(i.name, m.name, m.name)
00254         print >> cpps, '  impl_->%s_method_.callAsync(in, %sResponseCallback());'%(m.name, m.name)
00255         print >> cpps, '}\n'
00256         
00257 
00258 def write_cpp_proxy_definition(cpps, i, pkg):    
00259     print >> cpps, 'struct %sProxy::Impl\n{'%(i.name)
00260     print >> cpps, """ 
00261   Impl(rve_rpc::Client& client)
00262   : client_(client)
00263   {
00264   }
00265 """
00266 
00267     print >> cpps, '  rve_rpc::Client client_;'
00268     for m in i.methods:
00269         print >> cpps, '  rve_rpc::Method<%sRequest, %sResponse> %s_method_;'%(m.name, m.name, m.name)
00270     print >> cpps, '};\n'
00271     
00272     print >> cpps, '%sProxy::%sProxy(rve_rpc::Client& client)'%(i.name, i.name)
00273     print >> cpps, ': impl_(new Impl(client))\n{'
00274     for m in i.methods:
00275         print >> cpps, '  impl_->%s_method_ = impl_->client_.addMethod<%sRequest, %sResponse>("%s_%s_%s");'%(m.name, m.name, m.name, pkg, i.name, m.name)
00276 
00277     print >> cpps, '}\n'
00278     
00279     for m in i.methods:
00280         write_cpp_proxy_methods(cpps, i, m, pkg)
00281         
00282 def write_cpp_server_definition(cpps, i, pkg):
00283     for m in i.methods:
00284         print >> cpps, '  void %sServer::%s(%sHandle& handle)\n  {'%(i.name, m.name, m.name)
00285         # prevent warning about unused variable 'req'
00286         if (len(m.fields) > 0):
00287             print >> cpps, '    const %sRequestConstPtr& req = handle.getRequest();'%(m.name)
00288         print >> cpps, '    %sResponsePtr res(new %sResponse);'%(m.name, m.name)
00289         print >> cpps, '    this->%s('%(m.name),
00290         print >> cpps, ', '.join([f for f in (', '.join(['req->%s'%(f[1]) for f in m.fields]), ', '.join(['res->%s'%(f[1]) for f in m.return_fields])) if len(f) > 0]),
00291         print >> cpps, ');\n'
00292         print >> cpps, '    handle.respond(res);'
00293         print >> cpps, '  }'
00294     
00295     print >> cpps, 'struct %sServer::Impl\n{'%(i.name)
00296     print >> cpps, """
00297   Impl(rve_rpc::Server& server, %sServer* parent)
00298   : server_(server)
00299   , parent_(parent)
00300   {
00301   }
00302 """%(i.name)
00303 
00304     for m in i.methods:
00305         print >> cpps, '  void %s_callback(%sHandle& handle)\n  {'%(m.name, m.name)
00306         print >> cpps, '    parent_->%s(handle);'%(m.name)
00307         print >> cpps, '  }'
00308 
00309     print >> cpps
00310     print >> cpps, '  rve_rpc::Server server_;'
00311     print >> cpps, '  %sServer* parent_;'%(i.name)
00312     print >> cpps, '};\n'
00313     
00314     print >> cpps, '%sServer::%sServer(rve_rpc::Server& server)'%(i.name, i.name)
00315     print >> cpps, ': impl_(new Impl(server, this))'
00316     print >> cpps, '{'
00317     for m in i.methods:
00318         print >> cpps, '  impl_->server_.addMethod<%sRequest, %sResponse>("%s_%s_%s", boost::bind(&Impl::%s_callback, impl_.get(), _1));'%(m.name, m.name, pkg, i.name, m.name, m.name)
00319     print >> cpps, '}'
00320     
00321 
00322 def generate(output_dir, i, pkg, pkg_path):
00323     hs = StringIO()
00324     cpps = StringIO()
00325     
00326     write_header_begin(hs, i, pkg)
00327     write_header_includes(hs, i, pkg)
00328     
00329     write_header_forward_declarations(hs)
00330     
00331     print >> hs, 'namespace %s\n{\n'%(pkg)
00332     
00333     write_header_message_forward_declarations(hs, i)
00334     write_header_interface_declaration(hs, i, pkg)
00335     write_header_proxy_declaration(hs, i, pkg)
00336     write_header_server_declaration(hs, i, pkg)
00337     
00338     print >> hs, '}\n'
00339     
00340     write_header_end(hs, i, pkg)
00341     
00342     write_cpp_includes(cpps, i, pkg)
00343     write_cpp_proxy_definition(cpps, i, pkg)
00344     write_cpp_server_definition(cpps, i, pkg)
00345     
00346     header_dir = '%s/include/%s'%(output_dir, pkg)
00347     cpp_dir = '%s/src'%(output_dir)
00348     try:
00349         os.makedirs(header_dir)
00350     except OSError, e:
00351         pass
00352     try:
00353         os.makedirs(cpp_dir)
00354     except OSError, e:
00355         pass
00356          
00357     f = open('%s/%s.h'%(header_dir, i.name), 'w')
00358     print >> f, hs.getvalue()
00359     f.close()
00360     
00361     f = open('%s/%s.cpp'%(cpp_dir, i.name), 'w')
00362     print >> f, cpps.getvalue()
00363     f.close()
00364 
00365 if __name__ == "__main__":
00366     input = sys.argv[1]
00367     output_dir = sys.argv[2]
00368         
00369     (package_dir, package) = roslib.packages.get_dir_pkg(input)
00370     p = gen.load_from_file(input)
00371     for i in p.interfaces:
00372         generate(output_dir, i, package, package_dir)
00373         


rve_interface_gen
Author(s): Josh Faust
autogenerated on Wed Dec 11 2013 14:31:00