36 from cStringIO
import StringIO
38 from io
import StringIO
54 'string':
'std::basic_string<char, std::char_traits<char>, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<char>>',
56 'duration':
'ros::Duration',
63 Convert a message type into the C++ declaration for that type.
65 Example message types: uint32, std_msgs/String.
66 Example C++ types: uint32_t, std_msgs::String_<ContainerAllocator>
68 @param type_: The message type
70 @return: The C++ declaration
73 (base_type, is_array, array_len) = genmsg.msgs.parse_type(type_)
75 if (genmsg.msgs.is_builtin(base_type)):
76 cpp_type = MSG_TYPE_TO_CPP[base_type]
77 elif (len(base_type.split(
'/')) == 1):
78 if (genmsg.msgs.is_header_type(base_type)):
79 cpp_type =
' ::std_msgs::Header_<ContainerAllocator> '
81 cpp_type =
'%s_<ContainerAllocator> ' % (base_type)
83 pkg = base_type.split(
'/')[0]
84 msg = base_type.split(
'/')[1]
85 cpp_type =
' ::%s::%s_<ContainerAllocator> ' % (pkg, msg)
88 if (array_len
is None):
89 return 'std::vector<%s, typename std::allocator_traits<ContainerAllocator>::template rebind_alloc<%s>>' % (cpp_type, cpp_type)
91 return 'boost::array<%s, %s> ' % (cpp_type, array_len)
97 s = s.replace(
'\\',
'\\\\')
98 s = s.replace(
'"',
'\\"')
103 lines = definition.splitlines()
111 s.write(
'"%s\\n"\n' % (line))
121 Return the different possible C++ declarations for a message given the message itself.
123 @param name_prefix: The C++ prefix to be prepended to the name, e.g. "std_msgs::"
124 @type name_prefix: str
125 @param msg: The message type
127 @return: A tuple of 3 different names. cpp_message_decelarations("std_msgs::", "String") returns the tuple
128 ("std_msgs::String_", "std_msgs::String_<ContainerAllocator>", "std_msgs::String")
131 pkg, basetype = genmsg.names.package_resource_name(msg)
132 cpp_name =
' ::%s%s' % (name_prefix, msg)
134 cpp_name =
' ::%s::%s' % (pkg, basetype)
135 return (
'%s_' % (cpp_name),
'%s_<ContainerAllocator> ' % (cpp_name),
'%s' % (cpp_name))
141 Return whether or not the message is fixed-length.
143 @param spec: The message spec
144 @type spec: genmsg.msgs.MsgSpec
145 @param package: The package of the
149 for field
in spec.parsed_fields():
150 if (field.is_array
and field.array_len
is None):
153 if (field.base_type ==
'string'):
156 if (
not field.is_builtin):
157 types.append(field.base_type)
161 t = genmsg.msgs.resolve_type(t, spec.package)
162 assert isinstance(includepath, dict)
163 new_spec = genmsg.msg_loader.load_msg_by_type(msg_context, t, includepath)
173 Return the value to initialize a message member with.
175 0 for integer types, 0.0 for floating point, false for bool,
176 empty string for everything else
178 @param type_: The type
182 'byte',
'int8',
'int16',
'int32',
'int64',
183 'char',
'uint8',
'uint16',
'uint32',
'uint64',
186 elif type_
in [
'float32',
'float64']:
188 elif type_ ==
'bool':
197 Return whether or not a type can take an allocator in its constructor.
199 False for all builtin types except string.
202 @param type_: The type
205 return type_
not in [
206 'byte',
'int8',
'int16',
'int32',
'int64',
207 'char',
'uint8',
'uint16',
'uint32',
'uint64',
208 'float32',
'float64',
'bool',
'time',
'duration']
212 str_ = str_.replace(
'\\',
'\\\\')
213 str_ = str_.replace(
'"',
'\\"')
220 Initialize any fixed-length arrays.
222 @param s: The stream to write to
224 @param spec: The message spec
225 @type spec: genmsg.msgs.MsgSpec
226 @param container_gets_allocator: Whether or not a container type (whether it's another message, a vector, array or string)
227 should have the allocator passed to its constructor. Assumes the allocator is named _alloc.
228 @type container_gets_allocator: bool
229 @param cpp_name_prefix: The C++ prefix to use when referring to the message, e.g. "std_msgs::"
230 @type cpp_name_prefix: str
233 for field
in spec.parsed_fields():
234 if (
not field.is_array
or field.array_len
is None):
240 if (field.base_type ==
'string'):
242 yield ' %s.assign(%s(_alloc));\n' % (field.name, string_cpp)
245 yield ' %s.assign(%s(_alloc));\n' % (field.name, cpp_msg_with_alloc)
247 yield ' %s.assign(%s);\n' % (field.name, val)
253 Write the initializer list for a constructor.
255 @param s: The stream to write to
257 @param spec: The message spec
258 @type spec: genmsg.msgs.MsgSpec
259 @param container_gets_allocator: Whether or not a container type (whether it's another message, a vector, array or string)
260 should have the allocator passed to its constructor. Assumes the allocator is named _alloc.
261 @type container_gets_allocator: bool
264 for field
in spec.parsed_fields():
268 if (field.array_len
is None and container_gets_allocator):
269 yield ' %s %s(_alloc)' % (op, field.name)
271 yield ' %s %s()' % (op, field.name)
273 if (container_gets_allocator
and use_alloc):
274 yield ' %s %s(_alloc)' % (op, field.name)
276 yield ' %s %s(%s)' % (op, field.name, val)