create_boost_headers.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 import sys
00003 
00004 import roslib
00005 roslib.load_manifest("rtt_rosnode");
00006 
00007 try:
00008     if(roslib.stacks.get_stack_version('ros')<'1.8.0'):
00009         import roscpp
00010         import roscpp.msg_gen as gencpp
00011     else:
00012         import gencpp
00013 except:
00014     import gencpp
00015 
00016 from  roslib import packages,msgs 
00017 import os
00018 
00019 from cStringIO import StringIO
00020 
00021 NAME='create_boost_headers'
00022 
00023 def write_boost_includes(s, spec):
00024     """
00025     Writes the message-specific includes
00026     
00027     @param s: The stream to write to
00028     @type s: stream
00029     @param spec: The message spec to iterate over
00030     @type spec: roslib.msgs.MsgSpec
00031     @param serializer: The serializer type for which to include headers
00032     @type serializer: str
00033     """
00034     for field in spec.parsed_fields():
00035         if (not field.is_builtin):
00036             if (field.is_header):
00037                 s.write('#include <ros/common.h>\n')
00038                 s.write('#if ROS_VERSION_MINIMUM(1,4,0)\n')
00039                 s.write('#include <std_msgs/Header.h>\n')
00040                 s.write('#else\n')
00041                 s.write('#include <roslib/Header.h>\n')
00042                 s.write('#endif\n')
00043             else:
00044                 (pkg, name) = roslib.names.package_resource_name(field.base_type)
00045                 pkg = pkg or spec.package # convert '' to package
00046                 s.write('#include "%s/boost/%s.h"\n'%(pkg,  name))
00047                 
00048     s.write('\n') 
00049 
00050 
00051 def write_boost_serialization(s, spec, cpp_name_prefix, file):
00052     """
00053     Writes the boost::serialize function for a message
00054     
00055     @param s: Stream to write to
00056     @type s: stream
00057     @param spec: The message spec
00058     @type spec: roslib.msgs.MsgSpec
00059     @param cpp_name_prefix: The C++ prefix to prepend to a message to refer to it (e.g. "std_msgs::")
00060     @type cpp_name_prefix: str
00061     """
00062     (cpp_msg_unqualified, cpp_msg_with_alloc, _) = gencpp.cpp_message_declarations(cpp_name_prefix, spec.short_name)
00063     
00064     s.write("/* Auto-generated by genmsg_cpp for file %s */\n"%(file))
00065     s.write('#ifndef %s_BOOST_SERIALIZATION_%s_H\n'%(spec.package.upper(), spec.short_name.upper()))
00066     s.write('#define %s_BOOST_SERIALIZATION_%s_H\n\n'%(spec.package.upper(), spec.short_name.upper()))
00067     s.write('#include <boost/serialization/serialization.hpp>\n')
00068     s.write('#include <boost/serialization/nvp.hpp>\n')
00069     s.write('#include <%s/%s.h>\n'%(spec.package,spec.short_name))
00070     write_boost_includes(s, spec)
00071     s.write('namespace boost\n{\n')
00072     s.write('namespace serialization\n{\n\n')
00073     
00074     s.write('template<class Archive, class ContainerAllocator>\n')
00075 
00076     s.write('void serialize(Archive& a, %s & m, unsigned int)\n{\n'%(cpp_msg_with_alloc))
00077     
00078     for field in spec.parsed_fields():
00079         s.write('    a & make_nvp("%s",m.%s);\n'%(field.name,field.name))
00080     s.write('}\n\n')
00081         
00082     s.write('} // namespace serialization\n')
00083     s.write('} // namespace boost\n\n')
00084     s.write('#endif // %s_BOOST_SERIALIZATION_%s_H\n'%(spec.package.upper(), spec.short_name.upper()))
00085     
00086 
00087 
00088 def generate_boost_serialization(msg_path):
00089     """
00090     Generate a boost::serialization header
00091     
00092     @param msg_path: The path to the .msg file
00093     @type msg_path: str
00094     """
00095     (package_dir, package) = roslib.packages.get_dir_pkg(msg_path)
00096     (_, spec) = roslib.msgs.load_from_file(msg_path, package)
00097     cpp_prefix = '%s::'%(package)
00098     
00099     s = StringIO()
00100     write_boost_serialization(s, spec, cpp_prefix, msg_path)
00101     
00102     output_dir = 'include/%s/boost'%(package)
00103     try:
00104         os.makedirs(output_dir)
00105     except OSError, e:
00106         pass
00107          
00108     f = open('%s/%s.h'%(output_dir, spec.short_name), 'w')
00109     print >> f, s.getvalue()
00110     
00111     s.close()
00112 
00113 
00114 def create_boost_headers(argv, stdout, stderr):
00115     from optparse import OptionParser
00116     parser = OptionParser(usage="usage: %prog [packages]", prog=NAME)
00117     (options, args) = parser.parse_args(argv)
00118 
00119     # get the file name
00120     if len(args) < 2:
00121         parser.error("you must specify at least package")
00122     pkgs = args[1:]
00123     for pkg in pkgs:
00124         pp = roslib.packages.get_pkg_dir(pkg);
00125         msgs = roslib.msgs.list_msg_types(pkg,False)
00126         for msg in msgs:
00127             generate_boost_serialization(pp+'/msg/'+msg+'.msg')
00128 
00129 if __name__ == "__main__":
00130     try:
00131         create_boost_headers(sys.argv, sys.stdout, sys.stderr)
00132     except Exception, e:
00133         print >> sys.stderr, e
00134         sys.exit(1)


rtt_rosnode
Author(s): Ruben Smits, ruben.smits@mech.kuleuven.be
autogenerated on Mon Oct 6 2014 07:24:21