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