00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 import roslib; roslib.load_manifest('roscpp')
00040
00041 import sys
00042 import os
00043 import traceback
00044
00045 import roslib.msgs
00046 import roslib.packages
00047 import roslib.gentools
00048
00049 from cStringIO import StringIO
00050
00051 MSG_TYPE_TO_CPP = {'byte': 'int8_t', 'char': 'uint8_t',
00052 'bool': 'uint8_t',
00053 'uint8': 'uint8_t', 'int8': 'int8_t',
00054 'uint16': 'uint16_t', 'int16': 'int16_t',
00055 'uint32': 'uint32_t', 'int32': 'int32_t',
00056 'uint64': 'uint64_t', 'int64': 'int64_t',
00057 'float32': 'float',
00058 'float64': 'double',
00059 'string': 'std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > ',
00060 'time': 'ros::Time',
00061 'duration': 'ros::Duration'}
00062
00063 def msg_type_to_cpp(type):
00064 """
00065 Converts a message type (e.g. uint32, std_msgs/String, etc.) into the C++ declaration
00066 for that type (e.g. uint32_t, std_msgs::String_<ContainerAllocator>)
00067
00068 @param type: The message type
00069 @type type: str
00070 @return: The C++ declaration
00071 @rtype: str
00072 """
00073 (base_type, is_array, array_len) = roslib.msgs.parse_type(type)
00074 cpp_type = None
00075 if (roslib.msgs.is_builtin(base_type)):
00076 cpp_type = MSG_TYPE_TO_CPP[base_type]
00077 elif (len(base_type.split('/')) == 1):
00078 if (roslib.msgs.is_header_type(base_type)):
00079 cpp_type = ' ::std_msgs::Header_<ContainerAllocator> '
00080 else:
00081 cpp_type = '%s_<ContainerAllocator> '%(base_type)
00082 else:
00083 pkg = base_type.split('/')[0]
00084 msg = base_type.split('/')[1]
00085 cpp_type = ' ::%s::%s_<ContainerAllocator> '%(pkg, msg)
00086
00087 if (is_array):
00088 if (array_len is None):
00089 return 'std::vector<%s, typename ContainerAllocator::template rebind<%s>::other > '%(cpp_type, cpp_type)
00090 else:
00091 return 'boost::array<%s, %s> '%(cpp_type, array_len)
00092 else:
00093 return cpp_type
00094
00095 def cpp_message_declarations(name_prefix, msg):
00096 """
00097 Returns the different possible C++ declarations for a message given the message itself.
00098
00099 @param name_prefix: The C++ prefix to be prepended to the name, e.g. "std_msgs::"
00100 @type name_prefix: str
00101 @param msg: The message type
00102 @type msg: str
00103 @return: A tuple of 3 different names. cpp_message_decelarations("std_msgs::", "String") returns the tuple
00104 ("std_msgs::String_", "std_msgs::String_<ContainerAllocator>", "std_msgs::String")
00105 @rtype: str
00106 """
00107 pkg, basetype = roslib.names.package_resource_name(msg)
00108 cpp_name = ' ::%s%s'%(name_prefix, msg)
00109 if (pkg):
00110 cpp_name = ' ::%s::%s'%(pkg, basetype)
00111 return ('%s_'%(cpp_name), '%s_<ContainerAllocator> '%(cpp_name), '%s'%(cpp_name))
00112
00113 def write_begin(s, spec, file):
00114 """
00115 Writes the beginning of the header file: a comment saying it's auto-generated and the include guards
00116
00117 @param s: The stream to write to
00118 @type s: stream
00119 @param spec: The spec
00120 @type spec: roslib.msgs.MsgSpec
00121 @param file: The file this message is being generated for
00122 @type file: str
00123 """
00124 s.write("/* Auto-generated by genmsg_cpp for file %s */\n"%(file))
00125 s.write('#ifndef %s_MESSAGE_%s_H\n'%(spec.package.upper(), spec.short_name.upper()))
00126 s.write('#define %s_MESSAGE_%s_H\n'%(spec.package.upper(), spec.short_name.upper()))
00127
00128 def write_end(s, spec):
00129 """
00130 Writes the end of the header file: the ending of the include guards
00131
00132 @param s: The stream to write to
00133 @type s: stream
00134 @param spec: The spec
00135 @type spec: roslib.msgs.MsgSpec
00136 """
00137 s.write('#endif // %s_MESSAGE_%s_H\n'%(spec.package.upper(), spec.short_name.upper()))
00138
00139 def write_generic_includes(s):
00140 """
00141 Writes the includes that all messages need
00142
00143 @param s: The stream to write to
00144 @type s: stream
00145 """
00146 s.write('#include <string>\n')
00147 s.write('#include <vector>\n')
00148 s.write('#include <ostream>\n')
00149 s.write('#include "ros/serialization.h"\n')
00150 s.write('#include "ros/builtin_message_traits.h"\n')
00151 s.write('#include "ros/message_operations.h"\n')
00152 s.write('#include "ros/message.h"\n')
00153 s.write('#include "ros/time.h"\n\n')
00154
00155 def write_includes(s, spec):
00156 """
00157 Writes the message-specific includes
00158
00159 @param s: The stream to write to
00160 @type s: stream
00161 @param spec: The message spec to iterate over
00162 @type spec: roslib.msgs.MsgSpec
00163 """
00164 for field in spec.parsed_fields():
00165 if (not field.is_builtin):
00166 if (field.is_header):
00167 s.write('#include "std_msgs/Header.h"\n')
00168 else:
00169 (pkg, name) = roslib.names.package_resource_name(field.base_type)
00170 pkg = pkg or spec.package
00171 s.write('#include "%s/%s.h"\n'%(pkg, name))
00172
00173 s.write('\n')
00174
00175
00176 def write_struct(s, spec, cpp_name_prefix, extra_deprecated_traits = {}):
00177 """
00178 Writes the entire message struct: declaration, constructors, members, constants and (deprecated) member functions
00179 @param s: The stream to write to
00180 @type s: stream
00181 @param spec: The message spec
00182 @type spec: roslib.msgs.MsgSpec
00183 @param cpp_name_prefix: The C++ prefix to use when referring to the message, e.g. "std_msgs::"
00184 @type cpp_name_prefix: str
00185 """
00186
00187 msg = spec.short_name
00188 s.write('template <class ContainerAllocator>\n')
00189 s.write('struct %s_ : public ros::Message\n{\n'%(msg))
00190 s.write(' typedef %s_<ContainerAllocator> Type;\n\n'%(msg))
00191
00192 write_constructors(s, spec, cpp_name_prefix)
00193 write_members(s, spec)
00194 write_constant_declarations(s, spec)
00195
00196 gendeps_dict = roslib.gentools.get_dependencies(spec, spec.package, compute_files=False)
00197 md5sum = roslib.gentools.compute_md5(gendeps_dict)
00198 full_text = compute_full_text_escaped(gendeps_dict)
00199
00200 write_deprecated_member_functions(s, spec, dict({'MD5Sum': md5sum, 'DataType': '%s/%s'%(spec.package, spec.short_name), 'MessageDefinition': full_text}.items() + extra_deprecated_traits.items()))
00201
00202 (cpp_msg_unqualified, cpp_msg_with_alloc, cpp_msg_base) = cpp_message_declarations(cpp_name_prefix, msg)
00203 s.write(' typedef boost::shared_ptr<%s> Ptr;\n'%(cpp_msg_with_alloc))
00204 s.write(' typedef boost::shared_ptr<%s const> ConstPtr;\n'%(cpp_msg_with_alloc))
00205 s.write('}; // struct %s\n'%(msg))
00206
00207 s.write('typedef %s_<std::allocator<void> > %s;\n\n'%(cpp_msg_base, msg))
00208 s.write('typedef boost::shared_ptr<%s> %sPtr;\n'%(cpp_msg_base, msg))
00209 s.write('typedef boost::shared_ptr<%s const> %sConstPtr;\n\n'%(cpp_msg_base, msg))
00210
00211 def default_value(type):
00212 """
00213 Returns the value to initialize a message member with. 0 for integer types, 0.0 for floating point, false for bool,
00214 empty string for everything else
00215
00216 @param type: The type
00217 @type type: str
00218 """
00219 if type in ['byte', 'int8', 'int16', 'int32', 'int64',
00220 'char', 'uint8', 'uint16', 'uint32', 'uint64']:
00221 return '0'
00222 elif type in ['float32', 'float64']:
00223 return '0.0'
00224 elif type == 'bool':
00225 return 'false'
00226
00227 return ""
00228
00229 def takes_allocator(type):
00230 """
00231 Returns whether or not a type can take an allocator in its constructor. False for all builtin types except string.
00232 True for all others.
00233
00234 @param type: The type
00235 @type: str
00236 """
00237 return not type in ['byte', 'int8', 'int16', 'int32', 'int64',
00238 'char', 'uint8', 'uint16', 'uint32', 'uint64',
00239 'float32', 'float64', 'bool', 'time', 'duration']
00240
00241 def write_initializer_list(s, spec, container_gets_allocator):
00242 """
00243 Writes the initializer list for a constructor
00244
00245 @param s: The stream to write to
00246 @type s: stream
00247 @param spec: The message spec
00248 @type spec: roslib.msgs.MsgSpec
00249 @param container_gets_allocator: Whether or not a container type (whether it's another message, a vector, array or string)
00250 should have the allocator passed to its constructor. Assumes the allocator is named _alloc.
00251 @type container_gets_allocator: bool
00252 """
00253
00254 i = 0
00255 for field in spec.parsed_fields():
00256 if (i == 0):
00257 s.write(' : ')
00258 else:
00259 s.write(' , ')
00260
00261 val = default_value(field.base_type)
00262 use_alloc = takes_allocator(field.base_type)
00263 if (field.is_array):
00264 if (field.array_len is None and container_gets_allocator):
00265 s.write('%s(_alloc)\n'%(field.name))
00266 else:
00267 s.write('%s()\n'%(field.name))
00268 else:
00269 if (container_gets_allocator and use_alloc):
00270 s.write('%s(_alloc)\n'%(field.name))
00271 else:
00272 s.write('%s(%s)\n'%(field.name, val))
00273 i = i + 1
00274
00275 def write_fixed_length_assigns(s, spec, container_gets_allocator, cpp_name_prefix):
00276 """
00277 Initialize any fixed-length arrays
00278
00279 @param s: The stream to write to
00280 @type s: stream
00281 @param spec: The message spec
00282 @type spec: roslib.msgs.MsgSpec
00283 @param container_gets_allocator: Whether or not a container type (whether it's another message, a vector, array or string)
00284 should have the allocator passed to its constructor. Assumes the allocator is named _alloc.
00285 @type container_gets_allocator: bool
00286 @param cpp_name_prefix: The C++ prefix to use when referring to the message, e.g. "std_msgs::"
00287 @type cpp_name_prefix: str
00288 """
00289
00290 for field in spec.parsed_fields():
00291 if (not field.is_array or field.array_len is None):
00292 continue
00293
00294 val = default_value(field.base_type)
00295 if (container_gets_allocator and takes_allocator(field.base_type)):
00296
00297 if (field.base_type == "string"):
00298 string_cpp = msg_type_to_cpp("string")
00299 s.write(' %s.assign(%s(_alloc));\n'%(field.name, string_cpp))
00300 else:
00301 (cpp_msg_unqualified, cpp_msg_with_alloc, _) = cpp_message_declarations(cpp_name_prefix, field.base_type)
00302 s.write(' %s.assign(%s(_alloc));\n'%(field.name, cpp_msg_with_alloc))
00303 elif (len(val) > 0):
00304 s.write(' %s.assign(%s);\n'%(field.name, val))
00305
00306 def write_constructors(s, spec, cpp_name_prefix):
00307 """
00308 Writes any necessary constructors for the message
00309
00310 @param s: The stream to write to
00311 @type s: stream
00312 @param spec: The message spec
00313 @type spec: roslib.msgs.MsgSpec
00314 @param cpp_name_prefix: The C++ prefix to use when referring to the message, e.g. "std_msgs::"
00315 @type cpp_name_prefix: str
00316 """
00317
00318 msg = spec.short_name
00319
00320
00321 s.write(' %s_()\n'%(msg))
00322 write_initializer_list(s, spec, False)
00323 s.write(' {\n')
00324 write_fixed_length_assigns(s, spec, False, cpp_name_prefix)
00325 s.write(' }\n\n')
00326
00327
00328 s.write(' %s_(const ContainerAllocator& _alloc)\n'%(msg))
00329 write_initializer_list(s, spec, True)
00330 s.write(' {\n')
00331 write_fixed_length_assigns(s, spec, True, cpp_name_prefix)
00332 s.write(' }\n\n')
00333
00334 def write_member(s, field):
00335 """
00336 Writes a single member's declaration and type typedef
00337
00338 @param s: The stream to write to
00339 @type s: stream
00340 @param type: The member type
00341 @type type: str
00342 @param name: The name of the member
00343 @type name: str
00344 """
00345 cpp_type = msg_type_to_cpp(field.type)
00346 s.write(' typedef %s _%s_type;\n'%(cpp_type, field.name))
00347 s.write(' %s %s;\n\n'%(cpp_type, field.name))
00348
00349 def write_members(s, spec):
00350 """
00351 Write all the member declarations
00352
00353 @param s: The stream to write to
00354 @type s: stream
00355 @param spec: The message spec
00356 @type spec: roslib.msgs.MsgSpec
00357 """
00358 [write_member(s, field) for field in spec.parsed_fields()]
00359
00360 def escape_string(str):
00361 str = str.replace('\\', '\\\\')
00362 str = str.replace('"', '\\"')
00363 return str
00364
00365 def write_constant_declaration(s, constant):
00366 """
00367 Write a constant value as a static member
00368
00369 @param s: The stream to write to
00370 @type s: stream
00371 @param constant: The constant
00372 @type constant: roslib.msgs.Constant
00373 """
00374
00375
00376 if (constant.type in ['byte', 'int8', 'int16', 'int32', 'int64', 'char', 'uint8', 'uint16', 'uint32', 'uint64']):
00377 s.write(' enum { %s = %s };\n'%(constant.name, constant.val))
00378 else:
00379 s.write(' static const %s %s;\n'%(msg_type_to_cpp(constant.type), constant.name))
00380
00381 def write_constant_declarations(s, spec):
00382 """
00383 Write all the constants from a spec as static members
00384
00385 @param s: The stream to write to
00386 @type s: stream
00387 @param spec: The message spec
00388 @type spec: roslib.msgs.MsgSpec
00389 """
00390 [write_constant_declaration(s, constant) for constant in spec.constants]
00391 s.write('\n')
00392
00393 def write_constant_definition(s, spec, constant):
00394 """
00395 Write a constant value as a static member
00396
00397 @param s: The stream to write to
00398 @type s: stream
00399 @param constant: The constant
00400 @type constant: roslib.msgs.Constant
00401 """
00402
00403
00404 if (constant.type not in ['byte', 'int8', 'int16', 'int32', 'int64', 'char', 'uint8', 'uint16', 'uint32', 'uint64', 'string']):
00405 s.write('template<typename ContainerAllocator> const %s %s_<ContainerAllocator>::%s = %s;\n'%(msg_type_to_cpp(constant.type), spec.short_name, constant.name, constant.val))
00406 elif (constant.type == 'string'):
00407 s.write('template<typename ContainerAllocator> const %s %s_<ContainerAllocator>::%s = "%s";\n'%(msg_type_to_cpp(constant.type), spec.short_name, constant.name, escape_string(constant.val)))
00408
00409 def write_constant_definitions(s, spec):
00410 """
00411 Write all the constants from a spec as static members
00412
00413 @param s: The stream to write to
00414 @type s: stream
00415 @param spec: The message spec
00416 @type spec: roslib.msgs.MsgSpec
00417 """
00418 [write_constant_definition(s, spec, constant) for constant in spec.constants]
00419 s.write('\n')
00420
00421 def is_fixed_length(spec):
00422 """
00423 Returns whether or not the message is fixed-length
00424
00425 @param spec: The message spec
00426 @type spec: roslib.msgs.MsgSpec
00427 @param package: The package of the
00428 @type package: str
00429 """
00430 types = []
00431 for field in spec.parsed_fields():
00432 if (field.is_array and field.array_len is None):
00433 return False
00434
00435 if (field.base_type == 'string'):
00436 return False
00437
00438 if (not field.is_builtin):
00439 types.append(field.base_type)
00440
00441 types = set(types)
00442 for type in types:
00443 type = roslib.msgs.resolve_type(type, spec.package)
00444 (_, new_spec) = roslib.msgs.load_by_type(type, spec.package)
00445 if (not is_fixed_length(new_spec)):
00446 return False
00447
00448 return True
00449
00450 def write_deprecated_member_functions(s, spec, traits):
00451 """
00452 Writes the deprecated member functions for backwards compatibility
00453 """
00454 for field in spec.parsed_fields():
00455 if (field.is_array):
00456 s.write(' ROS_DEPRECATED uint32_t get_%s_size() const { return (uint32_t)%s.size(); }\n'%(field.name, field.name))
00457
00458 if (field.array_len is None):
00459 s.write(' ROS_DEPRECATED void set_%s_size(uint32_t size) { %s.resize((size_t)size); }\n'%(field.name, field.name))
00460 s.write(' ROS_DEPRECATED void get_%s_vec(%s& vec) const { vec = this->%s; }\n'%(field.name, msg_type_to_cpp(field.type), field.name))
00461 s.write(' ROS_DEPRECATED void set_%s_vec(const %s& vec) { this->%s = vec; }\n'%(field.name, msg_type_to_cpp(field.type), field.name))
00462
00463 for k, v in traits.iteritems():
00464 s.write('private:\n')
00465 s.write(' static const char* __s_get%s_() { return "%s"; }\n'%(k, v))
00466 s.write('public:\n')
00467 s.write(' ROS_DEPRECATED static const std::string __s_get%s() { return __s_get%s_(); }\n\n'%(k, k))
00468 s.write(' ROS_DEPRECATED const std::string __get%s() const { return __s_get%s_(); }\n\n'%(k, k))
00469
00470 s.write(' ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const\n {\n')
00471 s.write(' ros::serialization::OStream stream(write_ptr, 1000000000);\n')
00472 for field in spec.parsed_fields():
00473 s.write(' ros::serialization::serialize(stream, %s);\n'%(field.name))
00474 s.write(' return stream.getData();\n }\n\n')
00475
00476 s.write(' ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)\n {\n')
00477 s.write(' ros::serialization::IStream stream(read_ptr, 1000000000);\n');
00478 for field in spec.parsed_fields():
00479 s.write(' ros::serialization::deserialize(stream, %s);\n'%(field.name))
00480 s.write(' return stream.getData();\n }\n\n')
00481
00482 s.write(' ROS_DEPRECATED virtual uint32_t serializationLength() const\n {\n')
00483 s.write(' uint32_t size = 0;\n');
00484 for field in spec.parsed_fields():
00485 s.write(' size += ros::serialization::serializationLength(%s);\n'%(field.name))
00486 s.write(' return size;\n }\n\n')
00487
00488 def compute_full_text_escaped(gen_deps_dict):
00489 """
00490 Same as roslib.gentools.compute_full_text, except that the
00491 resulting text is escaped to be safe for C++ double quotes
00492
00493 @param get_deps_dict: dictionary returned by get_dependencies call
00494 @type get_deps_dict: dict
00495 @return: concatenated text for msg/srv file and embedded msg/srv types. Text will be escaped for double quotes
00496 @rtype: str
00497 """
00498 definition = roslib.gentools.compute_full_text(gen_deps_dict)
00499 lines = definition.split('\n')
00500 s = StringIO()
00501 for line in lines:
00502 line = escape_string(line)
00503 s.write('%s\\n\\\n'%(line))
00504
00505 val = s.getvalue()
00506 s.close()
00507 return val
00508
00509 def is_hex_string(str):
00510 for c in str:
00511 if c not in '0123456789abcdefABCDEF':
00512 return False
00513
00514 return True
00515
00516 def write_trait_char_class(s, class_name, cpp_msg_with_alloc, value, write_static_hex_value = False):
00517 """
00518 Writes a class trait for traits which have static value() members that return const char*
00519
00520 e.g. write_trait_char_class(s, "MD5Sum", "std_msgs::String_<ContainerAllocator>", "hello") yields:
00521 template<class ContainerAllocator>
00522 struct MD5Sum<std_msgs::String_<ContainerAllocator> >
00523 {
00524 static const char* value() { return "hello"; }
00525 static const char* value(const std_msgs::String_<ContainerAllocator>&) { return value(); }
00526 };
00527
00528 @param s: The stream to write to
00529 @type s: stream
00530 @param class_name: The name of the trait class to write
00531 @type class_name: str
00532 @param cpp_msg_with_alloc: The C++ declaration of the message, including the allocator template
00533 @type cpp_msg_with_alloc: str
00534 @param value: The value to return in the string
00535 @type value: str
00536 @param write_static_hex_value: Whether or not to write a set of compile-time-checkable static values. Useful for,
00537 for example, MD5Sum. Writes static const uint64_t static_value1... static_valueN
00538 @type write_static_hex_value: bool
00539 @raise ValueError if write_static_hex_value is True but value contains characters invalid in a hex value
00540 """
00541 s.write('template<class ContainerAllocator>\nstruct %s<%s> {\n'%(class_name, cpp_msg_with_alloc))
00542 s.write(' static const char* value() \n {\n return "%s";\n }\n\n'%(value))
00543 s.write(' static const char* value(const %s&) { return value(); } \n'%(cpp_msg_with_alloc))
00544 if (write_static_hex_value):
00545 if (not is_hex_string(value)):
00546 raise ValueError('%s is not a hex value'%(value))
00547
00548 iter_count = len(value) / 16
00549 for i in xrange(0, iter_count):
00550 start = i*16
00551 s.write(' static const uint64_t static_value%s = 0x%sULL;\n'%((i+1), value[start:start+16]))
00552 s.write('};\n\n')
00553
00554 def write_trait_true_class(s, class_name, cpp_msg_with_alloc):
00555 """
00556 Writes a true/false trait class
00557
00558 @param s: stream to write to
00559 @type s: stream
00560 @param class_name: Name of the trait class
00561 @type class_name: str
00562 @param cpp_msg_with_alloc: The C++ declaration of the message, including the allocator template
00563 @type cpp_msg_with_alloc: str
00564 """
00565 s.write('template<class ContainerAllocator> struct %s<%s> : public TrueType {};\n'%(class_name, cpp_msg_with_alloc))
00566
00567 def write_traits(s, spec, cpp_name_prefix, datatype = None):
00568 """
00569 Writes all the traits classes for a message
00570
00571 @param s: The stream to write to
00572 @type s: stream
00573 @param spec: The message spec
00574 @type spec: roslib.msgs.MsgSpec
00575 @param cpp_name_prefix: The C++ prefix to prepend to a message to refer to it (e.g. "std_msgs::")
00576 @type cpp_name_prefix: str
00577 @param datatype: The string to write as the datatype of the message. If None (default), pkg/msg is used.
00578 @type datatype: str
00579 """
00580
00581 gendeps_dict = roslib.gentools.get_dependencies(spec, spec.package, compute_files=False)
00582 md5sum = roslib.gentools.compute_md5(gendeps_dict)
00583 full_text = compute_full_text_escaped(gendeps_dict)
00584
00585 if (datatype is None):
00586 datatype = '%s'%(spec.full_name)
00587
00588 (cpp_msg_unqualified, cpp_msg_with_alloc, _) = cpp_message_declarations(cpp_name_prefix, spec.short_name)
00589 s.write('namespace ros\n{\n')
00590 s.write('namespace message_traits\n{\n')
00591 write_trait_char_class(s, 'MD5Sum', cpp_msg_with_alloc, md5sum, True)
00592 write_trait_char_class(s, 'DataType', cpp_msg_with_alloc, datatype)
00593 write_trait_char_class(s, 'Definition', cpp_msg_with_alloc, full_text)
00594
00595 if (spec.has_header()):
00596 write_trait_true_class(s, 'HasHeader', cpp_msg_with_alloc)
00597 write_trait_true_class(s, 'HasHeader', ' const' + cpp_msg_with_alloc)
00598
00599 if (is_fixed_length(spec)):
00600 write_trait_true_class(s, 'IsFixedSize', cpp_msg_with_alloc)
00601
00602 s.write('} // namespace message_traits\n')
00603 s.write('} // namespace ros\n\n')
00604
00605 def write_operations(s, spec, cpp_name_prefix):
00606 (cpp_msg_unqualified, cpp_msg_with_alloc, _) = cpp_message_declarations(cpp_name_prefix, spec.short_name)
00607 s.write('namespace ros\n{\n')
00608 s.write('namespace message_operations\n{\n')
00609
00610
00611 s.write('\ntemplate<class ContainerAllocator>\nstruct Printer<%s>\n{\n'%(cpp_msg_with_alloc))
00612 s.write(' template<typename Stream> static void stream(Stream& s, const std::string& indent, const %s& v) \n {\n'%cpp_msg_with_alloc)
00613 for field in spec.parsed_fields():
00614 cpp_type = msg_type_to_cpp(field.base_type)
00615 if (field.is_array):
00616 s.write(' s << indent << "%s[]" << std::endl;\n'%(field.name))
00617 s.write(' for (size_t i = 0; i < v.%s.size(); ++i)\n {\n'%(field.name))
00618 s.write(' s << indent << " %s[" << i << "]: ";\n'%field.name)
00619 indent_increment = ' '
00620 if (not field.is_builtin):
00621 s.write(' s << std::endl;\n')
00622 s.write(' s << indent;\n')
00623 indent_increment = ' ';
00624 s.write(' Printer<%s>::stream(s, indent + "%s", v.%s[i]);\n'%(cpp_type, indent_increment, field.name))
00625 s.write(' }\n')
00626 else:
00627 s.write(' s << indent << "%s: ";\n'%field.name)
00628 indent_increment = ' '
00629 if (not field.is_builtin or field.is_array):
00630 s.write('s << std::endl;\n')
00631 s.write(' Printer<%s>::stream(s, indent + "%s", v.%s);\n'%(cpp_type, indent_increment, field.name))
00632 s.write(' }\n')
00633 s.write('};\n\n')
00634
00635 s.write('\n')
00636
00637 s.write('} // namespace message_operations\n')
00638 s.write('} // namespace ros\n\n')
00639
00640 def write_serialization(s, spec, cpp_name_prefix):
00641 """
00642 Writes the Serializer class for a message
00643
00644 @param s: Stream to write to
00645 @type s: stream
00646 @param spec: The message spec
00647 @type spec: roslib.msgs.MsgSpec
00648 @param cpp_name_prefix: The C++ prefix to prepend to a message to refer to it (e.g. "std_msgs::")
00649 @type cpp_name_prefix: str
00650 """
00651 (cpp_msg_unqualified, cpp_msg_with_alloc, _) = cpp_message_declarations(cpp_name_prefix, spec.short_name)
00652
00653 s.write('namespace ros\n{\n')
00654 s.write('namespace serialization\n{\n\n')
00655
00656 s.write('template<class ContainerAllocator> struct Serializer<%s>\n{\n'%(cpp_msg_with_alloc))
00657
00658 s.write(' template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)\n {\n')
00659 for field in spec.parsed_fields():
00660 s.write(' stream.next(m.%s);\n'%(field.name))
00661 s.write(' }\n\n')
00662
00663 s.write(' ROS_DECLARE_ALLINONE_SERIALIZER;\n')
00664
00665 s.write('}; // struct %s_\n'%(spec.short_name))
00666
00667 s.write('} // namespace serialization\n')
00668 s.write('} // namespace ros\n\n')
00669
00670 def write_ostream_operator(s, spec, cpp_name_prefix):
00671 (cpp_msg_unqualified, cpp_msg_with_alloc, _) = cpp_message_declarations(cpp_name_prefix, spec.short_name)
00672 s.write('template<typename ContainerAllocator>\nstd::ostream& operator<<(std::ostream& s, const %s& v)\n{\n'%(cpp_msg_with_alloc))
00673 s.write(' ros::message_operations::Printer<%s>::stream(s, "", v);\n return s;}\n\n'%(cpp_msg_with_alloc))
00674
00675 def generate(msg_path):
00676 """
00677 Generate a message
00678
00679 @param msg_path: The path to the .msg file
00680 @type msg_path: str
00681 """
00682 (package_dir, package) = roslib.packages.get_dir_pkg(msg_path)
00683 (_, spec) = roslib.msgs.load_from_file(msg_path, package)
00684
00685 s = StringIO()
00686 write_begin(s, spec, msg_path)
00687 write_generic_includes(s)
00688 write_includes(s, spec)
00689
00690 cpp_prefix = '%s::'%(package)
00691
00692 s.write('namespace %s\n{\n'%(package))
00693 write_struct(s, spec, cpp_prefix)
00694 write_constant_definitions(s, spec)
00695 write_ostream_operator(s, spec, cpp_prefix)
00696 s.write('} // namespace %s\n\n'%(package))
00697
00698 write_traits(s, spec, cpp_prefix)
00699 write_serialization(s, spec, cpp_prefix)
00700 write_operations(s, spec, cpp_prefix)
00701
00702
00703
00704
00705 if (package == "std_msgs" and spec.short_name == "Header"):
00706 s.write("#define STD_MSGS_INCLUDING_HEADER_DEPRECATED_DEF 1\n")
00707 s.write("#include <std_msgs/header_deprecated_def.h>\n")
00708 s.write("#undef STD_MSGS_INCLUDING_HEADER_DEPRECATED_DEF\n\n")
00709
00710 write_end(s, spec)
00711
00712 output_dir = '%s/msg_gen/cpp/include/%s'%(package_dir, package)
00713 if (not os.path.exists(output_dir)):
00714
00715
00716 try:
00717 os.makedirs(output_dir)
00718 except OSError, e:
00719 pass
00720
00721 f = open('%s/%s.h'%(output_dir, spec.short_name), 'w')
00722 print >> f, s.getvalue()
00723
00724 s.close()
00725
00726 def generate_messages(argv):
00727 for arg in argv[1:]:
00728 generate(arg)
00729
00730 if __name__ == "__main__":
00731 roslib.msgs.set_verbose(False)
00732 generate_messages(sys.argv)
00733