36 from cStringIO
import StringIO
38 from io
import StringIO
40 MSG_TYPE_TO_CPP = {
'byte':
'int8_t',
53 'string':
'std::basic_string<char, std::char_traits<char>, typename ContainerAllocator::template rebind<char>::other > ',
55 'duration':
'ros::Duration'}
60 Converts a message type (e.g. uint32, std_msgs/String, etc.) into the C++ declaration 61 for that type (e.g. uint32_t, std_msgs::String_<ContainerAllocator>) 63 @param type: The message type 65 @return: The C++ declaration 68 (base_type, is_array, array_len) = genmsg.msgs.parse_type(type)
70 if (genmsg.msgs.is_builtin(base_type)):
71 cpp_type = MSG_TYPE_TO_CPP[base_type]
72 elif (len(base_type.split(
'/')) == 1):
73 if (genmsg.msgs.is_header_type(base_type)):
74 cpp_type =
' ::std_msgs::Header_<ContainerAllocator> ' 76 cpp_type =
'%s_<ContainerAllocator> '%(base_type)
78 pkg = base_type.split(
'/')[0]
79 msg = base_type.split(
'/')[1]
80 cpp_type =
' ::%s::%s_<ContainerAllocator> '%(pkg, msg)
83 if (array_len
is None):
84 return 'std::vector<%s, typename ContainerAllocator::template rebind<%s>::other > '%(cpp_type, cpp_type)
86 return 'boost::array<%s, %s> '%(cpp_type, array_len)
91 s = s.replace(
'\\',
'\\\\')
92 s = s.replace(
'"',
'\\"')
96 lines = definition.splitlines()
104 s.write(
'"%s\\n"\n'%(line))
113 Returns the different possible C++ declarations for a message given the message itself. 115 @param name_prefix: The C++ prefix to be prepended to the name, e.g. "std_msgs::" 116 @type name_prefix: str 117 @param msg: The message type 119 @return: A tuple of 3 different names. cpp_message_decelarations("std_msgs::", "String") returns the tuple 120 ("std_msgs::String_", "std_msgs::String_<ContainerAllocator>", "std_msgs::String") 123 pkg, basetype = genmsg.names.package_resource_name(msg)
124 cpp_name =
' ::%s%s'%(name_prefix, msg)
126 cpp_name =
' ::%s::%s'%(pkg, basetype)
127 return (
'%s_'%(cpp_name),
'%s_<ContainerAllocator> '%(cpp_name),
'%s'%(cpp_name))
132 Returns whether or not the message is fixed-length 134 @param spec: The message spec 135 @type spec: genmsg.msgs.MsgSpec 136 @param package: The package of the 140 for field
in spec.parsed_fields():
141 if (field.is_array
and field.array_len
is None):
144 if (field.base_type ==
'string'):
147 if (
not field.is_builtin):
148 types.append(field.base_type)
152 t = genmsg.msgs.resolve_type(t, spec.package)
153 assert isinstance(includepath, dict)
154 new_spec = genmsg.msg_loader.load_msg_by_type(msg_context, t, includepath)
163 Returns the value to initialize a message member with. 0 for integer types, 0.0 for floating point, false for bool, 164 empty string for everything else 166 @param type: The type 169 if type
in [
'byte',
'int8',
'int16',
'int32',
'int64',
170 'char',
'uint8',
'uint16',
'uint32',
'uint64']:
172 elif type
in [
'float32',
'float64']:
181 Returns whether or not a type can take an allocator in its constructor. False for all builtin types except string. 184 @param type: The type 187 return not type
in [
'byte',
'int8',
'int16',
'int32',
'int64',
188 'char',
'uint8',
'uint16',
'uint32',
'uint64',
189 'float32',
'float64',
'bool',
'time',
'duration']
192 str = str.replace(
'\\',
'\\\\')
193 str = str.replace(
'"',
'\\"')
199 Initialize any fixed-length arrays 201 @param s: The stream to write to 203 @param spec: The message spec 204 @type spec: genmsg.msgs.MsgSpec 205 @param container_gets_allocator: Whether or not a container type (whether it's another message, a vector, array or string) 206 should have the allocator passed to its constructor. Assumes the allocator is named _alloc. 207 @type container_gets_allocator: bool 208 @param cpp_name_prefix: The C++ prefix to use when referring to the message, e.g. "std_msgs::" 209 @type cpp_name_prefix: str 212 for field
in spec.parsed_fields():
213 if (
not field.is_array
or field.array_len
is None):
219 if (field.base_type ==
"string"):
221 yield ' %s.assign(%s(_alloc));\n'%(field.name, string_cpp)
224 yield ' %s.assign(%s(_alloc));\n'%(field.name, cpp_msg_with_alloc)
226 yield ' %s.assign(%s);\n'%(field.name, val)
231 Writes the initializer list for a constructor 233 @param s: The stream to write to 235 @param spec: The message spec 236 @type spec: genmsg.msgs.MsgSpec 237 @param container_gets_allocator: Whether or not a container type (whether it's another message, a vector, array or string) 238 should have the allocator passed to its constructor. Assumes the allocator is named _alloc. 239 @type container_gets_allocator: bool 243 for field
in spec.parsed_fields():
247 if (field.array_len
is None and container_gets_allocator):
248 yield ' %s %s(_alloc)'%(op, field.name)
250 yield ' %s %s()'%(op, field.name)
252 if (container_gets_allocator
and use_alloc):
253 yield ' %s %s(_alloc)'%(op, field.name)
255 yield ' %s %s(%s)'%(op, field.name, val)
def generate_fixed_length_assigns(spec, container_gets_allocator, cpp_name_prefix)
def takes_allocator(type)
def cpp_message_declarations(name_prefix, msg)
def generate_initializer_list(spec, container_gets_allocator)
def escape_message_definition(definition)
def is_fixed_length(spec, msg_context, includepath)
def msg_type_to_cpp(type)