diff --git a/src/rosbags/serde/cdr.py b/src/rosbags/serde/cdr.py index ba9cc6d8..de3ff282 100644 --- a/src/rosbags/serde/cdr.py +++ b/src/rosbags/serde/cdr.py @@ -68,19 +68,19 @@ def generate_getsize_cdr(fields: List[Field]) -> Tuple[Callable, int]: size += SIZEMAP[desc.args] elif desc.valtype == Valtype.ARRAY: - subdesc = desc.args[1] + subdesc, length = desc.args if subdesc.valtype == Valtype.BASE: if subdesc.args == 'string': lines.append(f' val = message.{fieldname}') - for idx in range(desc.args[0]): + for idx in range(length): lines.append(' pos = (pos + 4 - 1) & -4') lines.append(f' pos += 4 + len(val[{idx}].encode()) + 1') aligned = 1 is_stat = False else: - lines.append(f' pos += {desc.args[0] * SIZEMAP[subdesc.args]}') - size += desc.args[0] * SIZEMAP[subdesc.args] + lines.append(f' pos += {length * SIZEMAP[subdesc.args]}') + size += length * SIZEMAP[subdesc.args] else: assert subdesc.valtype == Valtype.MESSAGE @@ -88,7 +88,7 @@ def generate_getsize_cdr(fields: List[Field]) -> Tuple[Callable, int]: anext_after = align_after(subdesc) if subdesc.args.size_cdr: - for _ in range(desc.args[0]): + for _ in range(length): if anext > anext_after: lines.append(f' pos = (pos + {anext} - 1) & -{anext}') size = (size + anext - 1) & -anext @@ -97,7 +97,7 @@ def generate_getsize_cdr(fields: List[Field]) -> Tuple[Callable, int]: else: lines.append(f' func = get_msgdef("{subdesc.args.name}").getsize_cdr') lines.append(f' val = message.{fieldname}') - for idx in range(desc.args[0]): + for idx in range(length): if anext > anext_after: lines.append(f' pos = (pos + {anext} - 1) & -{anext}') lines.append(f' pos = func(pos, val[{idx}])') @@ -107,7 +107,7 @@ def generate_getsize_cdr(fields: List[Field]) -> Tuple[Callable, int]: assert desc.valtype == Valtype.SEQUENCE lines.append(' pos += 4') aligned = 4 - subdesc = desc.args + subdesc = desc.args[0] if subdesc.valtype == Valtype.BASE: if subdesc.args == 'string': lines.append(f' for val in message.{fieldname}:') @@ -211,13 +211,13 @@ def generate_serialize_cdr(fields: List[Field], endianess: str) -> Callable: aligned = SIZEMAP[desc.args] elif desc.valtype == Valtype.ARRAY: - subdesc = desc.args[1] - lines.append(f' if len(val) != {desc.args[0]}:') + subdesc, length = desc.args + lines.append(f' if len(val) != {length}:') lines.append(' raise SerdeError(\'Unexpected array length\')') if subdesc.valtype == Valtype.BASE: if subdesc.args == 'string': - for idx in range(desc.args[0]): + for idx in range(length): lines.append(f' bval = memoryview(val[{idx}].encode())') lines.append(' length = len(bval) + 1') lines.append(' pos = (pos + 4 - 1) & -4') @@ -229,7 +229,7 @@ def generate_serialize_cdr(fields: List[Field], endianess: str) -> Callable: else: if (endianess == 'le') != (sys.byteorder == 'little'): lines.append(' val = val.byteswap()') - size = desc.args[0] * SIZEMAP[subdesc.args] + size = length * SIZEMAP[subdesc.args] lines.append(f' rawdata[pos:pos + {size}] = val.view(numpy.uint8)') lines.append(f' pos += {size}') @@ -240,7 +240,7 @@ def generate_serialize_cdr(fields: List[Field], endianess: str) -> Callable: lines.append( f' func = get_msgdef("{subdesc.args.name}").serialize_cdr_{endianess}', ) - for idx in range(desc.args[0]): + for idx in range(length): if anext > anext_after: lines.append(f' pos = (pos + {anext} - 1) & -{anext}') lines.append(f' pos = func(rawdata, pos, val[{idx}])') @@ -250,7 +250,7 @@ def generate_serialize_cdr(fields: List[Field], endianess: str) -> Callable: lines.append(f' pack_int32_{endianess}(rawdata, pos, len(val))') lines.append(' pos += 4') aligned = 4 - subdesc = desc.args + subdesc = desc.args[0] if subdesc.valtype == Valtype.BASE: if subdesc.args == 'string': @@ -350,11 +350,11 @@ def generate_deserialize_cdr(fields: List[Field], endianess: str) -> Callable: aligned = SIZEMAP[desc.args] elif desc.valtype == Valtype.ARRAY: - subdesc = desc.args[1] + subdesc, length = desc.args if subdesc.valtype == Valtype.BASE: if subdesc.args == 'string': lines.append(' value = []') - for idx in range(desc.args[0]): + for idx in range(length): if idx: lines.append(' pos = (pos + 4 - 1) & -4') lines.append(f' length = unpack_int32_{endianess}(rawdata, pos)[0]') @@ -365,10 +365,10 @@ def generate_deserialize_cdr(fields: List[Field], endianess: str) -> Callable: lines.append(' values.append(value)') aligned = 1 else: - size = desc.args[0] * SIZEMAP[subdesc.args] + size = length * SIZEMAP[subdesc.args] lines.append( f' val = numpy.frombuffer(rawdata, ' - f'dtype=numpy.{subdesc.args}, count={desc.args[0]}, offset=pos)', + f'dtype=numpy.{subdesc.args}, count={length}, offset=pos)', ) if (endianess == 'le') != (sys.byteorder == 'little'): lines.append(' val = val.byteswap()') @@ -380,7 +380,7 @@ def generate_deserialize_cdr(fields: List[Field], endianess: str) -> Callable: anext_after = align_after(subdesc) lines.append(f' msgdef = get_msgdef("{subdesc.args.name}")') lines.append(' value = []') - for _ in range(desc.args[0]): + for _ in range(length): if anext > anext_after: lines.append(f' pos = (pos + {anext} - 1) & -{anext}') lines.append(f' obj, pos = msgdef.{funcname}(rawdata, pos, msgdef.cls)') @@ -393,7 +393,7 @@ def generate_deserialize_cdr(fields: List[Field], endianess: str) -> Callable: lines.append(f' size = unpack_int32_{endianess}(rawdata, pos)[0]') lines.append(' pos += 4') aligned = 4 - subdesc = desc.args + subdesc = desc.args[0] if subdesc.valtype == Valtype.BASE: if subdesc.args == 'string': diff --git a/src/rosbags/serde/messages.py b/src/rosbags/serde/messages.py index 3c2193d7..eae01a59 100644 --- a/src/rosbags/serde/messages.py +++ b/src/rosbags/serde/messages.py @@ -10,13 +10,12 @@ from rosbags.typesys import types from .cdr import generate_deserialize_cdr, generate_getsize_cdr, generate_serialize_cdr from .ros1 import generate_ros1_to_cdr -from .typing import Field, Msgdef -from .utils import Descriptor, Valtype +from .typing import Descriptor, Field, Msgdef +from .utils import Valtype if TYPE_CHECKING: from typing import Any, Dict - MSGDEFCACHE: Dict[str, Msgdef] = {} @@ -37,7 +36,7 @@ def get_msgdef(typename: str) -> Msgdef: """ if typename not in MSGDEFCACHE: - entries = types.FIELDDEFS[typename] + entries = types.FIELDDEFS[typename][1] def fixup(entry: Any) -> Descriptor: if entry[0] == Valtype.BASE: @@ -45,9 +44,9 @@ def get_msgdef(typename: str) -> Msgdef: if entry[0] == Valtype.MESSAGE: return Descriptor(Valtype.MESSAGE, get_msgdef(entry[1])) if entry[0] == Valtype.ARRAY: - return Descriptor(Valtype.ARRAY, (entry[1], fixup(entry[2]))) + return Descriptor(Valtype.ARRAY, (fixup(entry[1][0]), entry[1][1])) if entry[0] == Valtype.SEQUENCE: - return Descriptor(Valtype.SEQUENCE, fixup(entry[1])) + return Descriptor(Valtype.SEQUENCE, (fixup(entry[1][0]), entry[1][1])) raise SerdeError( # pragma: no cover f'Unknown field type {entry[0]!r} encountered.', ) diff --git a/src/rosbags/serde/ros1.py b/src/rosbags/serde/ros1.py index fb1c212b..e049adf6 100644 --- a/src/rosbags/serde/ros1.py +++ b/src/rosbags/serde/ros1.py @@ -22,12 +22,12 @@ if TYPE_CHECKING: def generate_ros1_to_cdr(fields: List[Field], typename: str, copy: bool) -> Callable: - """Generate CDR serialization function. + """Generate ROS1 to CDR conversion function. Args: fields: Fields of message. typename: Message type name. - copy: Generate serialization or sizing function. + copy: Generate conversion or sizing function. Returns: ROS1 to CDR conversion function. @@ -42,17 +42,7 @@ def generate_ros1_to_cdr(fields: List[Field], typename: str, copy: bool) -> Call 'import sys', 'import numpy', 'from rosbags.serde.messages import SerdeError, get_msgdef', - 'from rosbags.serde.primitives import pack_bool_le', - 'from rosbags.serde.primitives import pack_int8_le', - 'from rosbags.serde.primitives import pack_int16_le', 'from rosbags.serde.primitives import pack_int32_le', - 'from rosbags.serde.primitives import pack_int64_le', - 'from rosbags.serde.primitives import pack_uint8_le', - 'from rosbags.serde.primitives import pack_uint16_le', - 'from rosbags.serde.primitives import pack_uint32_le', - 'from rosbags.serde.primitives import pack_uint64_le', - 'from rosbags.serde.primitives import pack_float32_le', - 'from rosbags.serde.primitives import pack_float64_le', 'from rosbags.serde.primitives import unpack_int32_le', f'def {funcname}(input, ipos, output, opos):', ] @@ -89,11 +79,11 @@ def generate_ros1_to_cdr(fields: List[Field], typename: str, copy: bool) -> Call aligned = size elif desc.valtype == Valtype.ARRAY: - subdesc = desc.args[1] + subdesc, length = desc.args if subdesc.valtype == Valtype.BASE: if subdesc.args == 'string': - for _ in range(desc.args[0]): + for _ in range(length): lines.append(' opos = (opos + 4 - 1) & -4') lines.append(' length = unpack_int32_le(input, ipos)[0] + 1') if copy: @@ -108,7 +98,7 @@ def generate_ros1_to_cdr(fields: List[Field], typename: str, copy: bool) -> Call lines.append(' opos += length') aligned = 1 else: - size = desc.args[0] * SIZEMAP[subdesc.args] + size = length * SIZEMAP[subdesc.args] if copy: lines.append(f' output[opos:opos + {size}] = input[ipos:ipos + {size}]') lines.append(f' ipos += {size}') @@ -120,7 +110,7 @@ def generate_ros1_to_cdr(fields: List[Field], typename: str, copy: bool) -> Call anext_after = align_after(subdesc) lines.append(f' func = get_msgdef("{subdesc.args.name}").{funcname}') - for _ in range(desc.args[0]): + for _ in range(length): if anext > anext_after: lines.append(f' opos = (opos + {anext} - 1) & -{anext}') lines.append(' ipos, opos = func(input, ipos, output, opos)') @@ -132,7 +122,7 @@ def generate_ros1_to_cdr(fields: List[Field], typename: str, copy: bool) -> Call lines.append(' pack_int32_le(output, opos, size)') lines.append(' ipos += 4') lines.append(' opos += 4') - subdesc = desc.args + subdesc = desc.args[0] aligned = 4 if subdesc.valtype == Valtype.BASE: diff --git a/src/rosbags/serde/typing.py b/src/rosbags/serde/typing.py index a3b0d70c..3de40593 100644 --- a/src/rosbags/serde/typing.py +++ b/src/rosbags/serde/typing.py @@ -7,9 +7,14 @@ from __future__ import annotations from typing import TYPE_CHECKING, NamedTuple if TYPE_CHECKING: - from typing import Any, Callable, List # pylint: disable=ungrouped-imports + from typing import Any, Callable, List - from .utils import Descriptor + +class Descriptor(NamedTuple): + """Value type descriptor.""" + + valtype: int + args: Any class Field(NamedTuple): diff --git a/src/rosbags/serde/utils.py b/src/rosbags/serde/utils.py index 7ee18e49..5ebaa16c 100644 --- a/src/rosbags/serde/utils.py +++ b/src/rosbags/serde/utils.py @@ -6,11 +6,13 @@ from __future__ import annotations from enum import IntEnum from importlib.util import module_from_spec, spec_from_loader -from typing import TYPE_CHECKING, NamedTuple +from typing import TYPE_CHECKING if TYPE_CHECKING: from types import ModuleType - from typing import Any, Dict, List + from typing import Dict, List + + from .typing import Descriptor class Valtype(IntEnum): @@ -22,13 +24,6 @@ class Valtype(IntEnum): SEQUENCE = 4 -class Descriptor(NamedTuple): - """Value type descriptor.""" - - valtype: Valtype - args: Any # Union[Descriptor, Msgdef, Tuple[int, Descriptor], str] - - SIZEMAP: Dict[str, int] = { 'bool': 1, 'int8': 1, @@ -61,7 +56,7 @@ def align(entry: Descriptor) -> int: if entry.valtype == Valtype.MESSAGE: return align(entry.args.fields[0].descriptor) if entry.valtype == Valtype.ARRAY: - return align(entry.args[1]) + return align(entry.args[0]) assert entry.valtype == Valtype.SEQUENCE return 4 @@ -83,9 +78,9 @@ def align_after(entry: Descriptor) -> int: if entry.valtype == Valtype.MESSAGE: return align_after(entry.args.fields[-1].descriptor) if entry.valtype == Valtype.ARRAY: - return align_after(entry.args[1]) + return align_after(entry.args[0]) assert entry.valtype == Valtype.SEQUENCE - return min([4, align_after(entry.args)]) + return min([4, align_after(entry.args[0])]) def compile_lines(lines: List[str]) -> ModuleType: diff --git a/src/rosbags/typesys/base.py b/src/rosbags/typesys/base.py index d7d34377..02e0b3b9 100644 --- a/src/rosbags/typesys/base.py +++ b/src/rosbags/typesys/base.py @@ -8,12 +8,14 @@ from enum import IntEnum, auto from typing import TYPE_CHECKING if TYPE_CHECKING: - from typing import Any, Dict, List, Tuple + from typing import Any, Dict, List, Optional, Tuple, Union from .peg import Visitor - Fielddefs = List[Tuple[Any, Any]] - Typesdict = Dict[str, Fielddefs] + Constdefs = List[Tuple[str, str, Any]] + Fielddesc = Tuple[int, Union[str, Tuple[Tuple[int, str], Optional[int]]]] + Fielddefs = List[Tuple[str, Fielddesc]] + Typesdict = Dict[str, Tuple[Constdefs, Fielddefs]] class TypesysError(Exception): diff --git a/src/rosbags/typesys/idl.py b/src/rosbags/typesys/idl.py index 259f7ce5..6c930c8f 100644 --- a/src/rosbags/typesys/idl.py +++ b/src/rosbags/typesys/idl.py @@ -261,8 +261,20 @@ class VisitorIDL(Visitor): # pylint: disable=too-many-public-methods def visit_specification(self, children: Any) -> Typesdict: """Process start symbol, return only children of modules.""" children = [x[0] for x in children if x is not None] - modules = [y for t, x in children if t == Nodetype.MODULE for y in x] - return {x[1]: x[2] for x in modules if x[0] == Nodetype.STRUCT} + structs = {} + consts: dict[str, list[tuple[str, str, Any]]] = {} + for item in children: + if item[0] != Nodetype.MODULE: + continue + for subitem in item[1]: + if subitem[0] == Nodetype.STRUCT: + structs[subitem[1]] = subitem[2] + elif subitem[0] == Nodetype.CONST and '_Constants/' in subitem[1][1]: + structname, varname = subitem[1][1].split('_Constants/') + if structname not in consts: + consts[structname] = [] + consts[structname].append((varname, subitem[1][0], subitem[1][2])) + return {k: (consts.get(k, []), v) for k, v in structs.items()} def visit_comment(self, children: Any) -> Any: """Process comment, suppress output.""" @@ -273,12 +285,6 @@ class VisitorIDL(Visitor): # pylint: disable=too-many-public-methods def visit_include(self, children: Any) -> Any: """Process include, suppress output.""" - def visit_type_dcl(self, children: Any) -> Any: - """Process typedef, pass structs, suppress otherwise.""" - if children[0] == Nodetype.STRUCT: - return children - return None - def visit_module_dcl(self, children: Any) -> Any: """Process module declaration.""" assert len(children) == 6 @@ -288,7 +294,6 @@ class VisitorIDL(Visitor): # pylint: disable=too-many-public-methods children = children[4] consts = [] structs = [] - modules = [] for item in children: if not item or item[0] is None: continue @@ -299,20 +304,23 @@ class VisitorIDL(Visitor): # pylint: disable=too-many-public-methods structs.append(item) else: assert item[0] == Nodetype.MODULE - modules.append(item) + consts += [x for x in item[1] if x[0] == Nodetype.CONST] + structs += [x for x in item[1] if x[0] == Nodetype.STRUCT] - for _, module in modules: - consts += [x for x in module if x[0] == Nodetype.CONST] - structs += [x for x in module if x[0] == Nodetype.STRUCT] - - consts = [(x[0], f'{name}/{x[1][0]}', *x[1][1:]) for x in consts] + consts = [(x[0], (x[1][0], f'{name}/{x[1][1]}', x[1][2])) for x in consts] structs = [(x[0], f'{name}/{x[1]}', *x[2:]) for x in structs] return (Nodetype.MODULE, consts + structs) def visit_const_dcl(self, children: Any) -> Any: """Process const declaration.""" - return (Nodetype.CONST, (children[1][1], *children[2:])) + return (Nodetype.CONST, (children[1][1], children[2][1], children[4][1])) + + def visit_type_dcl(self, children: Any) -> Any: + """Process type, pass structs, suppress otherwise.""" + if children[0] == Nodetype.STRUCT: + return children + return None def visit_type_declarator(self, children: Any) -> Any: """Process type declarator, register type mapping in instance typedef dictionary.""" @@ -323,7 +331,7 @@ class VisitorIDL(Visitor): # pylint: disable=too-many-public-methods declarators = [children[1][0], *[x[1:][0] for x in children[1][1]]] for declarator in declarators: if declarator[0] == Nodetype.ADECLARATOR: - value = (Nodetype.ARRAY, declarator[2][1], base) + value = (Nodetype.ARRAY, (base, declarator[2][1])) else: value = base self.typedefs[declarator[1][1]] = value @@ -333,8 +341,7 @@ class VisitorIDL(Visitor): # pylint: disable=too-many-public-methods assert len(children) in [4, 6] if len(children) == 6: assert children[4][0] == Nodetype.LITERAL_NUMBER - return (Nodetype.SEQUENCE, children[2]) - return (Nodetype.SEQUENCE, children[2]) + return (Nodetype.SEQUENCE, (children[2], None)) def create_struct_field(self, parts: Any) -> Any: """Create struct field and expand typedefs.""" @@ -346,7 +353,7 @@ class VisitorIDL(Visitor): # pylint: disable=too-many-public-methods name = self.typedefs[name[1]] return name - yield from ((resolve_name(typename), x[1]) for x in params if x) + yield from ((x[1][1], resolve_name(typename)) for x in params if x) def visit_struct_dcl(self, children: Any) -> Any: """Process struct declaration.""" diff --git a/src/rosbags/typesys/msg.py b/src/rosbags/typesys/msg.py index 59739c0f..75a24c4d 100644 --- a/src/rosbags/typesys/msg.py +++ b/src/rosbags/typesys/msg.py @@ -21,7 +21,7 @@ from .peg import Rule, Visitor, parse_grammar if TYPE_CHECKING: from typing import Any, List - from .base import Typesdict + from .base import Fielddesc, Typesdict GRAMMAR_MSG = r""" specification @@ -42,7 +42,7 @@ comment = r'#[^\n]*' const_dcl - = type_spec identifier '=' r'[^=][^\n]*' + = type_spec identifier '=' integer_literal field_dcl = type_spec identifier @@ -89,7 +89,7 @@ def normalize_msgtype(name: str) -> str: return str(path) -def normalize_fieldtype(typename: str, field: Any, names: List[str]): +def normalize_fieldtype(typename: str, field: Fielddesc, names: List[str]) -> Fielddesc: """Normalize field typename. Args: @@ -97,18 +97,20 @@ def normalize_fieldtype(typename: str, field: Any, names: List[str]): field: Field definition. names: Valid message names. + Returns: + Normalized fieldtype. + """ dct = {Path(name).name: name for name in names} - namedef = field[0] - if namedef[0] == Nodetype.NAME: - name = namedef[1] - elif namedef[0] == Nodetype.SEQUENCE: - name = namedef[1][1] + ftype, args = field + if ftype == Nodetype.NAME: + name = args else: - name = namedef[2][1] + name = args[0][1] + assert isinstance(name, str) if name in VisitorMSG.BASETYPES: - inamedef = (Nodetype.BASE, name) + ifield = (Nodetype.BASE, name) else: if name in dct: name = dct[name] @@ -118,16 +120,13 @@ def normalize_fieldtype(typename: str, field: Any, names: List[str]): name = str(Path(typename).parent / name) elif '/msg/' not in name: name = str((path := Path(name)).parent / 'msg' / path.name) - inamedef = (Nodetype.NAME, name) + ifield = (Nodetype.NAME, name) - if namedef[0] == Nodetype.NAME: - namedef = inamedef - elif namedef[0] == Nodetype.SEQUENCE: - namedef = (Nodetype.SEQUENCE, inamedef) - else: - namedef = (Nodetype.ARRAY, namedef[1], inamedef) + if ftype == Nodetype.NAME: + return ifield - field[0] = namedef + assert not isinstance(args, str) + return (ftype, (ifield, args[1])) class VisitorMSG(Visitor): @@ -157,6 +156,7 @@ class VisitorMSG(Visitor): def visit_const_dcl(self, children: Any) -> Any: """Process const declaration, suppress output.""" + return Nodetype.CONST, (children[0][1], children[1][1], children[3]) def visit_specification(self, children: Any) -> Typesdict: """Process start symbol.""" @@ -164,8 +164,10 @@ class VisitorMSG(Visitor): typedict = dict(typelist) names = list(typedict.keys()) for name, fields in typedict.items(): - for field in fields: - normalize_fieldtype(name, field, names) + consts = [(x[1][1], x[1][0], x[1][2]) for x in fields if x[0] == Nodetype.CONST] + fields = [x for x in fields if x[0] != Nodetype.CONST] + fields = [(field[1][1], normalize_fieldtype(name, field[0], names)) for field in fields] + typedict[name] = consts, fields return typedict def visit_msgdef(self, children: Any) -> Any: @@ -180,8 +182,8 @@ class VisitorMSG(Visitor): """Process array type specifier.""" length = children[1][1] if length: - return (Nodetype.ARRAY, int(length[0]), children[0]) - return (Nodetype.SEQUENCE, children[0]) + return Nodetype.ARRAY, (children[0], length[0]) + return Nodetype.SEQUENCE, (children[0], None) def visit_simple_type_spec(self, children: Any) -> Any: """Process simple type specifier.""" @@ -204,6 +206,10 @@ class VisitorMSG(Visitor): """Process identifier.""" return (Nodetype.NAME, children) + def visit_integer_literal(self, children: Any) -> Any: + """Process integer literal.""" + return int(children) + def get_types_from_msg(text: str, name: str) -> Typesdict: """Get type from msg message definition. diff --git a/src/rosbags/typesys/register.py b/src/rosbags/typesys/register.py index 59ead36d..cd433e5b 100644 --- a/src/rosbags/typesys/register.py +++ b/src/rosbags/typesys/register.py @@ -4,7 +4,6 @@ from __future__ import annotations -import json import re import sys from importlib.util import module_from_spec, spec_from_loader @@ -37,7 +36,7 @@ def get_typehint(desc: tuple) -> str: if desc[0] == Nodetype.NAME: return desc[1].replace('/', '__') - sub = desc[2 if desc[0] == Nodetype.ARRAY else 1] + sub = desc[1][0] if INTLIKE.match(sub[1]): typ = 'bool8' if sub[1] == 'bool' else sub[1] return f'numpy.ndarray[Any, numpy.dtype[numpy.{typ}]]' @@ -71,21 +70,27 @@ def generate_python_code(typs: Typesdict) -> str: 'from typing import TYPE_CHECKING', '', 'if TYPE_CHECKING:', - ' from typing import Any', + ' from typing import Any, ClassVar', '', ' import numpy', '', + ' from .base import Typesdict', '', ] - for name, fields in typs.items(): + for name, (consts, fields) in typs.items(): pyname = name.replace('/', '__') lines += [ '@dataclass', f'class {pyname}:', f' """Class for {name}."""', '', - *[f' {fname[1]}: {get_typehint(desc)}' for desc, fname in fields], + *[f' {fname}: {get_typehint(desc)}' for fname, desc in fields], + *[ + f' {fname}: ClassVar[{get_typehint((1, ftype))}] = {fvalue}' + for fname, ftype, fvalue in consts + ], + f' __msgtype__: ClassVar[str] = {name!r}', ] lines += [ @@ -93,16 +98,20 @@ def generate_python_code(typs: Typesdict) -> str: '', ] - lines += ['FIELDDEFS = {'] - for name, fields in typs.items(): + def get_ftype(ftype: tuple) -> tuple: + if ftype[0] <= 2: + return int(ftype[0]), ftype[1] + return int(ftype[0]), ((int(ftype[1][0][0]), ftype[1][0][1]), ftype[1][1]) + + lines += ['FIELDDEFS: Typesdict = {'] + for name, (consts, fields) in typs.items(): pyname = name.replace('/', '__') lines += [ - f' \'{name}\': [', - *[ - f' ({repr(fname[1])}, {json.loads(json.dumps(ftype))}),' - for ftype, fname in fields - ], - ' ],', + f' \'{name}\': ([', + *[f' ({fname!r}, {ftype!r}, {fvalue!r}),' for fname, ftype, fvalue in consts], + ' ], [', + *[f' ({fname!r}, {get_ftype(ftype)!r}),' for fname, ftype in fields], + ' ]),', ] lines += [ '}', @@ -127,15 +136,16 @@ def register_types(typs: Typesdict) -> None: module = module_from_spec(spec) sys.modules[name] = module exec(code, module.__dict__) # pylint: disable=exec-used - fielddefs = module.FIELDDEFS # type: ignore + fielddefs: Typesdict = module.FIELDDEFS # type: ignore - for name, fields in fielddefs.items(): + for name, (_, fields) in fielddefs.items(): if name == 'std_msgs/msg/Header': continue if have := types.FIELDDEFS.get(name): - have = [(x[0].lower(), x[1]) for x in have] + _, have_fields = have + have_fields = [(x[0].lower(), x[1]) for x in have_fields] fields = [(x[0].lower(), x[1]) for x in fields] - if have != fields: + if have_fields != fields: raise TypesysError(f'Type {name!r} is already present with different definition.') for name in fielddefs.keys() - types.FIELDDEFS.keys(): diff --git a/src/rosbags/typesys/types.py b/src/rosbags/typesys/types.py index f6c6263d..7c24dcf1 100644 --- a/src/rosbags/typesys/types.py +++ b/src/rosbags/typesys/types.py @@ -14,10 +14,11 @@ from dataclasses import dataclass from typing import TYPE_CHECKING if TYPE_CHECKING: - from typing import Any + from typing import Any, ClassVar import numpy + from .base import Typesdict @dataclass class builtin_interfaces__msg__Time: @@ -25,6 +26,7 @@ class builtin_interfaces__msg__Time: sec: int nanosec: int + __msgtype__: ClassVar[str] = 'builtin_interfaces/msg/Time' @dataclass @@ -33,6 +35,7 @@ class builtin_interfaces__msg__Duration: sec: int nanosec: int + __msgtype__: ClassVar[str] = 'builtin_interfaces/msg/Duration' @dataclass @@ -44,6 +47,11 @@ class diagnostic_msgs__msg__DiagnosticStatus: message: str hardware_id: str values: list[diagnostic_msgs__msg__KeyValue] + OK: ClassVar[int] = 0 + WARN: ClassVar[int] = 1 + ERROR: ClassVar[int] = 2 + STALE: ClassVar[int] = 3 + __msgtype__: ClassVar[str] = 'diagnostic_msgs/msg/DiagnosticStatus' @dataclass @@ -52,6 +60,7 @@ class diagnostic_msgs__msg__DiagnosticArray: header: std_msgs__msg__Header status: list[diagnostic_msgs__msg__DiagnosticStatus] + __msgtype__: ClassVar[str] = 'diagnostic_msgs/msg/DiagnosticArray' @dataclass @@ -60,6 +69,7 @@ class diagnostic_msgs__msg__KeyValue: key: str value: str + __msgtype__: ClassVar[str] = 'diagnostic_msgs/msg/KeyValue' @dataclass @@ -68,6 +78,7 @@ class geometry_msgs__msg__AccelWithCovariance: accel: geometry_msgs__msg__Accel covariance: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/AccelWithCovariance' @dataclass @@ -77,6 +88,7 @@ class geometry_msgs__msg__Point32: x: float y: float z: float + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/Point32' @dataclass @@ -86,6 +98,7 @@ class geometry_msgs__msg__Vector3: x: float y: float z: float + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/Vector3' @dataclass @@ -100,6 +113,7 @@ class geometry_msgs__msg__Inertia: iyy: float iyz: float izz: float + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/Inertia' @dataclass @@ -108,6 +122,7 @@ class geometry_msgs__msg__PoseWithCovarianceStamped: header: std_msgs__msg__Header pose: geometry_msgs__msg__PoseWithCovariance + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/PoseWithCovarianceStamped' @dataclass @@ -116,6 +131,7 @@ class geometry_msgs__msg__Twist: linear: geometry_msgs__msg__Vector3 angular: geometry_msgs__msg__Vector3 + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/Twist' @dataclass @@ -124,6 +140,7 @@ class geometry_msgs__msg__Pose: position: geometry_msgs__msg__Point orientation: geometry_msgs__msg__Quaternion + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/Pose' @dataclass @@ -133,6 +150,7 @@ class geometry_msgs__msg__Point: x: float y: float z: float + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/Point' @dataclass @@ -141,6 +159,7 @@ class geometry_msgs__msg__Vector3Stamped: header: std_msgs__msg__Header vector: geometry_msgs__msg__Vector3 + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/Vector3Stamped' @dataclass @@ -149,6 +168,7 @@ class geometry_msgs__msg__Transform: translation: geometry_msgs__msg__Vector3 rotation: geometry_msgs__msg__Quaternion + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/Transform' @dataclass @@ -157,6 +177,7 @@ class geometry_msgs__msg__PolygonStamped: header: std_msgs__msg__Header polygon: geometry_msgs__msg__Polygon + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/PolygonStamped' @dataclass @@ -167,6 +188,7 @@ class geometry_msgs__msg__Quaternion: y: float z: float w: float + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/Quaternion' @dataclass @@ -176,6 +198,7 @@ class geometry_msgs__msg__Pose2D: x: float y: float theta: float + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/Pose2D' @dataclass @@ -184,6 +207,7 @@ class geometry_msgs__msg__InertiaStamped: header: std_msgs__msg__Header inertia: geometry_msgs__msg__Inertia + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/InertiaStamped' @dataclass @@ -192,6 +216,7 @@ class geometry_msgs__msg__TwistStamped: header: std_msgs__msg__Header twist: geometry_msgs__msg__Twist + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/TwistStamped' @dataclass @@ -200,6 +225,7 @@ class geometry_msgs__msg__PoseStamped: header: std_msgs__msg__Header pose: geometry_msgs__msg__Pose + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/PoseStamped' @dataclass @@ -208,6 +234,7 @@ class geometry_msgs__msg__PointStamped: header: std_msgs__msg__Header point: geometry_msgs__msg__Point + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/PointStamped' @dataclass @@ -215,6 +242,7 @@ class geometry_msgs__msg__Polygon: """Class for geometry_msgs/msg/Polygon.""" points: list[geometry_msgs__msg__Point32] + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/Polygon' @dataclass @@ -223,6 +251,7 @@ class geometry_msgs__msg__PoseArray: header: std_msgs__msg__Header poses: list[geometry_msgs__msg__Pose] + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/PoseArray' @dataclass @@ -231,6 +260,7 @@ class geometry_msgs__msg__AccelStamped: header: std_msgs__msg__Header accel: geometry_msgs__msg__Accel + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/AccelStamped' @dataclass @@ -239,6 +269,7 @@ class geometry_msgs__msg__TwistWithCovarianceStamped: header: std_msgs__msg__Header twist: geometry_msgs__msg__TwistWithCovariance + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/TwistWithCovarianceStamped' @dataclass @@ -247,6 +278,7 @@ class geometry_msgs__msg__QuaternionStamped: header: std_msgs__msg__Header quaternion: geometry_msgs__msg__Quaternion + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/QuaternionStamped' @dataclass @@ -255,6 +287,7 @@ class geometry_msgs__msg__WrenchStamped: header: std_msgs__msg__Header wrench: geometry_msgs__msg__Wrench + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/WrenchStamped' @dataclass @@ -263,6 +296,7 @@ class geometry_msgs__msg__AccelWithCovarianceStamped: header: std_msgs__msg__Header accel: geometry_msgs__msg__AccelWithCovariance + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/AccelWithCovarianceStamped' @dataclass @@ -271,6 +305,7 @@ class geometry_msgs__msg__PoseWithCovariance: pose: geometry_msgs__msg__Pose covariance: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/PoseWithCovariance' @dataclass @@ -279,6 +314,7 @@ class geometry_msgs__msg__Wrench: force: geometry_msgs__msg__Vector3 torque: geometry_msgs__msg__Vector3 + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/Wrench' @dataclass @@ -288,6 +324,7 @@ class geometry_msgs__msg__TransformStamped: header: std_msgs__msg__Header child_frame_id: str transform: geometry_msgs__msg__Transform + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/TransformStamped' @dataclass @@ -296,6 +333,7 @@ class geometry_msgs__msg__Accel: linear: geometry_msgs__msg__Vector3 angular: geometry_msgs__msg__Vector3 + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/Accel' @dataclass @@ -304,6 +342,7 @@ class geometry_msgs__msg__TwistWithCovariance: twist: geometry_msgs__msg__Twist covariance: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + __msgtype__: ClassVar[str] = 'geometry_msgs/msg/TwistWithCovariance' @dataclass @@ -311,6 +350,7 @@ class libstatistics_collector__msg__DummyMessage: """Class for libstatistics_collector/msg/DummyMessage.""" header: std_msgs__msg__Header + __msgtype__: ClassVar[str] = 'libstatistics_collector/msg/DummyMessage' @dataclass @@ -320,6 +360,7 @@ class lifecycle_msgs__msg__TransitionDescription: transition: lifecycle_msgs__msg__Transition start_state: lifecycle_msgs__msg__State goal_state: lifecycle_msgs__msg__State + __msgtype__: ClassVar[str] = 'lifecycle_msgs/msg/TransitionDescription' @dataclass @@ -328,6 +369,18 @@ class lifecycle_msgs__msg__State: id: int label: str + PRIMARY_STATE_UNKNOWN: ClassVar[int] = 0 + PRIMARY_STATE_UNCONFIGURED: ClassVar[int] = 1 + PRIMARY_STATE_INACTIVE: ClassVar[int] = 2 + PRIMARY_STATE_ACTIVE: ClassVar[int] = 3 + PRIMARY_STATE_FINALIZED: ClassVar[int] = 4 + TRANSITION_STATE_CONFIGURING: ClassVar[int] = 10 + TRANSITION_STATE_CLEANINGUP: ClassVar[int] = 11 + TRANSITION_STATE_SHUTTINGDOWN: ClassVar[int] = 12 + TRANSITION_STATE_ACTIVATING: ClassVar[int] = 13 + TRANSITION_STATE_DEACTIVATING: ClassVar[int] = 14 + TRANSITION_STATE_ERRORPROCESSING: ClassVar[int] = 15 + __msgtype__: ClassVar[str] = 'lifecycle_msgs/msg/State' @dataclass @@ -338,6 +391,7 @@ class lifecycle_msgs__msg__TransitionEvent: transition: lifecycle_msgs__msg__Transition start_state: lifecycle_msgs__msg__State goal_state: lifecycle_msgs__msg__State + __msgtype__: ClassVar[str] = 'lifecycle_msgs/msg/TransitionEvent' @dataclass @@ -346,6 +400,37 @@ class lifecycle_msgs__msg__Transition: id: int label: str + TRANSITION_CREATE: ClassVar[int] = 0 + TRANSITION_CONFIGURE: ClassVar[int] = 1 + TRANSITION_CLEANUP: ClassVar[int] = 2 + TRANSITION_ACTIVATE: ClassVar[int] = 3 + TRANSITION_DEACTIVATE: ClassVar[int] = 4 + TRANSITION_UNCONFIGURED_SHUTDOWN: ClassVar[int] = 5 + TRANSITION_INACTIVE_SHUTDOWN: ClassVar[int] = 6 + TRANSITION_ACTIVE_SHUTDOWN: ClassVar[int] = 7 + TRANSITION_DESTROY: ClassVar[int] = 8 + TRANSITION_ON_CONFIGURE_SUCCESS: ClassVar[int] = 10 + TRANSITION_ON_CONFIGURE_FAILURE: ClassVar[int] = 11 + TRANSITION_ON_CONFIGURE_ERROR: ClassVar[int] = 12 + TRANSITION_ON_CLEANUP_SUCCESS: ClassVar[int] = 20 + TRANSITION_ON_CLEANUP_FAILURE: ClassVar[int] = 21 + TRANSITION_ON_CLEANUP_ERROR: ClassVar[int] = 22 + TRANSITION_ON_ACTIVATE_SUCCESS: ClassVar[int] = 30 + TRANSITION_ON_ACTIVATE_FAILURE: ClassVar[int] = 31 + TRANSITION_ON_ACTIVATE_ERROR: ClassVar[int] = 32 + TRANSITION_ON_DEACTIVATE_SUCCESS: ClassVar[int] = 40 + TRANSITION_ON_DEACTIVATE_FAILURE: ClassVar[int] = 41 + TRANSITION_ON_DEACTIVATE_ERROR: ClassVar[int] = 42 + TRANSITION_ON_SHUTDOWN_SUCCESS: ClassVar[int] = 50 + TRANSITION_ON_SHUTDOWN_FAILURE: ClassVar[int] = 51 + TRANSITION_ON_SHUTDOWN_ERROR: ClassVar[int] = 52 + TRANSITION_ON_ERROR_SUCCESS: ClassVar[int] = 60 + TRANSITION_ON_ERROR_FAILURE: ClassVar[int] = 61 + TRANSITION_ON_ERROR_ERROR: ClassVar[int] = 62 + TRANSITION_CALLBACK_SUCCESS: ClassVar[int] = 97 + TRANSITION_CALLBACK_FAILURE: ClassVar[int] = 98 + TRANSITION_CALLBACK_ERROR: ClassVar[int] = 99 + __msgtype__: ClassVar[str] = 'lifecycle_msgs/msg/Transition' @dataclass @@ -357,6 +442,7 @@ class nav_msgs__msg__MapMetaData: width: int height: int origin: geometry_msgs__msg__Pose + __msgtype__: ClassVar[str] = 'nav_msgs/msg/MapMetaData' @dataclass @@ -367,6 +453,7 @@ class nav_msgs__msg__GridCells: cell_width: float cell_height: float cells: list[geometry_msgs__msg__Point] + __msgtype__: ClassVar[str] = 'nav_msgs/msg/GridCells' @dataclass @@ -377,6 +464,7 @@ class nav_msgs__msg__Odometry: child_frame_id: str pose: geometry_msgs__msg__PoseWithCovariance twist: geometry_msgs__msg__TwistWithCovariance + __msgtype__: ClassVar[str] = 'nav_msgs/msg/Odometry' @dataclass @@ -385,6 +473,7 @@ class nav_msgs__msg__Path: header: std_msgs__msg__Header poses: list[geometry_msgs__msg__PoseStamped] + __msgtype__: ClassVar[str] = 'nav_msgs/msg/Path' @dataclass @@ -394,6 +483,7 @@ class nav_msgs__msg__OccupancyGrid: header: std_msgs__msg__Header info: nav_msgs__msg__MapMetaData data: numpy.ndarray[Any, numpy.dtype[numpy.int8]] + __msgtype__: ClassVar[str] = 'nav_msgs/msg/OccupancyGrid' @dataclass @@ -402,6 +492,7 @@ class rcl_interfaces__msg__ListParametersResult: names: list[str] prefixes: list[str] + __msgtype__: ClassVar[str] = 'rcl_interfaces/msg/ListParametersResult' @dataclass @@ -409,6 +500,17 @@ class rcl_interfaces__msg__ParameterType: """Class for rcl_interfaces/msg/ParameterType.""" structure_needs_at_least_one_member: int + PARAMETER_NOT_SET: ClassVar[int] = 0 + PARAMETER_BOOL: ClassVar[int] = 1 + PARAMETER_INTEGER: ClassVar[int] = 2 + PARAMETER_DOUBLE: ClassVar[int] = 3 + PARAMETER_STRING: ClassVar[int] = 4 + PARAMETER_BYTE_ARRAY: ClassVar[int] = 5 + PARAMETER_BOOL_ARRAY: ClassVar[int] = 6 + PARAMETER_INTEGER_ARRAY: ClassVar[int] = 7 + PARAMETER_DOUBLE_ARRAY: ClassVar[int] = 8 + PARAMETER_STRING_ARRAY: ClassVar[int] = 9 + __msgtype__: ClassVar[str] = 'rcl_interfaces/msg/ParameterType' @dataclass @@ -418,6 +520,7 @@ class rcl_interfaces__msg__ParameterEventDescriptors: new_parameters: list[rcl_interfaces__msg__ParameterDescriptor] changed_parameters: list[rcl_interfaces__msg__ParameterDescriptor] deleted_parameters: list[rcl_interfaces__msg__ParameterDescriptor] + __msgtype__: ClassVar[str] = 'rcl_interfaces/msg/ParameterEventDescriptors' @dataclass @@ -429,6 +532,7 @@ class rcl_interfaces__msg__ParameterEvent: new_parameters: list[rcl_interfaces__msg__Parameter] changed_parameters: list[rcl_interfaces__msg__Parameter] deleted_parameters: list[rcl_interfaces__msg__Parameter] + __msgtype__: ClassVar[str] = 'rcl_interfaces/msg/ParameterEvent' @dataclass @@ -438,6 +542,7 @@ class rcl_interfaces__msg__IntegerRange: from_value: int to_value: int step: int + __msgtype__: ClassVar[str] = 'rcl_interfaces/msg/IntegerRange' @dataclass @@ -446,6 +551,7 @@ class rcl_interfaces__msg__Parameter: name: str value: rcl_interfaces__msg__ParameterValue + __msgtype__: ClassVar[str] = 'rcl_interfaces/msg/Parameter' @dataclass @@ -462,6 +568,7 @@ class rcl_interfaces__msg__ParameterValue: integer_array_value: numpy.ndarray[Any, numpy.dtype[numpy.int64]] double_array_value: numpy.ndarray[Any, numpy.dtype[numpy.float64]] string_array_value: list[str] + __msgtype__: ClassVar[str] = 'rcl_interfaces/msg/ParameterValue' @dataclass @@ -471,6 +578,7 @@ class rcl_interfaces__msg__FloatingPointRange: from_value: float to_value: float step: float + __msgtype__: ClassVar[str] = 'rcl_interfaces/msg/FloatingPointRange' @dataclass @@ -479,6 +587,7 @@ class rcl_interfaces__msg__SetParametersResult: successful: bool reason: str + __msgtype__: ClassVar[str] = 'rcl_interfaces/msg/SetParametersResult' @dataclass @@ -492,6 +601,12 @@ class rcl_interfaces__msg__Log: file: str function: str line: int + DEBUG: ClassVar[int] = 10 + INFO: ClassVar[int] = 20 + WARN: ClassVar[int] = 30 + ERROR: ClassVar[int] = 40 + FATAL: ClassVar[int] = 50 + __msgtype__: ClassVar[str] = 'rcl_interfaces/msg/Log' @dataclass @@ -505,6 +620,7 @@ class rcl_interfaces__msg__ParameterDescriptor: read_only: bool floating_point_range: list[rcl_interfaces__msg__FloatingPointRange] integer_range: list[rcl_interfaces__msg__IntegerRange] + __msgtype__: ClassVar[str] = 'rcl_interfaces/msg/ParameterDescriptor' @dataclass @@ -512,6 +628,7 @@ class rmw_dds_common__msg__Gid: """Class for rmw_dds_common/msg/Gid.""" data: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] + __msgtype__: ClassVar[str] = 'rmw_dds_common/msg/Gid' @dataclass @@ -522,6 +639,7 @@ class rmw_dds_common__msg__NodeEntitiesInfo: node_name: str reader_gid_seq: list[rmw_dds_common__msg__Gid] writer_gid_seq: list[rmw_dds_common__msg__Gid] + __msgtype__: ClassVar[str] = 'rmw_dds_common/msg/NodeEntitiesInfo' @dataclass @@ -530,6 +648,7 @@ class rmw_dds_common__msg__ParticipantEntitiesInfo: gid: rmw_dds_common__msg__Gid node_entities_info_seq: list[rmw_dds_common__msg__NodeEntitiesInfo] + __msgtype__: ClassVar[str] = 'rmw_dds_common/msg/ParticipantEntitiesInfo' @dataclass @@ -537,6 +656,7 @@ class rosgraph_msgs__msg__Clock: """Class for rosgraph_msgs/msg/Clock.""" clock: builtin_interfaces__msg__Time + __msgtype__: ClassVar[str] = 'rosgraph_msgs/msg/Clock' @dataclass @@ -546,6 +666,7 @@ class sensor_msgs__msg__Temperature: header: std_msgs__msg__Header temperature: float variance: float + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/Temperature' @dataclass @@ -558,6 +679,9 @@ class sensor_msgs__msg__Range: min_range: float max_range: float range: float + ULTRASOUND: ClassVar[int] = 0 + INFRARED: ClassVar[int] = 1 + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/Range' @dataclass @@ -569,6 +693,7 @@ class sensor_msgs__msg__RegionOfInterest: height: int width: int do_rectify: bool + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/RegionOfInterest' @dataclass @@ -576,6 +701,7 @@ class sensor_msgs__msg__JoyFeedbackArray: """Class for sensor_msgs/msg/JoyFeedbackArray.""" array: list[sensor_msgs__msg__JoyFeedback] + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/JoyFeedbackArray' @dataclass @@ -585,6 +711,7 @@ class sensor_msgs__msg__TimeReference: header: std_msgs__msg__Header time_ref: builtin_interfaces__msg__Time source: str + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/TimeReference' @dataclass @@ -594,6 +721,7 @@ class sensor_msgs__msg__CompressedImage: header: std_msgs__msg__Header format: str data: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/CompressedImage' @dataclass @@ -610,6 +738,7 @@ class sensor_msgs__msg__MultiEchoLaserScan: range_max: float ranges: list[sensor_msgs__msg__LaserEcho] intensities: list[sensor_msgs__msg__LaserEcho] + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/MultiEchoLaserScan' @dataclass @@ -617,6 +746,7 @@ class sensor_msgs__msg__LaserEcho: """Class for sensor_msgs/msg/LaserEcho.""" echoes: numpy.ndarray[Any, numpy.dtype[numpy.float32]] + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/LaserEcho' @dataclass @@ -625,6 +755,7 @@ class sensor_msgs__msg__ChannelFloat32: name: str values: numpy.ndarray[Any, numpy.dtype[numpy.float32]] + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/ChannelFloat32' @dataclass @@ -642,6 +773,7 @@ class sensor_msgs__msg__CameraInfo: binning_x: int binning_y: int roi: sensor_msgs__msg__RegionOfInterest + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/CameraInfo' @dataclass @@ -651,6 +783,7 @@ class sensor_msgs__msg__RelativeHumidity: header: std_msgs__msg__Header relative_humidity: float variance: float + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/RelativeHumidity' @dataclass @@ -660,6 +793,7 @@ class sensor_msgs__msg__FluidPressure: header: std_msgs__msg__Header fluid_pressure: float variance: float + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/FluidPressure' @dataclass @@ -676,6 +810,7 @@ class sensor_msgs__msg__LaserScan: range_max: float ranges: numpy.ndarray[Any, numpy.dtype[numpy.float32]] intensities: numpy.ndarray[Any, numpy.dtype[numpy.float32]] + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/LaserScan' @dataclass @@ -698,6 +833,28 @@ class sensor_msgs__msg__BatteryState: cell_temperature: numpy.ndarray[Any, numpy.dtype[numpy.float32]] location: str serial_number: str + POWER_SUPPLY_STATUS_UNKNOWN: ClassVar[int] = 0 + POWER_SUPPLY_STATUS_CHARGING: ClassVar[int] = 1 + POWER_SUPPLY_STATUS_DISCHARGING: ClassVar[int] = 2 + POWER_SUPPLY_STATUS_NOT_CHARGING: ClassVar[int] = 3 + POWER_SUPPLY_STATUS_FULL: ClassVar[int] = 4 + POWER_SUPPLY_HEALTH_UNKNOWN: ClassVar[int] = 0 + POWER_SUPPLY_HEALTH_GOOD: ClassVar[int] = 1 + POWER_SUPPLY_HEALTH_OVERHEAT: ClassVar[int] = 2 + POWER_SUPPLY_HEALTH_DEAD: ClassVar[int] = 3 + POWER_SUPPLY_HEALTH_OVERVOLTAGE: ClassVar[int] = 4 + POWER_SUPPLY_HEALTH_UNSPEC_FAILURE: ClassVar[int] = 5 + POWER_SUPPLY_HEALTH_COLD: ClassVar[int] = 6 + POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE: ClassVar[int] = 7 + POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE: ClassVar[int] = 8 + POWER_SUPPLY_TECHNOLOGY_UNKNOWN: ClassVar[int] = 0 + POWER_SUPPLY_TECHNOLOGY_NIMH: ClassVar[int] = 1 + POWER_SUPPLY_TECHNOLOGY_LION: ClassVar[int] = 2 + POWER_SUPPLY_TECHNOLOGY_LIPO: ClassVar[int] = 3 + POWER_SUPPLY_TECHNOLOGY_LIFE: ClassVar[int] = 4 + POWER_SUPPLY_TECHNOLOGY_NICD: ClassVar[int] = 5 + POWER_SUPPLY_TECHNOLOGY_LIMN: ClassVar[int] = 6 + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/BatteryState' @dataclass @@ -711,6 +868,7 @@ class sensor_msgs__msg__Image: is_bigendian: int step: int data: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/Image' @dataclass @@ -720,6 +878,7 @@ class sensor_msgs__msg__PointCloud: header: std_msgs__msg__Header points: list[geometry_msgs__msg__Point32] channels: list[sensor_msgs__msg__ChannelFloat32] + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/PointCloud' @dataclass @@ -733,6 +892,7 @@ class sensor_msgs__msg__Imu: angular_velocity_covariance: numpy.ndarray[Any, numpy.dtype[numpy.float64]] linear_acceleration: geometry_msgs__msg__Vector3 linear_acceleration_covariance: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/Imu' @dataclass @@ -741,6 +901,15 @@ class sensor_msgs__msg__NavSatStatus: status: int service: int + STATUS_NO_FIX: ClassVar[int] = -1 + STATUS_FIX: ClassVar[int] = 0 + STATUS_SBAS_FIX: ClassVar[int] = 1 + STATUS_GBAS_FIX: ClassVar[int] = 2 + SERVICE_GPS: ClassVar[int] = 1 + SERVICE_GLONASS: ClassVar[int] = 2 + SERVICE_COMPASS: ClassVar[int] = 4 + SERVICE_GALILEO: ClassVar[int] = 8 + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/NavSatStatus' @dataclass @@ -750,6 +919,7 @@ class sensor_msgs__msg__Illuminance: header: std_msgs__msg__Header illuminance: float variance: float + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/Illuminance' @dataclass @@ -759,6 +929,7 @@ class sensor_msgs__msg__Joy: header: std_msgs__msg__Header axes: numpy.ndarray[Any, numpy.dtype[numpy.float32]] buttons: numpy.ndarray[Any, numpy.dtype[numpy.int32]] + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/Joy' @dataclass @@ -772,6 +943,11 @@ class sensor_msgs__msg__NavSatFix: altitude: float position_covariance: numpy.ndarray[Any, numpy.dtype[numpy.float64]] position_covariance_type: int + COVARIANCE_TYPE_UNKNOWN: ClassVar[int] = 0 + COVARIANCE_TYPE_APPROXIMATED: ClassVar[int] = 1 + COVARIANCE_TYPE_DIAGONAL_KNOWN: ClassVar[int] = 2 + COVARIANCE_TYPE_KNOWN: ClassVar[int] = 3 + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/NavSatFix' @dataclass @@ -783,6 +959,7 @@ class sensor_msgs__msg__MultiDOFJointState: transforms: list[geometry_msgs__msg__Transform] twist: list[geometry_msgs__msg__Twist] wrench: list[geometry_msgs__msg__Wrench] + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/MultiDOFJointState' @dataclass @@ -792,6 +969,7 @@ class sensor_msgs__msg__MagneticField: header: std_msgs__msg__Header magnetic_field: geometry_msgs__msg__Vector3 magnetic_field_covariance: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/MagneticField' @dataclass @@ -803,6 +981,7 @@ class sensor_msgs__msg__JointState: position: numpy.ndarray[Any, numpy.dtype[numpy.float64]] velocity: numpy.ndarray[Any, numpy.dtype[numpy.float64]] effort: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/JointState' @dataclass @@ -813,6 +992,15 @@ class sensor_msgs__msg__PointField: offset: int datatype: int count: int + INT8: ClassVar[int] = 1 + UINT8: ClassVar[int] = 2 + INT16: ClassVar[int] = 3 + UINT16: ClassVar[int] = 4 + INT32: ClassVar[int] = 5 + UINT32: ClassVar[int] = 6 + FLOAT32: ClassVar[int] = 7 + FLOAT64: ClassVar[int] = 8 + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/PointField' @dataclass @@ -828,6 +1016,7 @@ class sensor_msgs__msg__PointCloud2: row_step: int data: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] is_dense: bool + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/PointCloud2' @dataclass @@ -837,6 +1026,10 @@ class sensor_msgs__msg__JoyFeedback: type: int id: int intensity: float + TYPE_LED: ClassVar[int] = 0 + TYPE_RUMBLE: ClassVar[int] = 1 + TYPE_BUZZER: ClassVar[int] = 2 + __msgtype__: ClassVar[str] = 'sensor_msgs/msg/JoyFeedback' @dataclass @@ -845,6 +1038,19 @@ class shape_msgs__msg__SolidPrimitive: type: int dimensions: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + BOX: ClassVar[int] = 1 + SPHERE: ClassVar[int] = 2 + CYLINDER: ClassVar[int] = 3 + CONE: ClassVar[int] = 4 + BOX_X: ClassVar[int] = 0 + BOX_Y: ClassVar[int] = 1 + BOX_Z: ClassVar[int] = 2 + SPHERE_RADIUS: ClassVar[int] = 0 + CYLINDER_HEIGHT: ClassVar[int] = 0 + CYLINDER_RADIUS: ClassVar[int] = 1 + CONE_HEIGHT: ClassVar[int] = 0 + CONE_RADIUS: ClassVar[int] = 1 + __msgtype__: ClassVar[str] = 'shape_msgs/msg/SolidPrimitive' @dataclass @@ -853,6 +1059,7 @@ class shape_msgs__msg__Mesh: triangles: list[shape_msgs__msg__MeshTriangle] vertices: list[geometry_msgs__msg__Point] + __msgtype__: ClassVar[str] = 'shape_msgs/msg/Mesh' @dataclass @@ -860,6 +1067,7 @@ class shape_msgs__msg__Plane: """Class for shape_msgs/msg/Plane.""" coef: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + __msgtype__: ClassVar[str] = 'shape_msgs/msg/Plane' @dataclass @@ -867,6 +1075,7 @@ class shape_msgs__msg__MeshTriangle: """Class for shape_msgs/msg/MeshTriangle.""" vertex_indices: numpy.ndarray[Any, numpy.dtype[numpy.uint32]] + __msgtype__: ClassVar[str] = 'shape_msgs/msg/MeshTriangle' @dataclass @@ -874,6 +1083,13 @@ class statistics_msgs__msg__StatisticDataType: """Class for statistics_msgs/msg/StatisticDataType.""" structure_needs_at_least_one_member: int + STATISTICS_DATA_TYPE_UNINITIALIZED: ClassVar[int] = 0 + STATISTICS_DATA_TYPE_AVERAGE: ClassVar[int] = 1 + STATISTICS_DATA_TYPE_MINIMUM: ClassVar[int] = 2 + STATISTICS_DATA_TYPE_MAXIMUM: ClassVar[int] = 3 + STATISTICS_DATA_TYPE_STDDEV: ClassVar[int] = 4 + STATISTICS_DATA_TYPE_SAMPLE_COUNT: ClassVar[int] = 5 + __msgtype__: ClassVar[str] = 'statistics_msgs/msg/StatisticDataType' @dataclass @@ -882,6 +1098,7 @@ class statistics_msgs__msg__StatisticDataPoint: data_type: int data: float + __msgtype__: ClassVar[str] = 'statistics_msgs/msg/StatisticDataPoint' @dataclass @@ -894,6 +1111,7 @@ class statistics_msgs__msg__MetricsMessage: window_start: builtin_interfaces__msg__Time window_stop: builtin_interfaces__msg__Time statistics: list[statistics_msgs__msg__StatisticDataPoint] + __msgtype__: ClassVar[str] = 'statistics_msgs/msg/MetricsMessage' @dataclass @@ -901,6 +1119,7 @@ class std_msgs__msg__UInt8: """Class for std_msgs/msg/UInt8.""" data: int + __msgtype__: ClassVar[str] = 'std_msgs/msg/UInt8' @dataclass @@ -909,6 +1128,7 @@ class std_msgs__msg__Float32MultiArray: layout: std_msgs__msg__MultiArrayLayout data: numpy.ndarray[Any, numpy.dtype[numpy.float32]] + __msgtype__: ClassVar[str] = 'std_msgs/msg/Float32MultiArray' @dataclass @@ -916,6 +1136,7 @@ class std_msgs__msg__Int8: """Class for std_msgs/msg/Int8.""" data: int + __msgtype__: ClassVar[str] = 'std_msgs/msg/Int8' @dataclass @@ -923,6 +1144,7 @@ class std_msgs__msg__Empty: """Class for std_msgs/msg/Empty.""" structure_needs_at_least_one_member: int + __msgtype__: ClassVar[str] = 'std_msgs/msg/Empty' @dataclass @@ -930,6 +1152,7 @@ class std_msgs__msg__String: """Class for std_msgs/msg/String.""" data: str + __msgtype__: ClassVar[str] = 'std_msgs/msg/String' @dataclass @@ -939,6 +1162,7 @@ class std_msgs__msg__MultiArrayDimension: label: str size: int stride: int + __msgtype__: ClassVar[str] = 'std_msgs/msg/MultiArrayDimension' @dataclass @@ -946,6 +1170,7 @@ class std_msgs__msg__UInt64: """Class for std_msgs/msg/UInt64.""" data: int + __msgtype__: ClassVar[str] = 'std_msgs/msg/UInt64' @dataclass @@ -953,6 +1178,7 @@ class std_msgs__msg__UInt16: """Class for std_msgs/msg/UInt16.""" data: int + __msgtype__: ClassVar[str] = 'std_msgs/msg/UInt16' @dataclass @@ -960,6 +1186,7 @@ class std_msgs__msg__Float32: """Class for std_msgs/msg/Float32.""" data: float + __msgtype__: ClassVar[str] = 'std_msgs/msg/Float32' @dataclass @@ -967,6 +1194,7 @@ class std_msgs__msg__Int64: """Class for std_msgs/msg/Int64.""" data: int + __msgtype__: ClassVar[str] = 'std_msgs/msg/Int64' @dataclass @@ -975,6 +1203,7 @@ class std_msgs__msg__Int16MultiArray: layout: std_msgs__msg__MultiArrayLayout data: numpy.ndarray[Any, numpy.dtype[numpy.int16]] + __msgtype__: ClassVar[str] = 'std_msgs/msg/Int16MultiArray' @dataclass @@ -982,6 +1211,7 @@ class std_msgs__msg__Int16: """Class for std_msgs/msg/Int16.""" data: int + __msgtype__: ClassVar[str] = 'std_msgs/msg/Int16' @dataclass @@ -990,6 +1220,7 @@ class std_msgs__msg__Float64MultiArray: layout: std_msgs__msg__MultiArrayLayout data: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + __msgtype__: ClassVar[str] = 'std_msgs/msg/Float64MultiArray' @dataclass @@ -998,6 +1229,7 @@ class std_msgs__msg__MultiArrayLayout: dim: list[std_msgs__msg__MultiArrayDimension] data_offset: int + __msgtype__: ClassVar[str] = 'std_msgs/msg/MultiArrayLayout' @dataclass @@ -1006,6 +1238,7 @@ class std_msgs__msg__UInt32MultiArray: layout: std_msgs__msg__MultiArrayLayout data: numpy.ndarray[Any, numpy.dtype[numpy.uint32]] + __msgtype__: ClassVar[str] = 'std_msgs/msg/UInt32MultiArray' @dataclass @@ -1014,6 +1247,7 @@ class std_msgs__msg__Header: stamp: builtin_interfaces__msg__Time frame_id: str + __msgtype__: ClassVar[str] = 'std_msgs/msg/Header' @dataclass @@ -1022,6 +1256,7 @@ class std_msgs__msg__ByteMultiArray: layout: std_msgs__msg__MultiArrayLayout data: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] + __msgtype__: ClassVar[str] = 'std_msgs/msg/ByteMultiArray' @dataclass @@ -1030,6 +1265,7 @@ class std_msgs__msg__Int8MultiArray: layout: std_msgs__msg__MultiArrayLayout data: numpy.ndarray[Any, numpy.dtype[numpy.int8]] + __msgtype__: ClassVar[str] = 'std_msgs/msg/Int8MultiArray' @dataclass @@ -1037,6 +1273,7 @@ class std_msgs__msg__Float64: """Class for std_msgs/msg/Float64.""" data: float + __msgtype__: ClassVar[str] = 'std_msgs/msg/Float64' @dataclass @@ -1045,6 +1282,7 @@ class std_msgs__msg__UInt8MultiArray: layout: std_msgs__msg__MultiArrayLayout data: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] + __msgtype__: ClassVar[str] = 'std_msgs/msg/UInt8MultiArray' @dataclass @@ -1052,6 +1290,7 @@ class std_msgs__msg__Byte: """Class for std_msgs/msg/Byte.""" data: int + __msgtype__: ClassVar[str] = 'std_msgs/msg/Byte' @dataclass @@ -1059,6 +1298,7 @@ class std_msgs__msg__Char: """Class for std_msgs/msg/Char.""" data: int + __msgtype__: ClassVar[str] = 'std_msgs/msg/Char' @dataclass @@ -1067,6 +1307,7 @@ class std_msgs__msg__UInt64MultiArray: layout: std_msgs__msg__MultiArrayLayout data: numpy.ndarray[Any, numpy.dtype[numpy.uint64]] + __msgtype__: ClassVar[str] = 'std_msgs/msg/UInt64MultiArray' @dataclass @@ -1075,6 +1316,7 @@ class std_msgs__msg__Int32MultiArray: layout: std_msgs__msg__MultiArrayLayout data: numpy.ndarray[Any, numpy.dtype[numpy.int32]] + __msgtype__: ClassVar[str] = 'std_msgs/msg/Int32MultiArray' @dataclass @@ -1085,6 +1327,7 @@ class std_msgs__msg__ColorRGBA: g: float b: float a: float + __msgtype__: ClassVar[str] = 'std_msgs/msg/ColorRGBA' @dataclass @@ -1092,6 +1335,7 @@ class std_msgs__msg__Bool: """Class for std_msgs/msg/Bool.""" data: bool + __msgtype__: ClassVar[str] = 'std_msgs/msg/Bool' @dataclass @@ -1099,6 +1343,7 @@ class std_msgs__msg__UInt32: """Class for std_msgs/msg/UInt32.""" data: int + __msgtype__: ClassVar[str] = 'std_msgs/msg/UInt32' @dataclass @@ -1107,6 +1352,7 @@ class std_msgs__msg__Int64MultiArray: layout: std_msgs__msg__MultiArrayLayout data: numpy.ndarray[Any, numpy.dtype[numpy.int64]] + __msgtype__: ClassVar[str] = 'std_msgs/msg/Int64MultiArray' @dataclass @@ -1114,6 +1360,7 @@ class std_msgs__msg__Int32: """Class for std_msgs/msg/Int32.""" data: int + __msgtype__: ClassVar[str] = 'std_msgs/msg/Int32' @dataclass @@ -1122,6 +1369,7 @@ class std_msgs__msg__UInt16MultiArray: layout: std_msgs__msg__MultiArrayLayout data: numpy.ndarray[Any, numpy.dtype[numpy.uint16]] + __msgtype__: ClassVar[str] = 'std_msgs/msg/UInt16MultiArray' @dataclass @@ -1136,6 +1384,7 @@ class stereo_msgs__msg__DisparityImage: min_disparity: float max_disparity: float delta_d: float + __msgtype__: ClassVar[str] = 'stereo_msgs/msg/DisparityImage' @dataclass @@ -1144,6 +1393,14 @@ class tf2_msgs__msg__TF2Error: error: int error_string: str + NO_ERROR: ClassVar[int] = 0 + LOOKUP_ERROR: ClassVar[int] = 1 + CONNECTIVITY_ERROR: ClassVar[int] = 2 + EXTRAPOLATION_ERROR: ClassVar[int] = 3 + INVALID_ARGUMENT_ERROR: ClassVar[int] = 4 + TIMEOUT_ERROR: ClassVar[int] = 5 + TRANSFORM_ERROR: ClassVar[int] = 6 + __msgtype__: ClassVar[str] = 'tf2_msgs/msg/TF2Error' @dataclass @@ -1151,6 +1408,7 @@ class tf2_msgs__msg__TFMessage: """Class for tf2_msgs/msg/TFMessage.""" transforms: list[geometry_msgs__msg__TransformStamped] + __msgtype__: ClassVar[str] = 'tf2_msgs/msg/TFMessage' @dataclass @@ -1160,6 +1418,7 @@ class trajectory_msgs__msg__MultiDOFJointTrajectory: header: std_msgs__msg__Header joint_names: list[str] points: list[trajectory_msgs__msg__MultiDOFJointTrajectoryPoint] + __msgtype__: ClassVar[str] = 'trajectory_msgs/msg/MultiDOFJointTrajectory' @dataclass @@ -1169,6 +1428,7 @@ class trajectory_msgs__msg__JointTrajectory: header: std_msgs__msg__Header joint_names: list[str] points: list[trajectory_msgs__msg__JointTrajectoryPoint] + __msgtype__: ClassVar[str] = 'trajectory_msgs/msg/JointTrajectory' @dataclass @@ -1180,6 +1440,7 @@ class trajectory_msgs__msg__JointTrajectoryPoint: accelerations: numpy.ndarray[Any, numpy.dtype[numpy.float64]] effort: numpy.ndarray[Any, numpy.dtype[numpy.float64]] time_from_start: builtin_interfaces__msg__Duration + __msgtype__: ClassVar[str] = 'trajectory_msgs/msg/JointTrajectoryPoint' @dataclass @@ -1190,6 +1451,7 @@ class trajectory_msgs__msg__MultiDOFJointTrajectoryPoint: velocities: list[geometry_msgs__msg__Twist] accelerations: list[geometry_msgs__msg__Twist] time_from_start: builtin_interfaces__msg__Duration + __msgtype__: ClassVar[str] = 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint' @dataclass @@ -1197,6 +1459,7 @@ class unique_identifier_msgs__msg__UUID: """Class for unique_identifier_msgs/msg/UUID.""" uuid: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] + __msgtype__: ClassVar[str] = 'unique_identifier_msgs/msg/UUID' @dataclass @@ -1218,6 +1481,23 @@ class visualization_msgs__msg__Marker: text: str mesh_resource: str mesh_use_embedded_materials: bool + ARROW: ClassVar[int] = 0 + CUBE: ClassVar[int] = 1 + SPHERE: ClassVar[int] = 2 + CYLINDER: ClassVar[int] = 3 + LINE_STRIP: ClassVar[int] = 4 + LINE_LIST: ClassVar[int] = 5 + CUBE_LIST: ClassVar[int] = 6 + SPHERE_LIST: ClassVar[int] = 7 + POINTS: ClassVar[int] = 8 + TEXT_VIEW_FACING: ClassVar[int] = 9 + MESH_RESOURCE: ClassVar[int] = 10 + TRIANGLE_LIST: ClassVar[int] = 11 + ADD: ClassVar[int] = 0 + MODIFY: ClassVar[int] = 0 + DELETE: ClassVar[int] = 2 + DELETEALL: ClassVar[int] = 3 + __msgtype__: ClassVar[str] = 'visualization_msgs/msg/Marker' @dataclass @@ -1227,6 +1507,7 @@ class visualization_msgs__msg__InteractiveMarkerInit: server_id: str seq_num: int markers: list[visualization_msgs__msg__InteractiveMarker] + __msgtype__: ClassVar[str] = 'visualization_msgs/msg/InteractiveMarkerInit' @dataclass @@ -1238,6 +1519,10 @@ class visualization_msgs__msg__MenuEntry: title: str command: str command_type: int + FEEDBACK: ClassVar[int] = 0 + ROSRUN: ClassVar[int] = 1 + ROSLAUNCH: ClassVar[int] = 2 + __msgtype__: ClassVar[str] = 'visualization_msgs/msg/MenuEntry' @dataclass @@ -1245,6 +1530,7 @@ class visualization_msgs__msg__MarkerArray: """Class for visualization_msgs/msg/MarkerArray.""" markers: list[visualization_msgs__msg__Marker] + __msgtype__: ClassVar[str] = 'visualization_msgs/msg/MarkerArray' @dataclass @@ -1257,6 +1543,9 @@ class visualization_msgs__msg__InteractiveMarkerUpdate: markers: list[visualization_msgs__msg__InteractiveMarker] poses: list[visualization_msgs__msg__InteractiveMarkerPose] erases: list[str] + KEEP_ALIVE: ClassVar[int] = 0 + UPDATE: ClassVar[int] = 1 + __msgtype__: ClassVar[str] = 'visualization_msgs/msg/InteractiveMarkerUpdate' @dataclass @@ -1270,6 +1559,7 @@ class visualization_msgs__msg__InteractiveMarker: scale: float menu_entries: list[visualization_msgs__msg__MenuEntry] controls: list[visualization_msgs__msg__InteractiveMarkerControl] + __msgtype__: ClassVar[str] = 'visualization_msgs/msg/InteractiveMarker' @dataclass @@ -1285,6 +1575,13 @@ class visualization_msgs__msg__InteractiveMarkerFeedback: menu_entry_id: int mouse_point: geometry_msgs__msg__Point mouse_point_valid: bool + KEEP_ALIVE: ClassVar[int] = 0 + POSE_UPDATE: ClassVar[int] = 1 + MENU_SELECT: ClassVar[int] = 2 + BUTTON_CLICK: ClassVar[int] = 3 + MOUSE_DOWN: ClassVar[int] = 4 + MOUSE_UP: ClassVar[int] = 5 + __msgtype__: ClassVar[str] = 'visualization_msgs/msg/InteractiveMarkerFeedback' @dataclass @@ -1304,6 +1601,14 @@ class visualization_msgs__msg__ImageMarker: lifetime: builtin_interfaces__msg__Duration points: list[geometry_msgs__msg__Point] outline_colors: list[std_msgs__msg__ColorRGBA] + CIRCLE: ClassVar[int] = 0 + LINE_STRIP: ClassVar[int] = 1 + LINE_LIST: ClassVar[int] = 2 + POLYGON: ClassVar[int] = 3 + POINTS: ClassVar[int] = 4 + ADD: ClassVar[int] = 0 + REMOVE: ClassVar[int] = 1 + __msgtype__: ClassVar[str] = 'visualization_msgs/msg/ImageMarker' @dataclass @@ -1318,6 +1623,20 @@ class visualization_msgs__msg__InteractiveMarkerControl: markers: list[visualization_msgs__msg__Marker] independent_marker_orientation: bool description: str + INHERIT: ClassVar[int] = 0 + FIXED: ClassVar[int] = 1 + VIEW_FACING: ClassVar[int] = 2 + NONE: ClassVar[int] = 0 + MENU: ClassVar[int] = 1 + BUTTON: ClassVar[int] = 2 + MOVE_AXIS: ClassVar[int] = 3 + MOVE_PLANE: ClassVar[int] = 4 + ROTATE_AXIS: ClassVar[int] = 5 + MOVE_ROTATE: ClassVar[int] = 6 + MOVE_3D: ClassVar[int] = 7 + ROTATE_3D: ClassVar[int] = 8 + MOVE_ROTATE_3D: ClassVar[int] = 9 + __msgtype__: ClassVar[str] = 'visualization_msgs/msg/InteractiveMarkerControl' @dataclass @@ -1327,753 +1646,1073 @@ class visualization_msgs__msg__InteractiveMarkerPose: header: std_msgs__msg__Header pose: geometry_msgs__msg__Pose name: str + __msgtype__: ClassVar[str] = 'visualization_msgs/msg/InteractiveMarkerPose' -FIELDDEFS = { - 'builtin_interfaces/msg/Time': [ - ('sec', [1, 'int32']), - ('nanosec', [1, 'uint32']), - ], - 'builtin_interfaces/msg/Duration': [ - ('sec', [1, 'int32']), - ('nanosec', [1, 'uint32']), - ], - 'diagnostic_msgs/msg/DiagnosticStatus': [ - ('level', [1, 'uint8']), - ('name', [1, 'string']), - ('message', [1, 'string']), - ('hardware_id', [1, 'string']), - ('values', [4, [2, 'diagnostic_msgs/msg/KeyValue']]), - ], - 'diagnostic_msgs/msg/DiagnosticArray': [ - ('header', [2, 'std_msgs/msg/Header']), - ('status', [4, [2, 'diagnostic_msgs/msg/DiagnosticStatus']]), - ], - 'diagnostic_msgs/msg/KeyValue': [ - ('key', [1, 'string']), - ('value', [1, 'string']), - ], - 'geometry_msgs/msg/AccelWithCovariance': [ - ('accel', [2, 'geometry_msgs/msg/Accel']), - ('covariance', [3, 36, [1, 'float64']]), - ], - 'geometry_msgs/msg/Point32': [ - ('x', [1, 'float32']), - ('y', [1, 'float32']), - ('z', [1, 'float32']), - ], - 'geometry_msgs/msg/Vector3': [ - ('x', [1, 'float64']), - ('y', [1, 'float64']), - ('z', [1, 'float64']), - ], - 'geometry_msgs/msg/Inertia': [ - ('m', [1, 'float64']), - ('com', [2, 'geometry_msgs/msg/Vector3']), - ('ixx', [1, 'float64']), - ('ixy', [1, 'float64']), - ('ixz', [1, 'float64']), - ('iyy', [1, 'float64']), - ('iyz', [1, 'float64']), - ('izz', [1, 'float64']), - ], - 'geometry_msgs/msg/PoseWithCovarianceStamped': [ - ('header', [2, 'std_msgs/msg/Header']), - ('pose', [2, 'geometry_msgs/msg/PoseWithCovariance']), - ], - 'geometry_msgs/msg/Twist': [ - ('linear', [2, 'geometry_msgs/msg/Vector3']), - ('angular', [2, 'geometry_msgs/msg/Vector3']), - ], - 'geometry_msgs/msg/Pose': [ - ('position', [2, 'geometry_msgs/msg/Point']), - ('orientation', [2, 'geometry_msgs/msg/Quaternion']), - ], - 'geometry_msgs/msg/Point': [ - ('x', [1, 'float64']), - ('y', [1, 'float64']), - ('z', [1, 'float64']), - ], - 'geometry_msgs/msg/Vector3Stamped': [ - ('header', [2, 'std_msgs/msg/Header']), - ('vector', [2, 'geometry_msgs/msg/Vector3']), - ], - 'geometry_msgs/msg/Transform': [ - ('translation', [2, 'geometry_msgs/msg/Vector3']), - ('rotation', [2, 'geometry_msgs/msg/Quaternion']), - ], - 'geometry_msgs/msg/PolygonStamped': [ - ('header', [2, 'std_msgs/msg/Header']), - ('polygon', [2, 'geometry_msgs/msg/Polygon']), - ], - 'geometry_msgs/msg/Quaternion': [ - ('x', [1, 'float64']), - ('y', [1, 'float64']), - ('z', [1, 'float64']), - ('w', [1, 'float64']), - ], - 'geometry_msgs/msg/Pose2D': [ - ('x', [1, 'float64']), - ('y', [1, 'float64']), - ('theta', [1, 'float64']), - ], - 'geometry_msgs/msg/InertiaStamped': [ - ('header', [2, 'std_msgs/msg/Header']), - ('inertia', [2, 'geometry_msgs/msg/Inertia']), - ], - 'geometry_msgs/msg/TwistStamped': [ - ('header', [2, 'std_msgs/msg/Header']), - ('twist', [2, 'geometry_msgs/msg/Twist']), - ], - 'geometry_msgs/msg/PoseStamped': [ - ('header', [2, 'std_msgs/msg/Header']), - ('pose', [2, 'geometry_msgs/msg/Pose']), - ], - 'geometry_msgs/msg/PointStamped': [ - ('header', [2, 'std_msgs/msg/Header']), - ('point', [2, 'geometry_msgs/msg/Point']), - ], - 'geometry_msgs/msg/Polygon': [ - ('points', [4, [2, 'geometry_msgs/msg/Point32']]), - ], - 'geometry_msgs/msg/PoseArray': [ - ('header', [2, 'std_msgs/msg/Header']), - ('poses', [4, [2, 'geometry_msgs/msg/Pose']]), - ], - 'geometry_msgs/msg/AccelStamped': [ - ('header', [2, 'std_msgs/msg/Header']), - ('accel', [2, 'geometry_msgs/msg/Accel']), - ], - 'geometry_msgs/msg/TwistWithCovarianceStamped': [ - ('header', [2, 'std_msgs/msg/Header']), - ('twist', [2, 'geometry_msgs/msg/TwistWithCovariance']), - ], - 'geometry_msgs/msg/QuaternionStamped': [ - ('header', [2, 'std_msgs/msg/Header']), - ('quaternion', [2, 'geometry_msgs/msg/Quaternion']), - ], - 'geometry_msgs/msg/WrenchStamped': [ - ('header', [2, 'std_msgs/msg/Header']), - ('wrench', [2, 'geometry_msgs/msg/Wrench']), - ], - 'geometry_msgs/msg/AccelWithCovarianceStamped': [ - ('header', [2, 'std_msgs/msg/Header']), - ('accel', [2, 'geometry_msgs/msg/AccelWithCovariance']), - ], - 'geometry_msgs/msg/PoseWithCovariance': [ - ('pose', [2, 'geometry_msgs/msg/Pose']), - ('covariance', [3, 36, [1, 'float64']]), - ], - 'geometry_msgs/msg/Wrench': [ - ('force', [2, 'geometry_msgs/msg/Vector3']), - ('torque', [2, 'geometry_msgs/msg/Vector3']), - ], - 'geometry_msgs/msg/TransformStamped': [ - ('header', [2, 'std_msgs/msg/Header']), - ('child_frame_id', [1, 'string']), - ('transform', [2, 'geometry_msgs/msg/Transform']), - ], - 'geometry_msgs/msg/Accel': [ - ('linear', [2, 'geometry_msgs/msg/Vector3']), - ('angular', [2, 'geometry_msgs/msg/Vector3']), - ], - 'geometry_msgs/msg/TwistWithCovariance': [ - ('twist', [2, 'geometry_msgs/msg/Twist']), - ('covariance', [3, 36, [1, 'float64']]), - ], - 'libstatistics_collector/msg/DummyMessage': [ - ('header', [2, 'std_msgs/msg/Header']), - ], - 'lifecycle_msgs/msg/TransitionDescription': [ - ('transition', [2, 'lifecycle_msgs/msg/Transition']), - ('start_state', [2, 'lifecycle_msgs/msg/State']), - ('goal_state', [2, 'lifecycle_msgs/msg/State']), - ], - 'lifecycle_msgs/msg/State': [ - ('id', [1, 'uint8']), - ('label', [1, 'string']), - ], - 'lifecycle_msgs/msg/TransitionEvent': [ - ('timestamp', [1, 'uint64']), - ('transition', [2, 'lifecycle_msgs/msg/Transition']), - ('start_state', [2, 'lifecycle_msgs/msg/State']), - ('goal_state', [2, 'lifecycle_msgs/msg/State']), - ], - 'lifecycle_msgs/msg/Transition': [ - ('id', [1, 'uint8']), - ('label', [1, 'string']), - ], - 'nav_msgs/msg/MapMetaData': [ - ('map_load_time', [2, 'builtin_interfaces/msg/Time']), - ('resolution', [1, 'float32']), - ('width', [1, 'uint32']), - ('height', [1, 'uint32']), - ('origin', [2, 'geometry_msgs/msg/Pose']), - ], - 'nav_msgs/msg/GridCells': [ - ('header', [2, 'std_msgs/msg/Header']), - ('cell_width', [1, 'float32']), - ('cell_height', [1, 'float32']), - ('cells', [4, [2, 'geometry_msgs/msg/Point']]), - ], - 'nav_msgs/msg/Odometry': [ - ('header', [2, 'std_msgs/msg/Header']), - ('child_frame_id', [1, 'string']), - ('pose', [2, 'geometry_msgs/msg/PoseWithCovariance']), - ('twist', [2, 'geometry_msgs/msg/TwistWithCovariance']), - ], - 'nav_msgs/msg/Path': [ - ('header', [2, 'std_msgs/msg/Header']), - ('poses', [4, [2, 'geometry_msgs/msg/PoseStamped']]), - ], - 'nav_msgs/msg/OccupancyGrid': [ - ('header', [2, 'std_msgs/msg/Header']), - ('info', [2, 'nav_msgs/msg/MapMetaData']), - ('data', [4, [1, 'int8']]), - ], - 'rcl_interfaces/msg/ListParametersResult': [ - ('names', [4, [1, 'string']]), - ('prefixes', [4, [1, 'string']]), - ], - 'rcl_interfaces/msg/ParameterType': [ - ('structure_needs_at_least_one_member', [1, 'uint8']), - ], - 'rcl_interfaces/msg/ParameterEventDescriptors': [ - ('new_parameters', [4, [2, 'rcl_interfaces/msg/ParameterDescriptor']]), - ('changed_parameters', [4, [2, 'rcl_interfaces/msg/ParameterDescriptor']]), - ('deleted_parameters', [4, [2, 'rcl_interfaces/msg/ParameterDescriptor']]), - ], - 'rcl_interfaces/msg/ParameterEvent': [ - ('stamp', [2, 'builtin_interfaces/msg/Time']), - ('node', [1, 'string']), - ('new_parameters', [4, [2, 'rcl_interfaces/msg/Parameter']]), - ('changed_parameters', [4, [2, 'rcl_interfaces/msg/Parameter']]), - ('deleted_parameters', [4, [2, 'rcl_interfaces/msg/Parameter']]), - ], - 'rcl_interfaces/msg/IntegerRange': [ - ('from_value', [1, 'int64']), - ('to_value', [1, 'int64']), - ('step', [1, 'uint64']), - ], - 'rcl_interfaces/msg/Parameter': [ - ('name', [1, 'string']), - ('value', [2, 'rcl_interfaces/msg/ParameterValue']), - ], - 'rcl_interfaces/msg/ParameterValue': [ - ('type', [1, 'uint8']), - ('bool_value', [1, 'bool']), - ('integer_value', [1, 'int64']), - ('double_value', [1, 'float64']), - ('string_value', [1, 'string']), - ('byte_array_value', [4, [1, 'uint8']]), - ('bool_array_value', [4, [1, 'bool']]), - ('integer_array_value', [4, [1, 'int64']]), - ('double_array_value', [4, [1, 'float64']]), - ('string_array_value', [4, [1, 'string']]), - ], - 'rcl_interfaces/msg/FloatingPointRange': [ - ('from_value', [1, 'float64']), - ('to_value', [1, 'float64']), - ('step', [1, 'float64']), - ], - 'rcl_interfaces/msg/SetParametersResult': [ - ('successful', [1, 'bool']), - ('reason', [1, 'string']), - ], - 'rcl_interfaces/msg/Log': [ - ('stamp', [2, 'builtin_interfaces/msg/Time']), - ('level', [1, 'uint8']), - ('name', [1, 'string']), - ('msg', [1, 'string']), - ('file', [1, 'string']), - ('function', [1, 'string']), - ('line', [1, 'uint32']), - ], - 'rcl_interfaces/msg/ParameterDescriptor': [ - ('name', [1, 'string']), - ('type', [1, 'uint8']), - ('description', [1, 'string']), - ('additional_constraints', [1, 'string']), - ('read_only', [1, 'bool']), - ('floating_point_range', [4, [2, 'rcl_interfaces/msg/FloatingPointRange']]), - ('integer_range', [4, [2, 'rcl_interfaces/msg/IntegerRange']]), - ], - 'rmw_dds_common/msg/Gid': [ - ('data', [3, 24, [1, 'uint8']]), - ], - 'rmw_dds_common/msg/NodeEntitiesInfo': [ - ('node_namespace', [1, 'string', [6, 256]]), - ('node_name', [1, 'string', [6, 256]]), - ('reader_gid_seq', [4, [2, 'rmw_dds_common/msg/Gid']]), - ('writer_gid_seq', [4, [2, 'rmw_dds_common/msg/Gid']]), - ], - 'rmw_dds_common/msg/ParticipantEntitiesInfo': [ - ('gid', [2, 'rmw_dds_common/msg/Gid']), - ('node_entities_info_seq', [4, [2, 'rmw_dds_common/msg/NodeEntitiesInfo']]), - ], - 'rosgraph_msgs/msg/Clock': [ - ('clock', [2, 'builtin_interfaces/msg/Time']), - ], - 'sensor_msgs/msg/Temperature': [ - ('header', [2, 'std_msgs/msg/Header']), - ('temperature', [1, 'float64']), - ('variance', [1, 'float64']), - ], - 'sensor_msgs/msg/Range': [ - ('header', [2, 'std_msgs/msg/Header']), - ('radiation_type', [1, 'uint8']), - ('field_of_view', [1, 'float32']), - ('min_range', [1, 'float32']), - ('max_range', [1, 'float32']), - ('range', [1, 'float32']), - ], - 'sensor_msgs/msg/RegionOfInterest': [ - ('x_offset', [1, 'uint32']), - ('y_offset', [1, 'uint32']), - ('height', [1, 'uint32']), - ('width', [1, 'uint32']), - ('do_rectify', [1, 'bool']), - ], - 'sensor_msgs/msg/JoyFeedbackArray': [ - ('array', [4, [2, 'sensor_msgs/msg/JoyFeedback']]), - ], - 'sensor_msgs/msg/TimeReference': [ - ('header', [2, 'std_msgs/msg/Header']), - ('time_ref', [2, 'builtin_interfaces/msg/Time']), - ('source', [1, 'string']), - ], - 'sensor_msgs/msg/CompressedImage': [ - ('header', [2, 'std_msgs/msg/Header']), - ('format', [1, 'string']), - ('data', [4, [1, 'uint8']]), - ], - 'sensor_msgs/msg/MultiEchoLaserScan': [ - ('header', [2, 'std_msgs/msg/Header']), - ('angle_min', [1, 'float32']), - ('angle_max', [1, 'float32']), - ('angle_increment', [1, 'float32']), - ('time_increment', [1, 'float32']), - ('scan_time', [1, 'float32']), - ('range_min', [1, 'float32']), - ('range_max', [1, 'float32']), - ('ranges', [4, [2, 'sensor_msgs/msg/LaserEcho']]), - ('intensities', [4, [2, 'sensor_msgs/msg/LaserEcho']]), - ], - 'sensor_msgs/msg/LaserEcho': [ - ('echoes', [4, [1, 'float32']]), - ], - 'sensor_msgs/msg/ChannelFloat32': [ - ('name', [1, 'string']), - ('values', [4, [1, 'float32']]), - ], - 'sensor_msgs/msg/CameraInfo': [ - ('header', [2, 'std_msgs/msg/Header']), - ('height', [1, 'uint32']), - ('width', [1, 'uint32']), - ('distortion_model', [1, 'string']), - ('d', [4, [1, 'float64']]), - ('k', [3, 9, [1, 'float64']]), - ('r', [3, 9, [1, 'float64']]), - ('p', [3, 12, [1, 'float64']]), - ('binning_x', [1, 'uint32']), - ('binning_y', [1, 'uint32']), - ('roi', [2, 'sensor_msgs/msg/RegionOfInterest']), - ], - 'sensor_msgs/msg/RelativeHumidity': [ - ('header', [2, 'std_msgs/msg/Header']), - ('relative_humidity', [1, 'float64']), - ('variance', [1, 'float64']), - ], - 'sensor_msgs/msg/FluidPressure': [ - ('header', [2, 'std_msgs/msg/Header']), - ('fluid_pressure', [1, 'float64']), - ('variance', [1, 'float64']), - ], - 'sensor_msgs/msg/LaserScan': [ - ('header', [2, 'std_msgs/msg/Header']), - ('angle_min', [1, 'float32']), - ('angle_max', [1, 'float32']), - ('angle_increment', [1, 'float32']), - ('time_increment', [1, 'float32']), - ('scan_time', [1, 'float32']), - ('range_min', [1, 'float32']), - ('range_max', [1, 'float32']), - ('ranges', [4, [1, 'float32']]), - ('intensities', [4, [1, 'float32']]), - ], - 'sensor_msgs/msg/BatteryState': [ - ('header', [2, 'std_msgs/msg/Header']), - ('voltage', [1, 'float32']), - ('temperature', [1, 'float32']), - ('current', [1, 'float32']), - ('charge', [1, 'float32']), - ('capacity', [1, 'float32']), - ('design_capacity', [1, 'float32']), - ('percentage', [1, 'float32']), - ('power_supply_status', [1, 'uint8']), - ('power_supply_health', [1, 'uint8']), - ('power_supply_technology', [1, 'uint8']), - ('present', [1, 'bool']), - ('cell_voltage', [4, [1, 'float32']]), - ('cell_temperature', [4, [1, 'float32']]), - ('location', [1, 'string']), - ('serial_number', [1, 'string']), - ], - 'sensor_msgs/msg/Image': [ - ('header', [2, 'std_msgs/msg/Header']), - ('height', [1, 'uint32']), - ('width', [1, 'uint32']), - ('encoding', [1, 'string']), - ('is_bigendian', [1, 'uint8']), - ('step', [1, 'uint32']), - ('data', [4, [1, 'uint8']]), - ], - 'sensor_msgs/msg/PointCloud': [ - ('header', [2, 'std_msgs/msg/Header']), - ('points', [4, [2, 'geometry_msgs/msg/Point32']]), - ('channels', [4, [2, 'sensor_msgs/msg/ChannelFloat32']]), - ], - 'sensor_msgs/msg/Imu': [ - ('header', [2, 'std_msgs/msg/Header']), - ('orientation', [2, 'geometry_msgs/msg/Quaternion']), - ('orientation_covariance', [3, 9, [1, 'float64']]), - ('angular_velocity', [2, 'geometry_msgs/msg/Vector3']), - ('angular_velocity_covariance', [3, 9, [1, 'float64']]), - ('linear_acceleration', [2, 'geometry_msgs/msg/Vector3']), - ('linear_acceleration_covariance', [3, 9, [1, 'float64']]), - ], - 'sensor_msgs/msg/NavSatStatus': [ - ('status', [1, 'int8']), - ('service', [1, 'uint16']), - ], - 'sensor_msgs/msg/Illuminance': [ - ('header', [2, 'std_msgs/msg/Header']), - ('illuminance', [1, 'float64']), - ('variance', [1, 'float64']), - ], - 'sensor_msgs/msg/Joy': [ - ('header', [2, 'std_msgs/msg/Header']), - ('axes', [4, [1, 'float32']]), - ('buttons', [4, [1, 'int32']]), - ], - 'sensor_msgs/msg/NavSatFix': [ - ('header', [2, 'std_msgs/msg/Header']), - ('status', [2, 'sensor_msgs/msg/NavSatStatus']), - ('latitude', [1, 'float64']), - ('longitude', [1, 'float64']), - ('altitude', [1, 'float64']), - ('position_covariance', [3, 9, [1, 'float64']]), - ('position_covariance_type', [1, 'uint8']), - ], - 'sensor_msgs/msg/MultiDOFJointState': [ - ('header', [2, 'std_msgs/msg/Header']), - ('joint_names', [4, [1, 'string']]), - ('transforms', [4, [2, 'geometry_msgs/msg/Transform']]), - ('twist', [4, [2, 'geometry_msgs/msg/Twist']]), - ('wrench', [4, [2, 'geometry_msgs/msg/Wrench']]), - ], - 'sensor_msgs/msg/MagneticField': [ - ('header', [2, 'std_msgs/msg/Header']), - ('magnetic_field', [2, 'geometry_msgs/msg/Vector3']), - ('magnetic_field_covariance', [3, 9, [1, 'float64']]), - ], - 'sensor_msgs/msg/JointState': [ - ('header', [2, 'std_msgs/msg/Header']), - ('name', [4, [1, 'string']]), - ('position', [4, [1, 'float64']]), - ('velocity', [4, [1, 'float64']]), - ('effort', [4, [1, 'float64']]), - ], - 'sensor_msgs/msg/PointField': [ - ('name', [1, 'string']), - ('offset', [1, 'uint32']), - ('datatype', [1, 'uint8']), - ('count', [1, 'uint32']), - ], - 'sensor_msgs/msg/PointCloud2': [ - ('header', [2, 'std_msgs/msg/Header']), - ('height', [1, 'uint32']), - ('width', [1, 'uint32']), - ('fields', [4, [2, 'sensor_msgs/msg/PointField']]), - ('is_bigendian', [1, 'bool']), - ('point_step', [1, 'uint32']), - ('row_step', [1, 'uint32']), - ('data', [4, [1, 'uint8']]), - ('is_dense', [1, 'bool']), - ], - 'sensor_msgs/msg/JoyFeedback': [ - ('type', [1, 'uint8']), - ('id', [1, 'uint8']), - ('intensity', [1, 'float32']), - ], - 'shape_msgs/msg/SolidPrimitive': [ - ('type', [1, 'uint8']), - ('dimensions', [4, [1, 'float64']]), - ], - 'shape_msgs/msg/Mesh': [ - ('triangles', [4, [2, 'shape_msgs/msg/MeshTriangle']]), - ('vertices', [4, [2, 'geometry_msgs/msg/Point']]), - ], - 'shape_msgs/msg/Plane': [ - ('coef', [3, 4, [1, 'float64']]), - ], - 'shape_msgs/msg/MeshTriangle': [ - ('vertex_indices', [3, 3, [1, 'uint32']]), - ], - 'statistics_msgs/msg/StatisticDataType': [ - ('structure_needs_at_least_one_member', [1, 'uint8']), - ], - 'statistics_msgs/msg/StatisticDataPoint': [ - ('data_type', [1, 'uint8']), - ('data', [1, 'float64']), - ], - 'statistics_msgs/msg/MetricsMessage': [ - ('measurement_source_name', [1, 'string']), - ('metrics_source', [1, 'string']), - ('unit', [1, 'string']), - ('window_start', [2, 'builtin_interfaces/msg/Time']), - ('window_stop', [2, 'builtin_interfaces/msg/Time']), - ('statistics', [4, [2, 'statistics_msgs/msg/StatisticDataPoint']]), - ], - 'std_msgs/msg/UInt8': [ - ('data', [1, 'uint8']), - ], - 'std_msgs/msg/Float32MultiArray': [ - ('layout', [2, 'std_msgs/msg/MultiArrayLayout']), - ('data', [4, [1, 'float32']]), - ], - 'std_msgs/msg/Int8': [ - ('data', [1, 'int8']), - ], - 'std_msgs/msg/Empty': [ - ('structure_needs_at_least_one_member', [1, 'uint8']), - ], - 'std_msgs/msg/String': [ - ('data', [1, 'string']), - ], - 'std_msgs/msg/MultiArrayDimension': [ - ('label', [1, 'string']), - ('size', [1, 'uint32']), - ('stride', [1, 'uint32']), - ], - 'std_msgs/msg/UInt64': [ - ('data', [1, 'uint64']), - ], - 'std_msgs/msg/UInt16': [ - ('data', [1, 'uint16']), - ], - 'std_msgs/msg/Float32': [ - ('data', [1, 'float32']), - ], - 'std_msgs/msg/Int64': [ - ('data', [1, 'int64']), - ], - 'std_msgs/msg/Int16MultiArray': [ - ('layout', [2, 'std_msgs/msg/MultiArrayLayout']), - ('data', [4, [1, 'int16']]), - ], - 'std_msgs/msg/Int16': [ - ('data', [1, 'int16']), - ], - 'std_msgs/msg/Float64MultiArray': [ - ('layout', [2, 'std_msgs/msg/MultiArrayLayout']), - ('data', [4, [1, 'float64']]), - ], - 'std_msgs/msg/MultiArrayLayout': [ - ('dim', [4, [2, 'std_msgs/msg/MultiArrayDimension']]), - ('data_offset', [1, 'uint32']), - ], - 'std_msgs/msg/UInt32MultiArray': [ - ('layout', [2, 'std_msgs/msg/MultiArrayLayout']), - ('data', [4, [1, 'uint32']]), - ], - 'std_msgs/msg/Header': [ - ('stamp', [2, 'builtin_interfaces/msg/Time']), - ('frame_id', [1, 'string']), - ], - 'std_msgs/msg/ByteMultiArray': [ - ('layout', [2, 'std_msgs/msg/MultiArrayLayout']), - ('data', [4, [1, 'uint8']]), - ], - 'std_msgs/msg/Int8MultiArray': [ - ('layout', [2, 'std_msgs/msg/MultiArrayLayout']), - ('data', [4, [1, 'int8']]), - ], - 'std_msgs/msg/Float64': [ - ('data', [1, 'float64']), - ], - 'std_msgs/msg/UInt8MultiArray': [ - ('layout', [2, 'std_msgs/msg/MultiArrayLayout']), - ('data', [4, [1, 'uint8']]), - ], - 'std_msgs/msg/Byte': [ - ('data', [1, 'uint8']), - ], - 'std_msgs/msg/Char': [ - ('data', [1, 'uint8']), - ], - 'std_msgs/msg/UInt64MultiArray': [ - ('layout', [2, 'std_msgs/msg/MultiArrayLayout']), - ('data', [4, [1, 'uint64']]), - ], - 'std_msgs/msg/Int32MultiArray': [ - ('layout', [2, 'std_msgs/msg/MultiArrayLayout']), - ('data', [4, [1, 'int32']]), - ], - 'std_msgs/msg/ColorRGBA': [ - ('r', [1, 'float32']), - ('g', [1, 'float32']), - ('b', [1, 'float32']), - ('a', [1, 'float32']), - ], - 'std_msgs/msg/Bool': [ - ('data', [1, 'bool']), - ], - 'std_msgs/msg/UInt32': [ - ('data', [1, 'uint32']), - ], - 'std_msgs/msg/Int64MultiArray': [ - ('layout', [2, 'std_msgs/msg/MultiArrayLayout']), - ('data', [4, [1, 'int64']]), - ], - 'std_msgs/msg/Int32': [ - ('data', [1, 'int32']), - ], - 'std_msgs/msg/UInt16MultiArray': [ - ('layout', [2, 'std_msgs/msg/MultiArrayLayout']), - ('data', [4, [1, 'uint16']]), - ], - 'stereo_msgs/msg/DisparityImage': [ - ('header', [2, 'std_msgs/msg/Header']), - ('image', [2, 'sensor_msgs/msg/Image']), - ('f', [1, 'float32']), - ('t', [1, 'float32']), - ('valid_window', [2, 'sensor_msgs/msg/RegionOfInterest']), - ('min_disparity', [1, 'float32']), - ('max_disparity', [1, 'float32']), - ('delta_d', [1, 'float32']), - ], - 'tf2_msgs/msg/TF2Error': [ - ('error', [1, 'uint8']), - ('error_string', [1, 'string']), - ], - 'tf2_msgs/msg/TFMessage': [ - ('transforms', [4, [2, 'geometry_msgs/msg/TransformStamped']]), - ], - 'trajectory_msgs/msg/MultiDOFJointTrajectory': [ - ('header', [2, 'std_msgs/msg/Header']), - ('joint_names', [4, [1, 'string']]), - ('points', [4, [2, 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint']]), - ], - 'trajectory_msgs/msg/JointTrajectory': [ - ('header', [2, 'std_msgs/msg/Header']), - ('joint_names', [4, [1, 'string']]), - ('points', [4, [2, 'trajectory_msgs/msg/JointTrajectoryPoint']]), - ], - 'trajectory_msgs/msg/JointTrajectoryPoint': [ - ('positions', [4, [1, 'float64']]), - ('velocities', [4, [1, 'float64']]), - ('accelerations', [4, [1, 'float64']]), - ('effort', [4, [1, 'float64']]), - ('time_from_start', [2, 'builtin_interfaces/msg/Duration']), - ], - 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint': [ - ('transforms', [4, [2, 'geometry_msgs/msg/Transform']]), - ('velocities', [4, [2, 'geometry_msgs/msg/Twist']]), - ('accelerations', [4, [2, 'geometry_msgs/msg/Twist']]), - ('time_from_start', [2, 'builtin_interfaces/msg/Duration']), - ], - 'unique_identifier_msgs/msg/UUID': [ - ('uuid', [3, 16, [1, 'uint8']]), - ], - 'visualization_msgs/msg/Marker': [ - ('header', [2, 'std_msgs/msg/Header']), - ('ns', [1, 'string']), - ('id', [1, 'int32']), - ('type', [1, 'int32']), - ('action', [1, 'int32']), - ('pose', [2, 'geometry_msgs/msg/Pose']), - ('scale', [2, 'geometry_msgs/msg/Vector3']), - ('color', [2, 'std_msgs/msg/ColorRGBA']), - ('lifetime', [2, 'builtin_interfaces/msg/Duration']), - ('frame_locked', [1, 'bool']), - ('points', [4, [2, 'geometry_msgs/msg/Point']]), - ('colors', [4, [2, 'std_msgs/msg/ColorRGBA']]), - ('text', [1, 'string']), - ('mesh_resource', [1, 'string']), - ('mesh_use_embedded_materials', [1, 'bool']), - ], - 'visualization_msgs/msg/InteractiveMarkerInit': [ - ('server_id', [1, 'string']), - ('seq_num', [1, 'uint64']), - ('markers', [4, [2, 'visualization_msgs/msg/InteractiveMarker']]), - ], - 'visualization_msgs/msg/MenuEntry': [ - ('id', [1, 'uint32']), - ('parent_id', [1, 'uint32']), - ('title', [1, 'string']), - ('command', [1, 'string']), - ('command_type', [1, 'uint8']), - ], - 'visualization_msgs/msg/MarkerArray': [ - ('markers', [4, [2, 'visualization_msgs/msg/Marker']]), - ], - 'visualization_msgs/msg/InteractiveMarkerUpdate': [ - ('server_id', [1, 'string']), - ('seq_num', [1, 'uint64']), - ('type', [1, 'uint8']), - ('markers', [4, [2, 'visualization_msgs/msg/InteractiveMarker']]), - ('poses', [4, [2, 'visualization_msgs/msg/InteractiveMarkerPose']]), - ('erases', [4, [1, 'string']]), - ], - 'visualization_msgs/msg/InteractiveMarker': [ - ('header', [2, 'std_msgs/msg/Header']), - ('pose', [2, 'geometry_msgs/msg/Pose']), - ('name', [1, 'string']), - ('description', [1, 'string']), - ('scale', [1, 'float32']), - ('menu_entries', [4, [2, 'visualization_msgs/msg/MenuEntry']]), - ('controls', [4, [2, 'visualization_msgs/msg/InteractiveMarkerControl']]), - ], - 'visualization_msgs/msg/InteractiveMarkerFeedback': [ - ('header', [2, 'std_msgs/msg/Header']), - ('client_id', [1, 'string']), - ('marker_name', [1, 'string']), - ('control_name', [1, 'string']), - ('event_type', [1, 'uint8']), - ('pose', [2, 'geometry_msgs/msg/Pose']), - ('menu_entry_id', [1, 'uint32']), - ('mouse_point', [2, 'geometry_msgs/msg/Point']), - ('mouse_point_valid', [1, 'bool']), - ], - 'visualization_msgs/msg/ImageMarker': [ - ('header', [2, 'std_msgs/msg/Header']), - ('ns', [1, 'string']), - ('id', [1, 'int32']), - ('type', [1, 'int32']), - ('action', [1, 'int32']), - ('position', [2, 'geometry_msgs/msg/Point']), - ('scale', [1, 'float32']), - ('outline_color', [2, 'std_msgs/msg/ColorRGBA']), - ('filled', [1, 'uint8']), - ('fill_color', [2, 'std_msgs/msg/ColorRGBA']), - ('lifetime', [2, 'builtin_interfaces/msg/Duration']), - ('points', [4, [2, 'geometry_msgs/msg/Point']]), - ('outline_colors', [4, [2, 'std_msgs/msg/ColorRGBA']]), - ], - 'visualization_msgs/msg/InteractiveMarkerControl': [ - ('name', [1, 'string']), - ('orientation', [2, 'geometry_msgs/msg/Quaternion']), - ('orientation_mode', [1, 'uint8']), - ('interaction_mode', [1, 'uint8']), - ('always_visible', [1, 'bool']), - ('markers', [4, [2, 'visualization_msgs/msg/Marker']]), - ('independent_marker_orientation', [1, 'bool']), - ('description', [1, 'string']), - ], - 'visualization_msgs/msg/InteractiveMarkerPose': [ - ('header', [2, 'std_msgs/msg/Header']), - ('pose', [2, 'geometry_msgs/msg/Pose']), - ('name', [1, 'string']), - ], +FIELDDEFS: Typesdict = { + 'builtin_interfaces/msg/Time': ([ + ], [ + ('sec', (1, 'int32')), + ('nanosec', (1, 'uint32')), + ]), + 'builtin_interfaces/msg/Duration': ([ + ], [ + ('sec', (1, 'int32')), + ('nanosec', (1, 'uint32')), + ]), + 'diagnostic_msgs/msg/DiagnosticStatus': ([ + ('OK', 'uint8', 0), + ('WARN', 'uint8', 1), + ('ERROR', 'uint8', 2), + ('STALE', 'uint8', 3), + ], [ + ('level', (1, 'uint8')), + ('name', (1, 'string')), + ('message', (1, 'string')), + ('hardware_id', (1, 'string')), + ('values', (4, ((2, 'diagnostic_msgs/msg/KeyValue'), None))), + ]), + 'diagnostic_msgs/msg/DiagnosticArray': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('status', (4, ((2, 'diagnostic_msgs/msg/DiagnosticStatus'), None))), + ]), + 'diagnostic_msgs/msg/KeyValue': ([ + ], [ + ('key', (1, 'string')), + ('value', (1, 'string')), + ]), + 'geometry_msgs/msg/AccelWithCovariance': ([ + ], [ + ('accel', (2, 'geometry_msgs/msg/Accel')), + ('covariance', (3, ((1, 'float64'), 36))), + ]), + 'geometry_msgs/msg/Point32': ([ + ], [ + ('x', (1, 'float32')), + ('y', (1, 'float32')), + ('z', (1, 'float32')), + ]), + 'geometry_msgs/msg/Vector3': ([ + ], [ + ('x', (1, 'float64')), + ('y', (1, 'float64')), + ('z', (1, 'float64')), + ]), + 'geometry_msgs/msg/Inertia': ([ + ], [ + ('m', (1, 'float64')), + ('com', (2, 'geometry_msgs/msg/Vector3')), + ('ixx', (1, 'float64')), + ('ixy', (1, 'float64')), + ('ixz', (1, 'float64')), + ('iyy', (1, 'float64')), + ('iyz', (1, 'float64')), + ('izz', (1, 'float64')), + ]), + 'geometry_msgs/msg/PoseWithCovarianceStamped': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('pose', (2, 'geometry_msgs/msg/PoseWithCovariance')), + ]), + 'geometry_msgs/msg/Twist': ([ + ], [ + ('linear', (2, 'geometry_msgs/msg/Vector3')), + ('angular', (2, 'geometry_msgs/msg/Vector3')), + ]), + 'geometry_msgs/msg/Pose': ([ + ], [ + ('position', (2, 'geometry_msgs/msg/Point')), + ('orientation', (2, 'geometry_msgs/msg/Quaternion')), + ]), + 'geometry_msgs/msg/Point': ([ + ], [ + ('x', (1, 'float64')), + ('y', (1, 'float64')), + ('z', (1, 'float64')), + ]), + 'geometry_msgs/msg/Vector3Stamped': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('vector', (2, 'geometry_msgs/msg/Vector3')), + ]), + 'geometry_msgs/msg/Transform': ([ + ], [ + ('translation', (2, 'geometry_msgs/msg/Vector3')), + ('rotation', (2, 'geometry_msgs/msg/Quaternion')), + ]), + 'geometry_msgs/msg/PolygonStamped': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('polygon', (2, 'geometry_msgs/msg/Polygon')), + ]), + 'geometry_msgs/msg/Quaternion': ([ + ], [ + ('x', (1, 'float64')), + ('y', (1, 'float64')), + ('z', (1, 'float64')), + ('w', (1, 'float64')), + ]), + 'geometry_msgs/msg/Pose2D': ([ + ], [ + ('x', (1, 'float64')), + ('y', (1, 'float64')), + ('theta', (1, 'float64')), + ]), + 'geometry_msgs/msg/InertiaStamped': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('inertia', (2, 'geometry_msgs/msg/Inertia')), + ]), + 'geometry_msgs/msg/TwistStamped': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('twist', (2, 'geometry_msgs/msg/Twist')), + ]), + 'geometry_msgs/msg/PoseStamped': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('pose', (2, 'geometry_msgs/msg/Pose')), + ]), + 'geometry_msgs/msg/PointStamped': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('point', (2, 'geometry_msgs/msg/Point')), + ]), + 'geometry_msgs/msg/Polygon': ([ + ], [ + ('points', (4, ((2, 'geometry_msgs/msg/Point32'), None))), + ]), + 'geometry_msgs/msg/PoseArray': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('poses', (4, ((2, 'geometry_msgs/msg/Pose'), None))), + ]), + 'geometry_msgs/msg/AccelStamped': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('accel', (2, 'geometry_msgs/msg/Accel')), + ]), + 'geometry_msgs/msg/TwistWithCovarianceStamped': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('twist', (2, 'geometry_msgs/msg/TwistWithCovariance')), + ]), + 'geometry_msgs/msg/QuaternionStamped': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('quaternion', (2, 'geometry_msgs/msg/Quaternion')), + ]), + 'geometry_msgs/msg/WrenchStamped': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('wrench', (2, 'geometry_msgs/msg/Wrench')), + ]), + 'geometry_msgs/msg/AccelWithCovarianceStamped': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('accel', (2, 'geometry_msgs/msg/AccelWithCovariance')), + ]), + 'geometry_msgs/msg/PoseWithCovariance': ([ + ], [ + ('pose', (2, 'geometry_msgs/msg/Pose')), + ('covariance', (3, ((1, 'float64'), 36))), + ]), + 'geometry_msgs/msg/Wrench': ([ + ], [ + ('force', (2, 'geometry_msgs/msg/Vector3')), + ('torque', (2, 'geometry_msgs/msg/Vector3')), + ]), + 'geometry_msgs/msg/TransformStamped': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('child_frame_id', (1, 'string')), + ('transform', (2, 'geometry_msgs/msg/Transform')), + ]), + 'geometry_msgs/msg/Accel': ([ + ], [ + ('linear', (2, 'geometry_msgs/msg/Vector3')), + ('angular', (2, 'geometry_msgs/msg/Vector3')), + ]), + 'geometry_msgs/msg/TwistWithCovariance': ([ + ], [ + ('twist', (2, 'geometry_msgs/msg/Twist')), + ('covariance', (3, ((1, 'float64'), 36))), + ]), + 'libstatistics_collector/msg/DummyMessage': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ]), + 'lifecycle_msgs/msg/TransitionDescription': ([ + ], [ + ('transition', (2, 'lifecycle_msgs/msg/Transition')), + ('start_state', (2, 'lifecycle_msgs/msg/State')), + ('goal_state', (2, 'lifecycle_msgs/msg/State')), + ]), + 'lifecycle_msgs/msg/State': ([ + ('PRIMARY_STATE_UNKNOWN', 'uint8', 0), + ('PRIMARY_STATE_UNCONFIGURED', 'uint8', 1), + ('PRIMARY_STATE_INACTIVE', 'uint8', 2), + ('PRIMARY_STATE_ACTIVE', 'uint8', 3), + ('PRIMARY_STATE_FINALIZED', 'uint8', 4), + ('TRANSITION_STATE_CONFIGURING', 'uint8', 10), + ('TRANSITION_STATE_CLEANINGUP', 'uint8', 11), + ('TRANSITION_STATE_SHUTTINGDOWN', 'uint8', 12), + ('TRANSITION_STATE_ACTIVATING', 'uint8', 13), + ('TRANSITION_STATE_DEACTIVATING', 'uint8', 14), + ('TRANSITION_STATE_ERRORPROCESSING', 'uint8', 15), + ], [ + ('id', (1, 'uint8')), + ('label', (1, 'string')), + ]), + 'lifecycle_msgs/msg/TransitionEvent': ([ + ], [ + ('timestamp', (1, 'uint64')), + ('transition', (2, 'lifecycle_msgs/msg/Transition')), + ('start_state', (2, 'lifecycle_msgs/msg/State')), + ('goal_state', (2, 'lifecycle_msgs/msg/State')), + ]), + 'lifecycle_msgs/msg/Transition': ([ + ('TRANSITION_CREATE', 'uint8', 0), + ('TRANSITION_CONFIGURE', 'uint8', 1), + ('TRANSITION_CLEANUP', 'uint8', 2), + ('TRANSITION_ACTIVATE', 'uint8', 3), + ('TRANSITION_DEACTIVATE', 'uint8', 4), + ('TRANSITION_UNCONFIGURED_SHUTDOWN', 'uint8', 5), + ('TRANSITION_INACTIVE_SHUTDOWN', 'uint8', 6), + ('TRANSITION_ACTIVE_SHUTDOWN', 'uint8', 7), + ('TRANSITION_DESTROY', 'uint8', 8), + ('TRANSITION_ON_CONFIGURE_SUCCESS', 'uint8', 10), + ('TRANSITION_ON_CONFIGURE_FAILURE', 'uint8', 11), + ('TRANSITION_ON_CONFIGURE_ERROR', 'uint8', 12), + ('TRANSITION_ON_CLEANUP_SUCCESS', 'uint8', 20), + ('TRANSITION_ON_CLEANUP_FAILURE', 'uint8', 21), + ('TRANSITION_ON_CLEANUP_ERROR', 'uint8', 22), + ('TRANSITION_ON_ACTIVATE_SUCCESS', 'uint8', 30), + ('TRANSITION_ON_ACTIVATE_FAILURE', 'uint8', 31), + ('TRANSITION_ON_ACTIVATE_ERROR', 'uint8', 32), + ('TRANSITION_ON_DEACTIVATE_SUCCESS', 'uint8', 40), + ('TRANSITION_ON_DEACTIVATE_FAILURE', 'uint8', 41), + ('TRANSITION_ON_DEACTIVATE_ERROR', 'uint8', 42), + ('TRANSITION_ON_SHUTDOWN_SUCCESS', 'uint8', 50), + ('TRANSITION_ON_SHUTDOWN_FAILURE', 'uint8', 51), + ('TRANSITION_ON_SHUTDOWN_ERROR', 'uint8', 52), + ('TRANSITION_ON_ERROR_SUCCESS', 'uint8', 60), + ('TRANSITION_ON_ERROR_FAILURE', 'uint8', 61), + ('TRANSITION_ON_ERROR_ERROR', 'uint8', 62), + ('TRANSITION_CALLBACK_SUCCESS', 'uint8', 97), + ('TRANSITION_CALLBACK_FAILURE', 'uint8', 98), + ('TRANSITION_CALLBACK_ERROR', 'uint8', 99), + ], [ + ('id', (1, 'uint8')), + ('label', (1, 'string')), + ]), + 'nav_msgs/msg/MapMetaData': ([ + ], [ + ('map_load_time', (2, 'builtin_interfaces/msg/Time')), + ('resolution', (1, 'float32')), + ('width', (1, 'uint32')), + ('height', (1, 'uint32')), + ('origin', (2, 'geometry_msgs/msg/Pose')), + ]), + 'nav_msgs/msg/GridCells': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('cell_width', (1, 'float32')), + ('cell_height', (1, 'float32')), + ('cells', (4, ((2, 'geometry_msgs/msg/Point'), None))), + ]), + 'nav_msgs/msg/Odometry': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('child_frame_id', (1, 'string')), + ('pose', (2, 'geometry_msgs/msg/PoseWithCovariance')), + ('twist', (2, 'geometry_msgs/msg/TwistWithCovariance')), + ]), + 'nav_msgs/msg/Path': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('poses', (4, ((2, 'geometry_msgs/msg/PoseStamped'), None))), + ]), + 'nav_msgs/msg/OccupancyGrid': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('info', (2, 'nav_msgs/msg/MapMetaData')), + ('data', (4, ((1, 'int8'), None))), + ]), + 'rcl_interfaces/msg/ListParametersResult': ([ + ], [ + ('names', (4, ((1, 'string'), None))), + ('prefixes', (4, ((1, 'string'), None))), + ]), + 'rcl_interfaces/msg/ParameterType': ([ + ('PARAMETER_NOT_SET', 'uint8', 0), + ('PARAMETER_BOOL', 'uint8', 1), + ('PARAMETER_INTEGER', 'uint8', 2), + ('PARAMETER_DOUBLE', 'uint8', 3), + ('PARAMETER_STRING', 'uint8', 4), + ('PARAMETER_BYTE_ARRAY', 'uint8', 5), + ('PARAMETER_BOOL_ARRAY', 'uint8', 6), + ('PARAMETER_INTEGER_ARRAY', 'uint8', 7), + ('PARAMETER_DOUBLE_ARRAY', 'uint8', 8), + ('PARAMETER_STRING_ARRAY', 'uint8', 9), + ], [ + ('structure_needs_at_least_one_member', (1, 'uint8')), + ]), + 'rcl_interfaces/msg/ParameterEventDescriptors': ([ + ], [ + ('new_parameters', (4, ((2, 'rcl_interfaces/msg/ParameterDescriptor'), None))), + ('changed_parameters', (4, ((2, 'rcl_interfaces/msg/ParameterDescriptor'), None))), + ('deleted_parameters', (4, ((2, 'rcl_interfaces/msg/ParameterDescriptor'), None))), + ]), + 'rcl_interfaces/msg/ParameterEvent': ([ + ], [ + ('stamp', (2, 'builtin_interfaces/msg/Time')), + ('node', (1, 'string')), + ('new_parameters', (4, ((2, 'rcl_interfaces/msg/Parameter'), None))), + ('changed_parameters', (4, ((2, 'rcl_interfaces/msg/Parameter'), None))), + ('deleted_parameters', (4, ((2, 'rcl_interfaces/msg/Parameter'), None))), + ]), + 'rcl_interfaces/msg/IntegerRange': ([ + ], [ + ('from_value', (1, 'int64')), + ('to_value', (1, 'int64')), + ('step', (1, 'uint64')), + ]), + 'rcl_interfaces/msg/Parameter': ([ + ], [ + ('name', (1, 'string')), + ('value', (2, 'rcl_interfaces/msg/ParameterValue')), + ]), + 'rcl_interfaces/msg/ParameterValue': ([ + ], [ + ('type', (1, 'uint8')), + ('bool_value', (1, 'bool')), + ('integer_value', (1, 'int64')), + ('double_value', (1, 'float64')), + ('string_value', (1, 'string')), + ('byte_array_value', (4, ((1, 'uint8'), None))), + ('bool_array_value', (4, ((1, 'bool'), None))), + ('integer_array_value', (4, ((1, 'int64'), None))), + ('double_array_value', (4, ((1, 'float64'), None))), + ('string_array_value', (4, ((1, 'string'), None))), + ]), + 'rcl_interfaces/msg/FloatingPointRange': ([ + ], [ + ('from_value', (1, 'float64')), + ('to_value', (1, 'float64')), + ('step', (1, 'float64')), + ]), + 'rcl_interfaces/msg/SetParametersResult': ([ + ], [ + ('successful', (1, 'bool')), + ('reason', (1, 'string')), + ]), + 'rcl_interfaces/msg/Log': ([ + ('DEBUG', 'uint8', 10), + ('INFO', 'uint8', 20), + ('WARN', 'uint8', 30), + ('ERROR', 'uint8', 40), + ('FATAL', 'uint8', 50), + ], [ + ('stamp', (2, 'builtin_interfaces/msg/Time')), + ('level', (1, 'uint8')), + ('name', (1, 'string')), + ('msg', (1, 'string')), + ('file', (1, 'string')), + ('function', (1, 'string')), + ('line', (1, 'uint32')), + ]), + 'rcl_interfaces/msg/ParameterDescriptor': ([ + ], [ + ('name', (1, 'string')), + ('type', (1, 'uint8')), + ('description', (1, 'string')), + ('additional_constraints', (1, 'string')), + ('read_only', (1, 'bool')), + ('floating_point_range', (4, ((2, 'rcl_interfaces/msg/FloatingPointRange'), None))), + ('integer_range', (4, ((2, 'rcl_interfaces/msg/IntegerRange'), None))), + ]), + 'rmw_dds_common/msg/Gid': ([ + ], [ + ('data', (3, ((1, 'uint8'), 24))), + ]), + 'rmw_dds_common/msg/NodeEntitiesInfo': ([ + ], [ + ('node_namespace', (1, 'string')), + ('node_name', (1, 'string')), + ('reader_gid_seq', (4, ((2, 'rmw_dds_common/msg/Gid'), None))), + ('writer_gid_seq', (4, ((2, 'rmw_dds_common/msg/Gid'), None))), + ]), + 'rmw_dds_common/msg/ParticipantEntitiesInfo': ([ + ], [ + ('gid', (2, 'rmw_dds_common/msg/Gid')), + ('node_entities_info_seq', (4, ((2, 'rmw_dds_common/msg/NodeEntitiesInfo'), None))), + ]), + 'rosgraph_msgs/msg/Clock': ([ + ], [ + ('clock', (2, 'builtin_interfaces/msg/Time')), + ]), + 'sensor_msgs/msg/Temperature': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('temperature', (1, 'float64')), + ('variance', (1, 'float64')), + ]), + 'sensor_msgs/msg/Range': ([ + ('ULTRASOUND', 'uint8', 0), + ('INFRARED', 'uint8', 1), + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('radiation_type', (1, 'uint8')), + ('field_of_view', (1, 'float32')), + ('min_range', (1, 'float32')), + ('max_range', (1, 'float32')), + ('range', (1, 'float32')), + ]), + 'sensor_msgs/msg/RegionOfInterest': ([ + ], [ + ('x_offset', (1, 'uint32')), + ('y_offset', (1, 'uint32')), + ('height', (1, 'uint32')), + ('width', (1, 'uint32')), + ('do_rectify', (1, 'bool')), + ]), + 'sensor_msgs/msg/JoyFeedbackArray': ([ + ], [ + ('array', (4, ((2, 'sensor_msgs/msg/JoyFeedback'), None))), + ]), + 'sensor_msgs/msg/TimeReference': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('time_ref', (2, 'builtin_interfaces/msg/Time')), + ('source', (1, 'string')), + ]), + 'sensor_msgs/msg/CompressedImage': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('format', (1, 'string')), + ('data', (4, ((1, 'uint8'), None))), + ]), + 'sensor_msgs/msg/MultiEchoLaserScan': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('angle_min', (1, 'float32')), + ('angle_max', (1, 'float32')), + ('angle_increment', (1, 'float32')), + ('time_increment', (1, 'float32')), + ('scan_time', (1, 'float32')), + ('range_min', (1, 'float32')), + ('range_max', (1, 'float32')), + ('ranges', (4, ((2, 'sensor_msgs/msg/LaserEcho'), None))), + ('intensities', (4, ((2, 'sensor_msgs/msg/LaserEcho'), None))), + ]), + 'sensor_msgs/msg/LaserEcho': ([ + ], [ + ('echoes', (4, ((1, 'float32'), None))), + ]), + 'sensor_msgs/msg/ChannelFloat32': ([ + ], [ + ('name', (1, 'string')), + ('values', (4, ((1, 'float32'), None))), + ]), + 'sensor_msgs/msg/CameraInfo': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('height', (1, 'uint32')), + ('width', (1, 'uint32')), + ('distortion_model', (1, 'string')), + ('d', (4, ((1, 'float64'), None))), + ('k', (3, ((1, 'float64'), 9))), + ('r', (3, ((1, 'float64'), 9))), + ('p', (3, ((1, 'float64'), 12))), + ('binning_x', (1, 'uint32')), + ('binning_y', (1, 'uint32')), + ('roi', (2, 'sensor_msgs/msg/RegionOfInterest')), + ]), + 'sensor_msgs/msg/RelativeHumidity': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('relative_humidity', (1, 'float64')), + ('variance', (1, 'float64')), + ]), + 'sensor_msgs/msg/FluidPressure': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('fluid_pressure', (1, 'float64')), + ('variance', (1, 'float64')), + ]), + 'sensor_msgs/msg/LaserScan': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('angle_min', (1, 'float32')), + ('angle_max', (1, 'float32')), + ('angle_increment', (1, 'float32')), + ('time_increment', (1, 'float32')), + ('scan_time', (1, 'float32')), + ('range_min', (1, 'float32')), + ('range_max', (1, 'float32')), + ('ranges', (4, ((1, 'float32'), None))), + ('intensities', (4, ((1, 'float32'), None))), + ]), + 'sensor_msgs/msg/BatteryState': ([ + ('POWER_SUPPLY_STATUS_UNKNOWN', 'uint8', 0), + ('POWER_SUPPLY_STATUS_CHARGING', 'uint8', 1), + ('POWER_SUPPLY_STATUS_DISCHARGING', 'uint8', 2), + ('POWER_SUPPLY_STATUS_NOT_CHARGING', 'uint8', 3), + ('POWER_SUPPLY_STATUS_FULL', 'uint8', 4), + ('POWER_SUPPLY_HEALTH_UNKNOWN', 'uint8', 0), + ('POWER_SUPPLY_HEALTH_GOOD', 'uint8', 1), + ('POWER_SUPPLY_HEALTH_OVERHEAT', 'uint8', 2), + ('POWER_SUPPLY_HEALTH_DEAD', 'uint8', 3), + ('POWER_SUPPLY_HEALTH_OVERVOLTAGE', 'uint8', 4), + ('POWER_SUPPLY_HEALTH_UNSPEC_FAILURE', 'uint8', 5), + ('POWER_SUPPLY_HEALTH_COLD', 'uint8', 6), + ('POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE', 'uint8', 7), + ('POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE', 'uint8', 8), + ('POWER_SUPPLY_TECHNOLOGY_UNKNOWN', 'uint8', 0), + ('POWER_SUPPLY_TECHNOLOGY_NIMH', 'uint8', 1), + ('POWER_SUPPLY_TECHNOLOGY_LION', 'uint8', 2), + ('POWER_SUPPLY_TECHNOLOGY_LIPO', 'uint8', 3), + ('POWER_SUPPLY_TECHNOLOGY_LIFE', 'uint8', 4), + ('POWER_SUPPLY_TECHNOLOGY_NICD', 'uint8', 5), + ('POWER_SUPPLY_TECHNOLOGY_LIMN', 'uint8', 6), + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('voltage', (1, 'float32')), + ('temperature', (1, 'float32')), + ('current', (1, 'float32')), + ('charge', (1, 'float32')), + ('capacity', (1, 'float32')), + ('design_capacity', (1, 'float32')), + ('percentage', (1, 'float32')), + ('power_supply_status', (1, 'uint8')), + ('power_supply_health', (1, 'uint8')), + ('power_supply_technology', (1, 'uint8')), + ('present', (1, 'bool')), + ('cell_voltage', (4, ((1, 'float32'), None))), + ('cell_temperature', (4, ((1, 'float32'), None))), + ('location', (1, 'string')), + ('serial_number', (1, 'string')), + ]), + 'sensor_msgs/msg/Image': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('height', (1, 'uint32')), + ('width', (1, 'uint32')), + ('encoding', (1, 'string')), + ('is_bigendian', (1, 'uint8')), + ('step', (1, 'uint32')), + ('data', (4, ((1, 'uint8'), None))), + ]), + 'sensor_msgs/msg/PointCloud': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('points', (4, ((2, 'geometry_msgs/msg/Point32'), None))), + ('channels', (4, ((2, 'sensor_msgs/msg/ChannelFloat32'), None))), + ]), + 'sensor_msgs/msg/Imu': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('orientation', (2, 'geometry_msgs/msg/Quaternion')), + ('orientation_covariance', (3, ((1, 'float64'), 9))), + ('angular_velocity', (2, 'geometry_msgs/msg/Vector3')), + ('angular_velocity_covariance', (3, ((1, 'float64'), 9))), + ('linear_acceleration', (2, 'geometry_msgs/msg/Vector3')), + ('linear_acceleration_covariance', (3, ((1, 'float64'), 9))), + ]), + 'sensor_msgs/msg/NavSatStatus': ([ + ('STATUS_NO_FIX', 'int8', -1), + ('STATUS_FIX', 'int8', 0), + ('STATUS_SBAS_FIX', 'int8', 1), + ('STATUS_GBAS_FIX', 'int8', 2), + ('SERVICE_GPS', 'uint16', 1), + ('SERVICE_GLONASS', 'uint16', 2), + ('SERVICE_COMPASS', 'uint16', 4), + ('SERVICE_GALILEO', 'uint16', 8), + ], [ + ('status', (1, 'int8')), + ('service', (1, 'uint16')), + ]), + 'sensor_msgs/msg/Illuminance': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('illuminance', (1, 'float64')), + ('variance', (1, 'float64')), + ]), + 'sensor_msgs/msg/Joy': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('axes', (4, ((1, 'float32'), None))), + ('buttons', (4, ((1, 'int32'), None))), + ]), + 'sensor_msgs/msg/NavSatFix': ([ + ('COVARIANCE_TYPE_UNKNOWN', 'uint8', 0), + ('COVARIANCE_TYPE_APPROXIMATED', 'uint8', 1), + ('COVARIANCE_TYPE_DIAGONAL_KNOWN', 'uint8', 2), + ('COVARIANCE_TYPE_KNOWN', 'uint8', 3), + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('status', (2, 'sensor_msgs/msg/NavSatStatus')), + ('latitude', (1, 'float64')), + ('longitude', (1, 'float64')), + ('altitude', (1, 'float64')), + ('position_covariance', (3, ((1, 'float64'), 9))), + ('position_covariance_type', (1, 'uint8')), + ]), + 'sensor_msgs/msg/MultiDOFJointState': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('joint_names', (4, ((1, 'string'), None))), + ('transforms', (4, ((2, 'geometry_msgs/msg/Transform'), None))), + ('twist', (4, ((2, 'geometry_msgs/msg/Twist'), None))), + ('wrench', (4, ((2, 'geometry_msgs/msg/Wrench'), None))), + ]), + 'sensor_msgs/msg/MagneticField': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('magnetic_field', (2, 'geometry_msgs/msg/Vector3')), + ('magnetic_field_covariance', (3, ((1, 'float64'), 9))), + ]), + 'sensor_msgs/msg/JointState': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('name', (4, ((1, 'string'), None))), + ('position', (4, ((1, 'float64'), None))), + ('velocity', (4, ((1, 'float64'), None))), + ('effort', (4, ((1, 'float64'), None))), + ]), + 'sensor_msgs/msg/PointField': ([ + ('INT8', 'uint8', 1), + ('UINT8', 'uint8', 2), + ('INT16', 'uint8', 3), + ('UINT16', 'uint8', 4), + ('INT32', 'uint8', 5), + ('UINT32', 'uint8', 6), + ('FLOAT32', 'uint8', 7), + ('FLOAT64', 'uint8', 8), + ], [ + ('name', (1, 'string')), + ('offset', (1, 'uint32')), + ('datatype', (1, 'uint8')), + ('count', (1, 'uint32')), + ]), + 'sensor_msgs/msg/PointCloud2': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('height', (1, 'uint32')), + ('width', (1, 'uint32')), + ('fields', (4, ((2, 'sensor_msgs/msg/PointField'), None))), + ('is_bigendian', (1, 'bool')), + ('point_step', (1, 'uint32')), + ('row_step', (1, 'uint32')), + ('data', (4, ((1, 'uint8'), None))), + ('is_dense', (1, 'bool')), + ]), + 'sensor_msgs/msg/JoyFeedback': ([ + ('TYPE_LED', 'uint8', 0), + ('TYPE_RUMBLE', 'uint8', 1), + ('TYPE_BUZZER', 'uint8', 2), + ], [ + ('type', (1, 'uint8')), + ('id', (1, 'uint8')), + ('intensity', (1, 'float32')), + ]), + 'shape_msgs/msg/SolidPrimitive': ([ + ('BOX', 'uint8', 1), + ('SPHERE', 'uint8', 2), + ('CYLINDER', 'uint8', 3), + ('CONE', 'uint8', 4), + ('BOX_X', 'uint8', 0), + ('BOX_Y', 'uint8', 1), + ('BOX_Z', 'uint8', 2), + ('SPHERE_RADIUS', 'uint8', 0), + ('CYLINDER_HEIGHT', 'uint8', 0), + ('CYLINDER_RADIUS', 'uint8', 1), + ('CONE_HEIGHT', 'uint8', 0), + ('CONE_RADIUS', 'uint8', 1), + ], [ + ('type', (1, 'uint8')), + ('dimensions', (4, ((1, 'float64'), None))), + ]), + 'shape_msgs/msg/Mesh': ([ + ], [ + ('triangles', (4, ((2, 'shape_msgs/msg/MeshTriangle'), None))), + ('vertices', (4, ((2, 'geometry_msgs/msg/Point'), None))), + ]), + 'shape_msgs/msg/Plane': ([ + ], [ + ('coef', (3, ((1, 'float64'), 4))), + ]), + 'shape_msgs/msg/MeshTriangle': ([ + ], [ + ('vertex_indices', (3, ((1, 'uint32'), 3))), + ]), + 'statistics_msgs/msg/StatisticDataType': ([ + ('STATISTICS_DATA_TYPE_UNINITIALIZED', 'uint8', 0), + ('STATISTICS_DATA_TYPE_AVERAGE', 'uint8', 1), + ('STATISTICS_DATA_TYPE_MINIMUM', 'uint8', 2), + ('STATISTICS_DATA_TYPE_MAXIMUM', 'uint8', 3), + ('STATISTICS_DATA_TYPE_STDDEV', 'uint8', 4), + ('STATISTICS_DATA_TYPE_SAMPLE_COUNT', 'uint8', 5), + ], [ + ('structure_needs_at_least_one_member', (1, 'uint8')), + ]), + 'statistics_msgs/msg/StatisticDataPoint': ([ + ], [ + ('data_type', (1, 'uint8')), + ('data', (1, 'float64')), + ]), + 'statistics_msgs/msg/MetricsMessage': ([ + ], [ + ('measurement_source_name', (1, 'string')), + ('metrics_source', (1, 'string')), + ('unit', (1, 'string')), + ('window_start', (2, 'builtin_interfaces/msg/Time')), + ('window_stop', (2, 'builtin_interfaces/msg/Time')), + ('statistics', (4, ((2, 'statistics_msgs/msg/StatisticDataPoint'), None))), + ]), + 'std_msgs/msg/UInt8': ([ + ], [ + ('data', (1, 'uint8')), + ]), + 'std_msgs/msg/Float32MultiArray': ([ + ], [ + ('layout', (2, 'std_msgs/msg/MultiArrayLayout')), + ('data', (4, ((1, 'float32'), None))), + ]), + 'std_msgs/msg/Int8': ([ + ], [ + ('data', (1, 'int8')), + ]), + 'std_msgs/msg/Empty': ([ + ], [ + ('structure_needs_at_least_one_member', (1, 'uint8')), + ]), + 'std_msgs/msg/String': ([ + ], [ + ('data', (1, 'string')), + ]), + 'std_msgs/msg/MultiArrayDimension': ([ + ], [ + ('label', (1, 'string')), + ('size', (1, 'uint32')), + ('stride', (1, 'uint32')), + ]), + 'std_msgs/msg/UInt64': ([ + ], [ + ('data', (1, 'uint64')), + ]), + 'std_msgs/msg/UInt16': ([ + ], [ + ('data', (1, 'uint16')), + ]), + 'std_msgs/msg/Float32': ([ + ], [ + ('data', (1, 'float32')), + ]), + 'std_msgs/msg/Int64': ([ + ], [ + ('data', (1, 'int64')), + ]), + 'std_msgs/msg/Int16MultiArray': ([ + ], [ + ('layout', (2, 'std_msgs/msg/MultiArrayLayout')), + ('data', (4, ((1, 'int16'), None))), + ]), + 'std_msgs/msg/Int16': ([ + ], [ + ('data', (1, 'int16')), + ]), + 'std_msgs/msg/Float64MultiArray': ([ + ], [ + ('layout', (2, 'std_msgs/msg/MultiArrayLayout')), + ('data', (4, ((1, 'float64'), None))), + ]), + 'std_msgs/msg/MultiArrayLayout': ([ + ], [ + ('dim', (4, ((2, 'std_msgs/msg/MultiArrayDimension'), None))), + ('data_offset', (1, 'uint32')), + ]), + 'std_msgs/msg/UInt32MultiArray': ([ + ], [ + ('layout', (2, 'std_msgs/msg/MultiArrayLayout')), + ('data', (4, ((1, 'uint32'), None))), + ]), + 'std_msgs/msg/Header': ([ + ], [ + ('stamp', (2, 'builtin_interfaces/msg/Time')), + ('frame_id', (1, 'string')), + ]), + 'std_msgs/msg/ByteMultiArray': ([ + ], [ + ('layout', (2, 'std_msgs/msg/MultiArrayLayout')), + ('data', (4, ((1, 'uint8'), None))), + ]), + 'std_msgs/msg/Int8MultiArray': ([ + ], [ + ('layout', (2, 'std_msgs/msg/MultiArrayLayout')), + ('data', (4, ((1, 'int8'), None))), + ]), + 'std_msgs/msg/Float64': ([ + ], [ + ('data', (1, 'float64')), + ]), + 'std_msgs/msg/UInt8MultiArray': ([ + ], [ + ('layout', (2, 'std_msgs/msg/MultiArrayLayout')), + ('data', (4, ((1, 'uint8'), None))), + ]), + 'std_msgs/msg/Byte': ([ + ], [ + ('data', (1, 'uint8')), + ]), + 'std_msgs/msg/Char': ([ + ], [ + ('data', (1, 'uint8')), + ]), + 'std_msgs/msg/UInt64MultiArray': ([ + ], [ + ('layout', (2, 'std_msgs/msg/MultiArrayLayout')), + ('data', (4, ((1, 'uint64'), None))), + ]), + 'std_msgs/msg/Int32MultiArray': ([ + ], [ + ('layout', (2, 'std_msgs/msg/MultiArrayLayout')), + ('data', (4, ((1, 'int32'), None))), + ]), + 'std_msgs/msg/ColorRGBA': ([ + ], [ + ('r', (1, 'float32')), + ('g', (1, 'float32')), + ('b', (1, 'float32')), + ('a', (1, 'float32')), + ]), + 'std_msgs/msg/Bool': ([ + ], [ + ('data', (1, 'bool')), + ]), + 'std_msgs/msg/UInt32': ([ + ], [ + ('data', (1, 'uint32')), + ]), + 'std_msgs/msg/Int64MultiArray': ([ + ], [ + ('layout', (2, 'std_msgs/msg/MultiArrayLayout')), + ('data', (4, ((1, 'int64'), None))), + ]), + 'std_msgs/msg/Int32': ([ + ], [ + ('data', (1, 'int32')), + ]), + 'std_msgs/msg/UInt16MultiArray': ([ + ], [ + ('layout', (2, 'std_msgs/msg/MultiArrayLayout')), + ('data', (4, ((1, 'uint16'), None))), + ]), + 'stereo_msgs/msg/DisparityImage': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('image', (2, 'sensor_msgs/msg/Image')), + ('f', (1, 'float32')), + ('t', (1, 'float32')), + ('valid_window', (2, 'sensor_msgs/msg/RegionOfInterest')), + ('min_disparity', (1, 'float32')), + ('max_disparity', (1, 'float32')), + ('delta_d', (1, 'float32')), + ]), + 'tf2_msgs/msg/TF2Error': ([ + ('NO_ERROR', 'uint8', 0), + ('LOOKUP_ERROR', 'uint8', 1), + ('CONNECTIVITY_ERROR', 'uint8', 2), + ('EXTRAPOLATION_ERROR', 'uint8', 3), + ('INVALID_ARGUMENT_ERROR', 'uint8', 4), + ('TIMEOUT_ERROR', 'uint8', 5), + ('TRANSFORM_ERROR', 'uint8', 6), + ], [ + ('error', (1, 'uint8')), + ('error_string', (1, 'string')), + ]), + 'tf2_msgs/msg/TFMessage': ([ + ], [ + ('transforms', (4, ((2, 'geometry_msgs/msg/TransformStamped'), None))), + ]), + 'trajectory_msgs/msg/MultiDOFJointTrajectory': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('joint_names', (4, ((1, 'string'), None))), + ('points', (4, ((2, 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint'), None))), + ]), + 'trajectory_msgs/msg/JointTrajectory': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('joint_names', (4, ((1, 'string'), None))), + ('points', (4, ((2, 'trajectory_msgs/msg/JointTrajectoryPoint'), None))), + ]), + 'trajectory_msgs/msg/JointTrajectoryPoint': ([ + ], [ + ('positions', (4, ((1, 'float64'), None))), + ('velocities', (4, ((1, 'float64'), None))), + ('accelerations', (4, ((1, 'float64'), None))), + ('effort', (4, ((1, 'float64'), None))), + ('time_from_start', (2, 'builtin_interfaces/msg/Duration')), + ]), + 'trajectory_msgs/msg/MultiDOFJointTrajectoryPoint': ([ + ], [ + ('transforms', (4, ((2, 'geometry_msgs/msg/Transform'), None))), + ('velocities', (4, ((2, 'geometry_msgs/msg/Twist'), None))), + ('accelerations', (4, ((2, 'geometry_msgs/msg/Twist'), None))), + ('time_from_start', (2, 'builtin_interfaces/msg/Duration')), + ]), + 'unique_identifier_msgs/msg/UUID': ([ + ], [ + ('uuid', (3, ((1, 'uint8'), 16))), + ]), + 'visualization_msgs/msg/Marker': ([ + ('ARROW', 'int32', 0), + ('CUBE', 'int32', 1), + ('SPHERE', 'int32', 2), + ('CYLINDER', 'int32', 3), + ('LINE_STRIP', 'int32', 4), + ('LINE_LIST', 'int32', 5), + ('CUBE_LIST', 'int32', 6), + ('SPHERE_LIST', 'int32', 7), + ('POINTS', 'int32', 8), + ('TEXT_VIEW_FACING', 'int32', 9), + ('MESH_RESOURCE', 'int32', 10), + ('TRIANGLE_LIST', 'int32', 11), + ('ADD', 'int32', 0), + ('MODIFY', 'int32', 0), + ('DELETE', 'int32', 2), + ('DELETEALL', 'int32', 3), + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('ns', (1, 'string')), + ('id', (1, 'int32')), + ('type', (1, 'int32')), + ('action', (1, 'int32')), + ('pose', (2, 'geometry_msgs/msg/Pose')), + ('scale', (2, 'geometry_msgs/msg/Vector3')), + ('color', (2, 'std_msgs/msg/ColorRGBA')), + ('lifetime', (2, 'builtin_interfaces/msg/Duration')), + ('frame_locked', (1, 'bool')), + ('points', (4, ((2, 'geometry_msgs/msg/Point'), None))), + ('colors', (4, ((2, 'std_msgs/msg/ColorRGBA'), None))), + ('text', (1, 'string')), + ('mesh_resource', (1, 'string')), + ('mesh_use_embedded_materials', (1, 'bool')), + ]), + 'visualization_msgs/msg/InteractiveMarkerInit': ([ + ], [ + ('server_id', (1, 'string')), + ('seq_num', (1, 'uint64')), + ('markers', (4, ((2, 'visualization_msgs/msg/InteractiveMarker'), None))), + ]), + 'visualization_msgs/msg/MenuEntry': ([ + ('FEEDBACK', 'uint8', 0), + ('ROSRUN', 'uint8', 1), + ('ROSLAUNCH', 'uint8', 2), + ], [ + ('id', (1, 'uint32')), + ('parent_id', (1, 'uint32')), + ('title', (1, 'string')), + ('command', (1, 'string')), + ('command_type', (1, 'uint8')), + ]), + 'visualization_msgs/msg/MarkerArray': ([ + ], [ + ('markers', (4, ((2, 'visualization_msgs/msg/Marker'), None))), + ]), + 'visualization_msgs/msg/InteractiveMarkerUpdate': ([ + ('KEEP_ALIVE', 'uint8', 0), + ('UPDATE', 'uint8', 1), + ], [ + ('server_id', (1, 'string')), + ('seq_num', (1, 'uint64')), + ('type', (1, 'uint8')), + ('markers', (4, ((2, 'visualization_msgs/msg/InteractiveMarker'), None))), + ('poses', (4, ((2, 'visualization_msgs/msg/InteractiveMarkerPose'), None))), + ('erases', (4, ((1, 'string'), None))), + ]), + 'visualization_msgs/msg/InteractiveMarker': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('pose', (2, 'geometry_msgs/msg/Pose')), + ('name', (1, 'string')), + ('description', (1, 'string')), + ('scale', (1, 'float32')), + ('menu_entries', (4, ((2, 'visualization_msgs/msg/MenuEntry'), None))), + ('controls', (4, ((2, 'visualization_msgs/msg/InteractiveMarkerControl'), None))), + ]), + 'visualization_msgs/msg/InteractiveMarkerFeedback': ([ + ('KEEP_ALIVE', 'uint8', 0), + ('POSE_UPDATE', 'uint8', 1), + ('MENU_SELECT', 'uint8', 2), + ('BUTTON_CLICK', 'uint8', 3), + ('MOUSE_DOWN', 'uint8', 4), + ('MOUSE_UP', 'uint8', 5), + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('client_id', (1, 'string')), + ('marker_name', (1, 'string')), + ('control_name', (1, 'string')), + ('event_type', (1, 'uint8')), + ('pose', (2, 'geometry_msgs/msg/Pose')), + ('menu_entry_id', (1, 'uint32')), + ('mouse_point', (2, 'geometry_msgs/msg/Point')), + ('mouse_point_valid', (1, 'bool')), + ]), + 'visualization_msgs/msg/ImageMarker': ([ + ('CIRCLE', 'int32', 0), + ('LINE_STRIP', 'int32', 1), + ('LINE_LIST', 'int32', 2), + ('POLYGON', 'int32', 3), + ('POINTS', 'int32', 4), + ('ADD', 'int32', 0), + ('REMOVE', 'int32', 1), + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('ns', (1, 'string')), + ('id', (1, 'int32')), + ('type', (1, 'int32')), + ('action', (1, 'int32')), + ('position', (2, 'geometry_msgs/msg/Point')), + ('scale', (1, 'float32')), + ('outline_color', (2, 'std_msgs/msg/ColorRGBA')), + ('filled', (1, 'uint8')), + ('fill_color', (2, 'std_msgs/msg/ColorRGBA')), + ('lifetime', (2, 'builtin_interfaces/msg/Duration')), + ('points', (4, ((2, 'geometry_msgs/msg/Point'), None))), + ('outline_colors', (4, ((2, 'std_msgs/msg/ColorRGBA'), None))), + ]), + 'visualization_msgs/msg/InteractiveMarkerControl': ([ + ('INHERIT', 'uint8', 0), + ('FIXED', 'uint8', 1), + ('VIEW_FACING', 'uint8', 2), + ('NONE', 'uint8', 0), + ('MENU', 'uint8', 1), + ('BUTTON', 'uint8', 2), + ('MOVE_AXIS', 'uint8', 3), + ('MOVE_PLANE', 'uint8', 4), + ('ROTATE_AXIS', 'uint8', 5), + ('MOVE_ROTATE', 'uint8', 6), + ('MOVE_3D', 'uint8', 7), + ('ROTATE_3D', 'uint8', 8), + ('MOVE_ROTATE_3D', 'uint8', 9), + ], [ + ('name', (1, 'string')), + ('orientation', (2, 'geometry_msgs/msg/Quaternion')), + ('orientation_mode', (1, 'uint8')), + ('interaction_mode', (1, 'uint8')), + ('always_visible', (1, 'bool')), + ('markers', (4, ((2, 'visualization_msgs/msg/Marker'), None))), + ('independent_marker_orientation', (1, 'bool')), + ('description', (1, 'string')), + ]), + 'visualization_msgs/msg/InteractiveMarkerPose': ([ + ], [ + ('header', (2, 'std_msgs/msg/Header')), + ('pose', (2, 'geometry_msgs/msg/Pose')), + ('name', (1, 'string')), + ]), } diff --git a/tests/cdr.py b/tests/cdr.py index f1361891..c3cbb249 100644 --- a/tests/cdr.py +++ b/tests/cdr.py @@ -161,12 +161,13 @@ def deserialize_message(rawdata: bytes, bmap: BasetypeMap, pos: int, msgdef: Msg values.append(num) elif desc.valtype == Valtype.ARRAY: - arr, pos = deserialize_array(rawdata, bmap, pos, *desc.args) + subdesc, length = desc.args + arr, pos = deserialize_array(rawdata, bmap, pos, length, subdesc) values.append(arr) elif desc.valtype == Valtype.SEQUENCE: size, pos = deserialize_number(rawdata, bmap, pos, 'int32') - arr, pos = deserialize_array(rawdata, bmap, pos, int(size), desc.args) + arr, pos = deserialize_array(rawdata, bmap, pos, int(size), desc.args[0]) values.append(arr) return msgdef.cls(*values), pos @@ -323,12 +324,12 @@ def serialize_message( pos = serialize_number(rawdata, bmap, pos, desc.args, val) elif desc.valtype == Valtype.ARRAY: - pos = serialize_array(rawdata, bmap, pos, desc.args[1], val) + pos = serialize_array(rawdata, bmap, pos, desc.args[0], val) elif desc.valtype == Valtype.SEQUENCE: size = len(val) pos = serialize_number(rawdata, bmap, pos, 'int32', size) - pos = serialize_array(rawdata, bmap, pos, desc.args, val) + pos = serialize_array(rawdata, bmap, pos, desc.args[0], val) return pos @@ -397,14 +398,15 @@ def get_size(message: Any, msgdef: Msgdef, size: int = 0) -> int: size += isize elif desc.valtype == Valtype.ARRAY: - if len(val) != desc.args[0]: - raise SerdeError(f'Unexpected array length: {len(val)} != {desc.args[0]}.') - size = get_array_size(desc.args[1], val, size) + subdesc, length = desc.args + if len(val) != length: + raise SerdeError(f'Unexpected array length: {len(val)} != {length}.') + size = get_array_size(subdesc, val, size) elif desc.valtype == Valtype.SEQUENCE: size = (size + 4 - 1) & -4 size += 4 - size = get_array_size(desc.args, val, size) + size = get_array_size(desc.args[0], val, size) return size diff --git a/tests/test_parse.py b/tests/test_parse.py index d5ea00fe..cc78bbfc 100644 --- a/tests/test_parse.py +++ b/tests/test_parse.py @@ -35,6 +35,7 @@ time time ================================================================================ MSG: test_msgs/Other uint64[3] Header +uint32 static = 42 """ RELSIBLING_MSG = """ @@ -81,6 +82,11 @@ module test_msgs { typedef test_msgs::msg::Bar Bar; typedef double d4[4]; + module Foo_Constants { + const int32 FOO = 32; + const int64 BAR = 64; + }; + @comment(type="text", text="ignore") struct Foo { std_msgs::msg::Header header; @@ -102,17 +108,18 @@ def test_parse_msg(): get_types_from_msg('', 'test_msgs/msg/Foo') ret = get_types_from_msg(MSG, 'test_msgs/msg/Foo') assert 'test_msgs/msg/Foo' in ret - fields = ret['test_msgs/msg/Foo'] - assert fields[0][0][1] == 'std_msgs/msg/Header' - assert fields[0][1][1] == 'header' - assert fields[1][0][1] == 'std_msgs/msg/Bool' - assert fields[1][1][1] == 'bool' - assert fields[2][0][1] == 'test_msgs/msg/Bar' - assert fields[2][1][1] == 'sibling' - assert fields[3][0][0] == Nodetype.BASE - assert fields[4][0][0] == Nodetype.SEQUENCE - assert fields[5][0][0] == Nodetype.SEQUENCE - assert fields[6][0][0] == Nodetype.ARRAY + consts, fields = ret['test_msgs/msg/Foo'] + assert consts == [('global', 'int32', 42)] + assert fields[0][0] == 'header' + assert fields[0][1][1] == 'std_msgs/msg/Header' + assert fields[1][0] == 'bool' + assert fields[1][1][1] == 'std_msgs/msg/Bool' + assert fields[2][0] == 'sibling' + assert fields[2][1][1] == 'test_msgs/msg/Bar' + assert fields[3][1][0] == Nodetype.BASE + assert fields[4][1][0] == Nodetype.SEQUENCE + assert fields[5][1][0] == Nodetype.SEQUENCE + assert fields[6][1][0] == Nodetype.ARRAY def test_parse_multi_msg(): @@ -122,20 +129,23 @@ def test_parse_multi_msg(): assert 'test_msgs/msg/Foo' in ret assert 'std_msgs/msg/Header' in ret assert 'test_msgs/msg/Other' in ret - assert ret['test_msgs/msg/Foo'][0][0][1] == 'std_msgs/msg/Header' - assert ret['test_msgs/msg/Foo'][1][0][1] == 'uint8' - assert ret['test_msgs/msg/Foo'][2][0][1] == 'uint8' + fields = ret['test_msgs/msg/Foo'][1] + assert fields[0][1][1] == 'std_msgs/msg/Header' + assert fields[1][1][1] == 'uint8' + assert fields[2][1][1] == 'uint8' + consts = ret['test_msgs/msg/Other'][0] + assert consts == [('static', 'uint32', 42)] def test_parse_relative_siblings_msg(): """Test relative siblings with msg parser.""" ret = get_types_from_msg(RELSIBLING_MSG, 'test_msgs/msg/Foo') - assert ret['test_msgs/msg/Foo'][0][0][1] == 'std_msgs/msg/Header' - assert ret['test_msgs/msg/Foo'][1][0][1] == 'test_msgs/msg/Other' + assert ret['test_msgs/msg/Foo'][1][0][1][1] == 'std_msgs/msg/Header' + assert ret['test_msgs/msg/Foo'][1][1][1][1] == 'test_msgs/msg/Other' ret = get_types_from_msg(RELSIBLING_MSG, 'rel_msgs/msg/Foo') - assert ret['rel_msgs/msg/Foo'][0][0][1] == 'std_msgs/msg/Header' - assert ret['rel_msgs/msg/Foo'][1][0][1] == 'rel_msgs/msg/Other' + assert ret['rel_msgs/msg/Foo'][1][0][1][1] == 'std_msgs/msg/Header' + assert ret['rel_msgs/msg/Foo'][1][1][1][1] == 'rel_msgs/msg/Other' def test_parse_idl(): @@ -145,28 +155,29 @@ def test_parse_idl(): ret = get_types_from_idl(IDL) assert 'test_msgs/msg/Foo' in ret - fields = ret['test_msgs/msg/Foo'] - assert fields[0][0][1] == 'std_msgs/msg/Header' - assert fields[0][1][1] == 'header' - assert fields[1][0][1] == 'std_msgs/msg/Bool' - assert fields[1][1][1] == 'bool' - assert fields[2][0][1] == 'test_msgs/msg/Bar' - assert fields[2][1][1] == 'sibling' - assert fields[3][0][0] == Nodetype.BASE - assert fields[4][0][0] == Nodetype.SEQUENCE - assert fields[5][0][0] == Nodetype.SEQUENCE - assert fields[6][0][0] == Nodetype.ARRAY + consts, fields = ret['test_msgs/msg/Foo'] + assert consts == [('FOO', 'int32', 32), ('BAR', 'int64', 64)] + assert fields[0][0] == 'header' + assert fields[0][1][1] == 'std_msgs/msg/Header' + assert fields[1][0] == 'bool' + assert fields[1][1][1] == 'std_msgs/msg/Bool' + assert fields[2][0] == 'sibling' + assert fields[2][1][1] == 'test_msgs/msg/Bar' + assert fields[3][1][0] == Nodetype.BASE + assert fields[4][1][0] == Nodetype.SEQUENCE + assert fields[5][1][0] == Nodetype.SEQUENCE + assert fields[6][1][0] == Nodetype.ARRAY def test_register_types(): """Test type registeration.""" assert 'foo' not in FIELDDEFS register_types({}) - register_types({'foo': [[(1, 'bool'), (2, 'b')]]}) + register_types({'foo': [[], [('b', (1, 'bool'))]]}) assert 'foo' in FIELDDEFS - register_types({'std_msgs/msg/Header': []}) - assert len(FIELDDEFS['std_msgs/msg/Header']) == 2 + register_types({'std_msgs/msg/Header': [[], []]}) + assert len(FIELDDEFS['std_msgs/msg/Header'][1]) == 2 with pytest.raises(TypesysError, match='different definition'): - register_types({'foo': [[(1, 'bool'), (2, 'x')]]}) + register_types({'foo': [[], [('x', (1, 'bool'))]]})