create_boost_header.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 import sys
00003 
00004 import roslib
00005 
00006 import gencpp
00007 import genmsg
00008 
00009 from  roslib import packages,msgs
00010 import os
00011 
00012 from cStringIO import StringIO
00013 
00014 import argparse
00015 
00016 NAME='create_boost_header'
00017 
00018 def write_boost_includes(s, spec):
00019     """
00020     Writes the message-specific includes
00021 
00022     @param s: The stream to write to
00023     @type s: stream
00024     @param spec: The message spec to iterate over
00025     @type spec: roslib.msgs.MsgSpec
00026     @param serializer: The serializer type for which to include headers
00027     @type serializer: str
00028     """
00029     for field in spec.parsed_fields():
00030         if (not field.is_builtin):
00031             (pkg, name) = genmsg.names.package_resource_name(field.base_type)
00032             pkg = (pkg or spec.package) # convert '' to this package
00033             s.write('#include <%s/boost/%s.h>\n'%(pkg,  name))
00034 
00035     s.write('\n')
00036 
00037 
00038 def write_boost_serialization(s, spec, cpp_name_prefix, file):
00039     """
00040     Writes the boost::serialize function for a message
00041 
00042     @param s: Stream to write to
00043     @type s: stream
00044     @param spec: The message spec
00045     @type spec: roslib.msgs.MsgSpec
00046     @param cpp_name_prefix: The C++ prefix to prepend to a message to refer to it (e.g. "std_msgs::")
00047     @type cpp_name_prefix: str
00048     """
00049     (cpp_msg_unqualified, cpp_msg_with_alloc, _) = gencpp.cpp_message_declarations(cpp_name_prefix, spec.short_name)
00050 
00051     s.write("/* Auto-generated by create_boost_header.py for file %s */\n"%(file))
00052     s.write('#ifndef %s_BOOST_SERIALIZATION_%s_H\n'%(spec.package.upper(), spec.short_name.upper()))
00053     s.write('#define %s_BOOST_SERIALIZATION_%s_H\n\n'%(spec.package.upper(), spec.short_name.upper()))
00054     s.write('#include <boost/serialization/serialization.hpp>\n')
00055     s.write('#include <boost/serialization/nvp.hpp>\n')
00056     s.write('#include <boost/serialization/vector.hpp>\n')
00057     s.write('#include <boost/serialization/string.hpp>\n')
00058     s.write('#include <%s/%s.h>\n'%(spec.package,spec.short_name))
00059     write_boost_includes(s, spec)
00060     s.write('namespace boost\n{\n')
00061     s.write('namespace serialization\n{\n\n')
00062 
00063     s.write('template<class Archive, class ContainerAllocator>\n')
00064 
00065     s.write('void serialize(Archive& a, %s & m, unsigned int)\n{\n'%(cpp_msg_with_alloc))
00066 
00067     for field in spec.parsed_fields():
00068         s.write('    a & make_nvp("%s",m.%s);\n'%(field.name,field.name))
00069     s.write('}\n\n')
00070 
00071     s.write('} // namespace serialization\n')
00072     s.write('} // namespace boost\n\n')
00073     s.write('#endif // %s_BOOST_SERIALIZATION_%s_H\n'%(spec.package.upper(), spec.short_name.upper()))
00074 
00075 
00076 
00077 def generate_boost_serialization(package, msg_path, msg_type, boost_header_path):
00078     """
00079     Generate a boost::serialization header
00080 
00081     @param msg_path: The path to the .msg file
00082     @type msg_path: str
00083     """
00084     mc = genmsg.msg_loader.MsgContext()
00085 
00086     spec = genmsg.msg_loader.load_msg_from_file(mc, msg_path, msg_type)
00087     cpp_prefix = '%s::'%(package)
00088 
00089     s = StringIO()
00090     write_boost_serialization(s, spec, cpp_prefix, msg_path)
00091 
00092     (output_dir,filename) = os.path.split(boost_header_path)
00093     try:
00094         os.makedirs(output_dir)
00095     except OSError, e:
00096         pass
00097 
00098     f = open(boost_header_path, 'w')
00099     print >> f, s.getvalue()
00100 
00101     s.close()
00102 
00103 
00104 def create_boost_headers(argv, stdout, stderr):
00105     parser = argparse.ArgumentParser(description='Generate boost serialization header for ROS message.')
00106     parser.add_argument('pkg',metavar='PKG',type=str, nargs=1,help='The package name.')
00107     parser.add_argument('msg_type',metavar='MSG_TYPE',type=str, nargs=1,help='The message type.')
00108     parser.add_argument('msg_file_path',metavar='MSG_FILE_PATH',type=str, nargs=1,help='The full path to a .msg file.')
00109     parser.add_argument('boost_file_path',metavar='BOOST_HEADER_PATH',type=str, nargs=1,help='The full path to the generated boost header file.')
00110 
00111     args = parser.parse_args()
00112 
00113     generate_boost_serialization(args.pkg[0], args.msg_file_path[0], args.msg_type[0], args.boost_file_path[0])
00114 
00115 if __name__ == "__main__":
00116     try:
00117         create_boost_headers(sys.argv, sys.stdout, sys.stderr)
00118     except Exception, e:
00119         sys.stderr.write("Failed to generate boost headers: " + str(e))
00120         raise
00121         #sys.exit(1)


rtt_roscomm
Author(s): Ruben Smits, Jonathan Bohren
autogenerated on Mon Apr 3 2017 03:34:43