00001
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)
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 <%s/%s.h>\n'%(spec.package,spec.short_name))
00057 write_boost_includes(s, spec)
00058 s.write('namespace boost\n{\n')
00059 s.write('namespace serialization\n{\n\n')
00060
00061 s.write('template<class Archive, class ContainerAllocator>\n')
00062
00063 s.write('void serialize(Archive& a, %s & m, unsigned int)\n{\n'%(cpp_msg_with_alloc))
00064
00065 for field in spec.parsed_fields():
00066 s.write(' a & make_nvp("%s",m.%s);\n'%(field.name,field.name))
00067 s.write('}\n\n')
00068
00069 s.write('} // namespace serialization\n')
00070 s.write('} // namespace boost\n\n')
00071 s.write('#endif // %s_BOOST_SERIALIZATION_%s_H\n'%(spec.package.upper(), spec.short_name.upper()))
00072
00073
00074
00075 def generate_boost_serialization(package, msg_path, msg_type, boost_header_path):
00076 """
00077 Generate a boost::serialization header
00078
00079 @param msg_path: The path to the .msg file
00080 @type msg_path: str
00081 """
00082 mc = genmsg.msg_loader.MsgContext()
00083
00084 spec = genmsg.msg_loader.load_msg_from_file(mc, msg_path, msg_type)
00085 cpp_prefix = '%s::'%(package)
00086
00087 s = StringIO()
00088 write_boost_serialization(s, spec, cpp_prefix, msg_path)
00089
00090 (output_dir,filename) = os.path.split(boost_header_path)
00091 try:
00092 os.makedirs(output_dir)
00093 except OSError, e:
00094 pass
00095
00096 f = open(boost_header_path, 'w')
00097 print >> f, s.getvalue()
00098
00099 s.close()
00100
00101
00102 def create_boost_headers(argv, stdout, stderr):
00103 parser = argparse.ArgumentParser(description='Generate boost serialization header for ROS message.')
00104 parser.add_argument('pkg',metavar='PKG',type=str, nargs=1,help='The package name.')
00105 parser.add_argument('msg_type',metavar='MSG_TYPE',type=str, nargs=1,help='The message type.')
00106 parser.add_argument('msg_file_path',metavar='MSG_FILE_PATH',type=str, nargs=1,help='The full path to a .msg file.')
00107 parser.add_argument('boost_file_path',metavar='BOOST_HEADER_PATH',type=str, nargs=1,help='The full path to the generated boost header file.')
00108
00109 args = parser.parse_args()
00110
00111 generate_boost_serialization(args.pkg[0], args.msg_file_path[0], args.msg_type[0], args.boost_file_path[0])
00112
00113 if __name__ == "__main__":
00114 try:
00115 create_boost_headers(sys.argv, sys.stdout, sys.stderr)
00116 except Exception, e:
00117 sys.stderr.write("Failed to generate boost headers: " + str(e))
00118 raise
00119