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 from rosidl import log, plog
00040
00041
00042
00043 import sys
00044 import os
00045 import traceback
00046
00047 import rosidl.msgs
00048 import rosidl.gentools
00049
00050 from cStringIO 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) = rosidl.msgs.parse_type(type)
00075 cpp_type = None
00076 if (rosidl.msgs.is_builtin(base_type)):
00077 cpp_type = MSG_TYPE_TO_CPP[base_type]
00078 elif (len(base_type.split('/')) == 1):
00079 if (rosidl.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 = rosidl.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: rosidl.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: rosidl.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: rosidl.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) = rosidl.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, includepath,
00180 extra_deprecated_traits = {}):
00181 """
00182 Writes the entire message struct: declaration, constructors, members, constants and (deprecated) member functions
00183 @param s: The stream to write to
00184 @type s: stream
00185 @param spec: The message spec
00186 @type spec: rosidl.msgs.MsgSpec
00187 @param cpp_name_prefix: The C++ prefix to use when referring to the message, e.g. "std_msgs::"
00188 @type cpp_name_prefix: str
00189 """
00190
00191 msg = spec.short_name
00192 s.write('template <class ContainerAllocator>\n')
00193 s.write('struct %s_ {\n'%(msg))
00194 s.write(' typedef %s_<ContainerAllocator> Type;\n\n'%(msg))
00195
00196 write_constructors(s, spec, cpp_name_prefix)
00197 write_members(s, spec)
00198 write_constant_declarations(s, spec)
00199
00200 gendeps_dict = rosidl.gentools.get_dependencies(spec, spec.package,
00201 includepath,
00202 compute_files=False)
00203 md5sum = rosidl.gentools.compute_md5(gendeps_dict, includepath)
00204 full_text = compute_full_text_escaped(gendeps_dict)
00205
00206 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()))
00207
00208 (cpp_msg_unqualified, cpp_msg_with_alloc, cpp_msg_base) = cpp_message_declarations(cpp_name_prefix, msg)
00209 s.write(' typedef boost::shared_ptr<%s> Ptr;\n'%(cpp_msg_with_alloc))
00210 s.write(' typedef boost::shared_ptr<%s const> ConstPtr;\n'%(cpp_msg_with_alloc))
00211 s.write(' boost::shared_ptr<std::map<std::string, std::string> > __connection_header;\n')
00212
00213 s.write('}; // struct %s\n'%(msg))
00214
00215 s.write('typedef %s_<std::allocator<void> > %s;\n\n'%(cpp_msg_base, msg))
00216 s.write('typedef boost::shared_ptr<%s> %sPtr;\n'%(cpp_msg_base, msg))
00217 s.write('typedef boost::shared_ptr<%s const> %sConstPtr;\n\n'%(cpp_msg_base, msg))
00218
00219 def default_value(type):
00220 """
00221 Returns the value to initialize a message member with. 0 for integer types, 0.0 for floating point, false for bool,
00222 empty string for everything else
00223
00224 @param type: The type
00225 @type type: str
00226 """
00227 if type in ['byte', 'int8', 'int16', 'int32', 'int64',
00228 'char', 'uint8', 'uint16', 'uint32', 'uint64']:
00229 return '0'
00230 elif type in ['float32', 'float64']:
00231 return '0.0'
00232 elif type == 'bool':
00233 return 'false'
00234
00235 return ""
00236
00237 def takes_allocator(type):
00238 """
00239 Returns whether or not a type can take an allocator in its constructor. False for all builtin types except string.
00240 True for all others.
00241
00242 @param type: The type
00243 @type: str
00244 """
00245 return not type in ['byte', 'int8', 'int16', 'int32', 'int64',
00246 'char', 'uint8', 'uint16', 'uint32', 'uint64',
00247 'float32', 'float64', 'bool', 'time', 'duration']
00248
00249 def write_initializer_list(s, spec, container_gets_allocator):
00250 """
00251 Writes the initializer list for a constructor
00252
00253 @param s: The stream to write to
00254 @type s: stream
00255 @param spec: The message spec
00256 @type spec: rosidl.msgs.MsgSpec
00257 @param container_gets_allocator: Whether or not a container type (whether it's another message, a vector, array or string)
00258 should have the allocator passed to its constructor. Assumes the allocator is named _alloc.
00259 @type container_gets_allocator: bool
00260 """
00261
00262 i = 0
00263 for field in spec.parsed_fields():
00264 if (i == 0):
00265 s.write(' : ')
00266 else:
00267 s.write(' , ')
00268
00269 val = default_value(field.base_type)
00270 use_alloc = takes_allocator(field.base_type)
00271 if (field.is_array):
00272 if (field.array_len is None and container_gets_allocator):
00273 s.write('%s(_alloc)\n'%(field.name))
00274 else:
00275 s.write('%s()\n'%(field.name))
00276 else:
00277 if (container_gets_allocator and use_alloc):
00278 s.write('%s(_alloc)\n'%(field.name))
00279 else:
00280 s.write('%s(%s)\n'%(field.name, val))
00281 i = i + 1
00282
00283 def write_fixed_length_assigns(s, spec, container_gets_allocator, cpp_name_prefix):
00284 """
00285 Initialize any fixed-length arrays
00286
00287 @param s: The stream to write to
00288 @type s: stream
00289 @param spec: The message spec
00290 @type spec: rosidl.msgs.MsgSpec
00291 @param container_gets_allocator: Whether or not a container type (whether it's another message, a vector, array or string)
00292 should have the allocator passed to its constructor. Assumes the allocator is named _alloc.
00293 @type container_gets_allocator: bool
00294 @param cpp_name_prefix: The C++ prefix to use when referring to the message, e.g. "std_msgs::"
00295 @type cpp_name_prefix: str
00296 """
00297
00298 for field in spec.parsed_fields():
00299 if (not field.is_array or field.array_len is None):
00300 continue
00301
00302 val = default_value(field.base_type)
00303 if (container_gets_allocator and takes_allocator(field.base_type)):
00304
00305 if (field.base_type == "string"):
00306 string_cpp = msg_type_to_cpp("string")
00307 s.write(' %s.assign(%s(_alloc));\n'%(field.name, string_cpp))
00308 else:
00309 (cpp_msg_unqualified, cpp_msg_with_alloc, _) = cpp_message_declarations(cpp_name_prefix, field.base_type)
00310 s.write(' %s.assign(%s(_alloc));\n'%(field.name, cpp_msg_with_alloc))
00311 elif (len(val) > 0):
00312 s.write(' %s.assign(%s);\n'%(field.name, val))
00313
00314 def write_constructors(s, spec, cpp_name_prefix):
00315 """
00316 Writes any necessary constructors for the message
00317
00318 @param s: The stream to write to
00319 @type s: stream
00320 @param spec: The message spec
00321 @type spec: rosidl.msgs.MsgSpec
00322 @param cpp_name_prefix: The C++ prefix to use when referring to the message, e.g. "std_msgs::"
00323 @type cpp_name_prefix: str
00324 """
00325
00326 msg = spec.short_name
00327
00328
00329 s.write(' %s_()\n'%(msg))
00330 write_initializer_list(s, spec, False)
00331 s.write(' {\n')
00332 write_fixed_length_assigns(s, spec, False, cpp_name_prefix)
00333 s.write(' }\n\n')
00334
00335
00336 s.write(' %s_(const ContainerAllocator& _alloc)\n'%(msg))
00337 write_initializer_list(s, spec, True)
00338 s.write(' {\n')
00339 write_fixed_length_assigns(s, spec, True, cpp_name_prefix)
00340 s.write(' }\n\n')
00341
00342 def write_member(s, field):
00343 """
00344 Writes a single member's declaration and type typedef
00345
00346 @param s: The stream to write to
00347 @type s: stream
00348 @param type: The member type
00349 @type type: str
00350 @param name: The name of the member
00351 @type name: str
00352 """
00353 cpp_type = msg_type_to_cpp(field.type)
00354 s.write(' typedef %s _%s_type;\n'%(cpp_type, field.name))
00355 s.write(' %s %s;\n\n'%(cpp_type, field.name))
00356
00357 def write_members(s, spec):
00358 """
00359 Write all the member declarations
00360
00361 @param s: The stream to write to
00362 @type s: stream
00363 @param spec: The message spec
00364 @type spec: rosidl.msgs.MsgSpec
00365 """
00366 [write_member(s, field) for field in spec.parsed_fields()]
00367
00368 def escape_string(str):
00369 str = str.replace('\\', '\\\\')
00370 str = str.replace('"', '\\"')
00371 return str
00372
00373 def write_constant_declaration(s, constant):
00374 """
00375 Write a constant value as a static member
00376
00377 @param s: The stream to write to
00378 @type s: stream
00379 @param constant: The constant
00380 @type constant: rosidl.msgs.Constant
00381 """
00382
00383
00384 if (constant.type in ['byte', 'int8', 'int16', 'int32', 'int64', 'char', 'uint8', 'uint16', 'uint32', 'uint64']):
00385 s.write(' enum { %s = %s };\n'%(constant.name, constant.val))
00386 else:
00387 s.write(' static const %s %s;\n'%(msg_type_to_cpp(constant.type), constant.name))
00388
00389 def write_constant_declarations(s, spec):
00390 """
00391 Write all the constants from a spec as static members
00392
00393 @param s: The stream to write to
00394 @type s: stream
00395 @param spec: The message spec
00396 @type spec: rosidl.msgs.MsgSpec
00397 """
00398 [write_constant_declaration(s, constant) for constant in spec.constants]
00399 s.write('\n')
00400
00401 def write_constant_definition(s, spec, constant):
00402 """
00403 Write a constant value as a static member
00404
00405 @param s: The stream to write to
00406 @type s: stream
00407 @param constant: The constant
00408 @type constant: rosidl.msgs.Constant
00409 """
00410
00411
00412 if (constant.type not in ['byte', 'int8', 'int16', 'int32', 'int64', 'char', 'uint8', 'uint16', 'uint32', 'uint64', 'string']):
00413 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))
00414 elif (constant.type == 'string'):
00415 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)))
00416
00417 def write_constant_definitions(s, spec):
00418 """
00419 Write all the constants from a spec as static members
00420
00421 @param s: The stream to write to
00422 @type s: stream
00423 @param spec: The message spec
00424 @type spec: rosidl.msgs.MsgSpec
00425 """
00426 [write_constant_definition(s, spec, constant) for constant in spec.constants]
00427 s.write('\n')
00428
00429 def is_fixed_length(spec, includepath):
00430 """
00431 Returns whether or not the message is fixed-length
00432
00433 @param spec: The message spec
00434 @type spec: rosidl.msgs.MsgSpec
00435 @param package: The package of the
00436 @type package: str
00437 """
00438 assert isinstance(includepath, list)
00439 types = []
00440 for field in spec.parsed_fields():
00441 if (field.is_array and field.array_len is None):
00442 return False
00443
00444 if (field.base_type == 'string'):
00445 return False
00446
00447 if (not field.is_builtin):
00448 types.append(field.base_type)
00449
00450 types = set(types)
00451 for type in types:
00452 type = rosidl.msgs.resolve_type(type, spec.package)
00453 (_, new_spec) = rosidl.msgs.load_by_type(type, includepath, spec.package)
00454 if (not is_fixed_length(new_spec, includepath)):
00455 return False
00456
00457 return True
00458
00459 def write_deprecated_member_functions(s, spec, traits):
00460 """
00461 Writes the deprecated member functions for backwards compatibility
00462 """
00463 for field in spec.parsed_fields():
00464 if (field.is_array):
00465 s.write(' ROS_DEPRECATED uint32_t get_%s_size() const { return (uint32_t)%s.size(); }\n'%(field.name, field.name))
00466
00467 if (field.array_len is None):
00468 s.write(' ROS_DEPRECATED void set_%s_size(uint32_t size) { %s.resize((size_t)size); }\n'%(field.name, field.name))
00469 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))
00470 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))
00471
00472 for k, v in traits.iteritems():
00473 s.write('private:\n')
00474 s.write(' static const char* __s_get%s_() { return "%s"; }\n'%(k, v))
00475 s.write('public:\n')
00476 s.write(' ROS_DEPRECATED static const std::string __s_get%s() { return __s_get%s_(); }\n\n'%(k, k))
00477 s.write(' ROS_DEPRECATED const std::string __get%s() const { return __s_get%s_(); }\n\n'%(k, k))
00478
00479 s.write(' ROS_DEPRECATED virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const\n {\n')
00480 s.write(' ros::serialization::OStream stream(write_ptr, 1000000000);\n')
00481 for field in spec.parsed_fields():
00482 s.write(' ros::serialization::serialize(stream, %s);\n'%(field.name))
00483 s.write(' return stream.getData();\n }\n\n')
00484
00485 s.write(' ROS_DEPRECATED virtual uint8_t *deserialize(uint8_t *read_ptr)\n {\n')
00486 s.write(' ros::serialization::IStream stream(read_ptr, 1000000000);\n');
00487 for field in spec.parsed_fields():
00488 s.write(' ros::serialization::deserialize(stream, %s);\n'%(field.name))
00489 s.write(' return stream.getData();\n }\n\n')
00490
00491 s.write(' ROS_DEPRECATED virtual uint32_t serializationLength() const\n {\n')
00492 s.write(' uint32_t size = 0;\n');
00493 for field in spec.parsed_fields():
00494 s.write(' size += ros::serialization::serializationLength(%s);\n'%(field.name))
00495 s.write(' return size;\n }\n\n')
00496
00497 def compute_full_text_escaped(gen_deps_dict):
00498 """
00499 Same as rosidl.gentools.compute_full_text, except that the
00500 resulting text is escaped to be safe for C++ double quotes
00501
00502 @param get_deps_dict: dictionary returned by get_dependencies call
00503 @type get_deps_dict: dict
00504 @return: concatenated text for msg/srv file and embedded msg/srv types. Text will be escaped for double quotes
00505 @rtype: str
00506 """
00507 definition = rosidl.gentools.compute_full_text(gen_deps_dict)
00508 lines = definition.split('\n')
00509 s = StringIO()
00510 for line in lines:
00511 line = escape_string(line)
00512 s.write('%s\\n\\\n'%(line))
00513
00514 val = s.getvalue()
00515 s.close()
00516 return val
00517
00518 def is_hex_string(str):
00519 for c in str:
00520 if c not in '0123456789abcdefABCDEF':
00521 return False
00522
00523 return True
00524
00525 def write_trait_char_class(s, class_name, cpp_msg_with_alloc, value, write_static_hex_value = False):
00526 """
00527 Writes a class trait for traits which have static value() members that return const char*
00528
00529 e.g. write_trait_char_class(s, "MD5Sum", "std_msgs::String_<ContainerAllocator>", "hello") yields:
00530 template<class ContainerAllocator>
00531 struct MD5Sum<std_msgs::String_<ContainerAllocator> >
00532 {
00533 static const char* value() { return "hello"; }
00534 static const char* value(const std_msgs::String_<ContainerAllocator>&) { return value(); }
00535 };
00536
00537 @param s: The stream to write to
00538 @type s: stream
00539 @param class_name: The name of the trait class to write
00540 @type class_name: str
00541 @param cpp_msg_with_alloc: The C++ declaration of the message, including the allocator template
00542 @type cpp_msg_with_alloc: str
00543 @param value: The value to return in the string
00544 @type value: str
00545 @param write_static_hex_value: Whether or not to write a set of compile-time-checkable static values. Useful for,
00546 for example, MD5Sum. Writes static const uint64_t static_value1... static_valueN
00547 @type write_static_hex_value: bool
00548 @raise ValueError if write_static_hex_value is True but value contains characters invalid in a hex value
00549 """
00550 s.write('template<class ContainerAllocator>\nstruct %s<%s> {\n'%(class_name, cpp_msg_with_alloc))
00551 s.write(' static const char* value() \n {\n return "%s";\n }\n\n'%(value))
00552 s.write(' static const char* value(const %s&) { return value(); } \n'%(cpp_msg_with_alloc))
00553 if (write_static_hex_value):
00554 if (not is_hex_string(value)):
00555 raise ValueError('%s is not a hex value'%(value))
00556
00557 iter_count = len(value) / 16
00558 for i in xrange(0, iter_count):
00559 start = i*16
00560 s.write(' static const uint64_t static_value%s = 0x%sULL;\n'%((i+1), value[start:start+16]))
00561 s.write('};\n\n')
00562
00563 def write_trait_true_class(s, class_name, cpp_msg_with_alloc):
00564 """
00565 Writes a true/false trait class
00566
00567 @param s: stream to write to
00568 @type s: stream
00569 @param class_name: Name of the trait class
00570 @type class_name: str
00571 @param cpp_msg_with_alloc: The C++ declaration of the message, including the allocator template
00572 @type cpp_msg_with_alloc: str
00573 """
00574 s.write('template<class ContainerAllocator> struct %s<%s> : public TrueType {};\n'%(class_name, cpp_msg_with_alloc))
00575
00576 def write_traits(s, spec, cpp_name_prefix, includepath, datatype = None):
00577 """
00578 Writes all the traits classes for a message
00579
00580 @param s: The stream to write to
00581 @type s: stream
00582 @param spec: The message spec
00583 @type spec: rosidl.msgs.MsgSpec
00584 @param cpp_name_prefix: The C++ prefix to prepend to a message to refer to it (e.g. "std_msgs::")
00585 @type cpp_name_prefix: str
00586 @param datatype: The string to write as the datatype of the message. If None (default), pkg/msg is used.
00587 @type datatype: str
00588 """
00589 assert isinstance(includepath, list)
00590 assert isinstance(cpp_name_prefix, str)
00591
00592
00593 gendeps_dict = rosidl.gentools.get_dependencies(spec, spec.package,
00594 includepath, compute_files=False)
00595 md5sum = rosidl.gentools.compute_md5(gendeps_dict, includepath)
00596 full_text = compute_full_text_escaped(gendeps_dict)
00597
00598 if (datatype is None):
00599 datatype = '%s'%(spec.full_name)
00600
00601 (cpp_msg_unqualified, cpp_msg_with_alloc, _) = cpp_message_declarations(cpp_name_prefix, spec.short_name)
00602 s.write('namespace ros\n{\n')
00603 s.write('namespace message_traits\n{\n')
00604
00605 write_trait_true_class(s, 'IsMessage', cpp_msg_with_alloc)
00606 write_trait_true_class(s, 'IsMessage', cpp_msg_with_alloc + " const")
00607
00608 write_trait_char_class(s, 'MD5Sum', cpp_msg_with_alloc, md5sum, True)
00609 write_trait_char_class(s, 'DataType', cpp_msg_with_alloc, datatype)
00610 write_trait_char_class(s, 'Definition', cpp_msg_with_alloc, full_text)
00611
00612 if (spec.has_header()):
00613 write_trait_true_class(s, 'HasHeader', cpp_msg_with_alloc)
00614 write_trait_true_class(s, 'HasHeader', ' const' + cpp_msg_with_alloc)
00615
00616 if (is_fixed_length(spec, includepath)):
00617 write_trait_true_class(s, 'IsFixedSize', cpp_msg_with_alloc)
00618
00619 s.write('} // namespace message_traits\n')
00620 s.write('} // namespace ros\n\n')
00621
00622 def write_operations(s, spec, cpp_name_prefix):
00623 (cpp_msg_unqualified, cpp_msg_with_alloc, _) = cpp_message_declarations(cpp_name_prefix, spec.short_name)
00624 s.write('namespace ros\n{\n')
00625 s.write('namespace message_operations\n{\n')
00626
00627
00628 s.write('\ntemplate<class ContainerAllocator>\nstruct Printer<%s>\n{\n'%(cpp_msg_with_alloc))
00629 s.write(' template<typename Stream> static void stream(Stream& s, const std::string& indent, const %s& v) \n {\n'%cpp_msg_with_alloc)
00630 for field in spec.parsed_fields():
00631 cpp_type = msg_type_to_cpp(field.base_type)
00632 if (field.is_array):
00633 s.write(' s << indent << "%s[]" << std::endl;\n'%(field.name))
00634 s.write(' for (size_t i = 0; i < v.%s.size(); ++i)\n {\n'%(field.name))
00635 s.write(' s << indent << " %s[" << i << "]: ";\n'%field.name)
00636 indent_increment = ' '
00637 if (not field.is_builtin):
00638 s.write(' s << std::endl;\n')
00639 s.write(' s << indent;\n')
00640 indent_increment = ' ';
00641 s.write(' Printer<%s>::stream(s, indent + "%s", v.%s[i]);\n'%(cpp_type, indent_increment, field.name))
00642 s.write(' }\n')
00643 else:
00644 s.write(' s << indent << "%s: ";\n'%field.name)
00645 indent_increment = ' '
00646 if (not field.is_builtin or field.is_array):
00647 s.write('s << std::endl;\n')
00648 s.write(' Printer<%s>::stream(s, indent + "%s", v.%s);\n'%(cpp_type, indent_increment, field.name))
00649 s.write(' }\n')
00650 s.write('};\n\n')
00651
00652 s.write('\n')
00653
00654 s.write('} // namespace message_operations\n')
00655 s.write('} // namespace ros\n\n')
00656
00657 def write_serialization(s, spec, cpp_name_prefix):
00658 """
00659 Writes the Serializer class for a message
00660
00661 @param s: Stream to write to
00662 @type s: stream
00663 @param spec: The message spec
00664 @type spec: rosidl.msgs.MsgSpec
00665 @param cpp_name_prefix: The C++ prefix to prepend to a message to refer to it (e.g. "std_msgs::")
00666 @type cpp_name_prefix: str
00667 """
00668 (cpp_msg_unqualified, cpp_msg_with_alloc, _) = cpp_message_declarations(cpp_name_prefix, spec.short_name)
00669
00670 s.write('namespace ros\n{\n')
00671 s.write('namespace serialization\n{\n\n')
00672
00673 s.write('template<class ContainerAllocator> struct Serializer<%s>\n{\n'%(cpp_msg_with_alloc))
00674
00675 s.write(' template<typename Stream, typename T> inline static void allInOne(Stream& stream, T m)\n {\n')
00676 for field in spec.parsed_fields():
00677 s.write(' stream.next(m.%s);\n'%(field.name))
00678 s.write(' }\n\n')
00679
00680 s.write(' ROS_DECLARE_ALLINONE_SERIALIZER;\n')
00681
00682 s.write('}; // struct %s_\n'%(spec.short_name))
00683
00684 s.write('} // namespace serialization\n')
00685 s.write('} // namespace ros\n\n')
00686
00687 def write_ostream_operator(s, spec, cpp_name_prefix):
00688 (cpp_msg_unqualified, cpp_msg_with_alloc, _) = cpp_message_declarations(cpp_name_prefix, spec.short_name)
00689 s.write('template<typename ContainerAllocator>\nstd::ostream& operator<<(std::ostream& s, const %s& v)\n{\n'%(cpp_msg_with_alloc))
00690 s.write(' ros::message_operations::Printer<%s>::stream(s, "", v);\n return s;}\n\n'%(cpp_msg_with_alloc))
00691
00692 def generate(args):
00693 """
00694 Generate a message
00695
00696 @param msg_path: The path to the .msg file
00697 @type msg_path: str
00698 """
00699
00700 log("generate(%s)" % args)
00701 from optparse import OptionParser
00702 parser = OptionParser("generates c++ message serialization code")
00703
00704 parser.add_option('-p', dest='package',
00705 help="package name")
00706 parser.add_option('-o', dest='outdir',
00707 help="absolute path to output directory")
00708 parser.add_option('-I', dest='includepath',
00709 help="include path to search for messages",
00710 action='append')
00711 (options, args) = parser.parse_args(args)
00712
00713 if not isinstance(options.includepath, list):
00714 options.includepath = []
00715
00716
00717
00718
00719 rosidl.msgs._init()
00720
00721 (_, spec) = rosidl.msgs.load_from_file(args[1], options.package)
00722 plog("spec", spec)
00723
00724 s = StringIO()
00725 write_begin(s, spec, args[1])
00726 write_generic_includes(s)
00727 write_includes(s, spec)
00728
00729 cpp_prefix = '%s::'%(options.package)
00730
00731 s.write('namespace %s\n{\n'%(options.package))
00732 write_struct(s, spec, cpp_prefix, options.includepath)
00733 write_constant_definitions(s, spec)
00734 write_ostream_operator(s, spec, cpp_prefix)
00735 s.write('} // namespace %s\n\n'%(options.package))
00736
00737 write_traits(s, spec, cpp_prefix, options.includepath)
00738 write_serialization(s, spec, cpp_prefix)
00739 write_operations(s, spec, cpp_prefix)
00740
00741
00742 if options.package == "std_msgs" and spec.short_name == "Header":
00743 s.write("#define STD_MSGS_INCLUDING_HEADER_DEPRECATED_DEF 1\n")
00744 s.write("#include <std_msgs/header_deprecated_def.h>\n")
00745 s.write("#undef STD_MSGS_INCLUDING_HEADER_DEPRECATED_DEF\n\n")
00746
00747
00748 write_end(s, spec)
00749
00750 if 'ROS_BUILD' in os.environ:
00751 package_dir = os.environ['ROS_BUILD']
00752
00753
00754 odir = os.path.join(options.outdir, options.package)
00755
00756 if (not os.path.exists(odir)):
00757
00758
00759 try:
00760 os.makedirs(odir)
00761 except OSError, e:
00762 pass
00763
00764 oname = '%s/%s.h' % (odir, spec.short_name)
00765 f = open(oname, 'w')
00766 print >> f, s.getvalue()
00767
00768 s.close()
00769
00770 if __name__ == "__main__":
00771 generate(sys.argv)