From 24cc3e0c2f6a1a17d6f34c42cb3690f3bb0fb3f1 Mon Sep 17 00:00:00 2001 From: Marko Durkovic Date: Mon, 5 Jul 2021 10:30:05 +0200 Subject: [PATCH] Add type hints to message classes --- src/rosbags/typesys/register.py | 35 +- src/rosbags/typesys/types.py | 931 ++++++++++++++++---------------- 2 files changed, 500 insertions(+), 466 deletions(-) diff --git a/src/rosbags/typesys/register.py b/src/rosbags/typesys/register.py index 875f930e..59ead36d 100644 --- a/src/rosbags/typesys/register.py +++ b/src/rosbags/typesys/register.py @@ -5,16 +5,44 @@ from __future__ import annotations import json +import re import sys from importlib.util import module_from_spec, spec_from_loader from typing import TYPE_CHECKING from . import types -from .base import TypesysError +from .base import Nodetype, TypesysError if TYPE_CHECKING: from .base import Typesdict +INTLIKE = re.compile('^u?(bool|int|float)') + + +def get_typehint(desc: tuple) -> str: + """Get python type hint for field. + + Args: + desc: Field descriptor. + + Returns: + Type hint for field. + + """ + if desc[0] == Nodetype.BASE: + if match := INTLIKE.match(desc[1]): + return match.group(1) + return 'str' + + if desc[0] == Nodetype.NAME: + return desc[1].replace('/', '__') + + sub = desc[2 if desc[0] == Nodetype.ARRAY else 1] + if INTLIKE.match(sub[1]): + typ = 'bool8' if sub[1] == 'bool' else sub[1] + return f'numpy.ndarray[Any, numpy.dtype[numpy.{typ}]]' + return f'list[{get_typehint(sub)}]' + def generate_python_code(typs: Typesdict) -> str: """Generate python code from types dictionary. @@ -35,6 +63,7 @@ def generate_python_code(typs: Typesdict) -> str: '', '# flake8: noqa N801', '# pylint: disable=invalid-name,too-many-instance-attributes,too-many-lines', + '# pylint: disable=unsubscriptable-object', '', 'from __future__ import annotations', '', @@ -44,6 +73,8 @@ def generate_python_code(typs: Typesdict) -> str: 'if TYPE_CHECKING:', ' from typing import Any', '', + ' import numpy', + '', '', ] @@ -54,7 +85,7 @@ def generate_python_code(typs: Typesdict) -> str: f'class {pyname}:', f' """Class for {name}."""', '', - *[f' {fname[1]}: Any' for _, fname in fields], + *[f' {fname[1]}: {get_typehint(desc)}' for desc, fname in fields], ] lines += [ diff --git a/src/rosbags/typesys/types.py b/src/rosbags/typesys/types.py index 861d911c..f6c6263d 100644 --- a/src/rosbags/typesys/types.py +++ b/src/rosbags/typesys/types.py @@ -6,6 +6,7 @@ # flake8: noqa N801 # pylint: disable=invalid-name,too-many-instance-attributes,too-many-lines +# pylint: disable=unsubscriptable-object from __future__ import annotations @@ -15,1315 +16,1317 @@ from typing import TYPE_CHECKING if TYPE_CHECKING: from typing import Any + import numpy + @dataclass class builtin_interfaces__msg__Time: """Class for builtin_interfaces/msg/Time.""" - sec: Any - nanosec: Any + sec: int + nanosec: int @dataclass class builtin_interfaces__msg__Duration: """Class for builtin_interfaces/msg/Duration.""" - sec: Any - nanosec: Any + sec: int + nanosec: int @dataclass class diagnostic_msgs__msg__DiagnosticStatus: """Class for diagnostic_msgs/msg/DiagnosticStatus.""" - level: Any - name: Any - message: Any - hardware_id: Any - values: Any + level: int + name: str + message: str + hardware_id: str + values: list[diagnostic_msgs__msg__KeyValue] @dataclass class diagnostic_msgs__msg__DiagnosticArray: """Class for diagnostic_msgs/msg/DiagnosticArray.""" - header: Any - status: Any + header: std_msgs__msg__Header + status: list[diagnostic_msgs__msg__DiagnosticStatus] @dataclass class diagnostic_msgs__msg__KeyValue: """Class for diagnostic_msgs/msg/KeyValue.""" - key: Any - value: Any + key: str + value: str @dataclass class geometry_msgs__msg__AccelWithCovariance: """Class for geometry_msgs/msg/AccelWithCovariance.""" - accel: Any - covariance: Any + accel: geometry_msgs__msg__Accel + covariance: numpy.ndarray[Any, numpy.dtype[numpy.float64]] @dataclass class geometry_msgs__msg__Point32: """Class for geometry_msgs/msg/Point32.""" - x: Any - y: Any - z: Any + x: float + y: float + z: float @dataclass class geometry_msgs__msg__Vector3: """Class for geometry_msgs/msg/Vector3.""" - x: Any - y: Any - z: Any + x: float + y: float + z: float @dataclass class geometry_msgs__msg__Inertia: """Class for geometry_msgs/msg/Inertia.""" - m: Any - com: Any - ixx: Any - ixy: Any - ixz: Any - iyy: Any - iyz: Any - izz: Any + m: float + com: geometry_msgs__msg__Vector3 + ixx: float + ixy: float + ixz: float + iyy: float + iyz: float + izz: float @dataclass class geometry_msgs__msg__PoseWithCovarianceStamped: """Class for geometry_msgs/msg/PoseWithCovarianceStamped.""" - header: Any - pose: Any + header: std_msgs__msg__Header + pose: geometry_msgs__msg__PoseWithCovariance @dataclass class geometry_msgs__msg__Twist: """Class for geometry_msgs/msg/Twist.""" - linear: Any - angular: Any + linear: geometry_msgs__msg__Vector3 + angular: geometry_msgs__msg__Vector3 @dataclass class geometry_msgs__msg__Pose: """Class for geometry_msgs/msg/Pose.""" - position: Any - orientation: Any + position: geometry_msgs__msg__Point + orientation: geometry_msgs__msg__Quaternion @dataclass class geometry_msgs__msg__Point: """Class for geometry_msgs/msg/Point.""" - x: Any - y: Any - z: Any + x: float + y: float + z: float @dataclass class geometry_msgs__msg__Vector3Stamped: """Class for geometry_msgs/msg/Vector3Stamped.""" - header: Any - vector: Any + header: std_msgs__msg__Header + vector: geometry_msgs__msg__Vector3 @dataclass class geometry_msgs__msg__Transform: """Class for geometry_msgs/msg/Transform.""" - translation: Any - rotation: Any + translation: geometry_msgs__msg__Vector3 + rotation: geometry_msgs__msg__Quaternion @dataclass class geometry_msgs__msg__PolygonStamped: """Class for geometry_msgs/msg/PolygonStamped.""" - header: Any - polygon: Any + header: std_msgs__msg__Header + polygon: geometry_msgs__msg__Polygon @dataclass class geometry_msgs__msg__Quaternion: """Class for geometry_msgs/msg/Quaternion.""" - x: Any - y: Any - z: Any - w: Any + x: float + y: float + z: float + w: float @dataclass class geometry_msgs__msg__Pose2D: """Class for geometry_msgs/msg/Pose2D.""" - x: Any - y: Any - theta: Any + x: float + y: float + theta: float @dataclass class geometry_msgs__msg__InertiaStamped: """Class for geometry_msgs/msg/InertiaStamped.""" - header: Any - inertia: Any + header: std_msgs__msg__Header + inertia: geometry_msgs__msg__Inertia @dataclass class geometry_msgs__msg__TwistStamped: """Class for geometry_msgs/msg/TwistStamped.""" - header: Any - twist: Any + header: std_msgs__msg__Header + twist: geometry_msgs__msg__Twist @dataclass class geometry_msgs__msg__PoseStamped: """Class for geometry_msgs/msg/PoseStamped.""" - header: Any - pose: Any + header: std_msgs__msg__Header + pose: geometry_msgs__msg__Pose @dataclass class geometry_msgs__msg__PointStamped: """Class for geometry_msgs/msg/PointStamped.""" - header: Any - point: Any + header: std_msgs__msg__Header + point: geometry_msgs__msg__Point @dataclass class geometry_msgs__msg__Polygon: """Class for geometry_msgs/msg/Polygon.""" - points: Any + points: list[geometry_msgs__msg__Point32] @dataclass class geometry_msgs__msg__PoseArray: """Class for geometry_msgs/msg/PoseArray.""" - header: Any - poses: Any + header: std_msgs__msg__Header + poses: list[geometry_msgs__msg__Pose] @dataclass class geometry_msgs__msg__AccelStamped: """Class for geometry_msgs/msg/AccelStamped.""" - header: Any - accel: Any + header: std_msgs__msg__Header + accel: geometry_msgs__msg__Accel @dataclass class geometry_msgs__msg__TwistWithCovarianceStamped: """Class for geometry_msgs/msg/TwistWithCovarianceStamped.""" - header: Any - twist: Any + header: std_msgs__msg__Header + twist: geometry_msgs__msg__TwistWithCovariance @dataclass class geometry_msgs__msg__QuaternionStamped: """Class for geometry_msgs/msg/QuaternionStamped.""" - header: Any - quaternion: Any + header: std_msgs__msg__Header + quaternion: geometry_msgs__msg__Quaternion @dataclass class geometry_msgs__msg__WrenchStamped: """Class for geometry_msgs/msg/WrenchStamped.""" - header: Any - wrench: Any + header: std_msgs__msg__Header + wrench: geometry_msgs__msg__Wrench @dataclass class geometry_msgs__msg__AccelWithCovarianceStamped: """Class for geometry_msgs/msg/AccelWithCovarianceStamped.""" - header: Any - accel: Any + header: std_msgs__msg__Header + accel: geometry_msgs__msg__AccelWithCovariance @dataclass class geometry_msgs__msg__PoseWithCovariance: """Class for geometry_msgs/msg/PoseWithCovariance.""" - pose: Any - covariance: Any + pose: geometry_msgs__msg__Pose + covariance: numpy.ndarray[Any, numpy.dtype[numpy.float64]] @dataclass class geometry_msgs__msg__Wrench: """Class for geometry_msgs/msg/Wrench.""" - force: Any - torque: Any + force: geometry_msgs__msg__Vector3 + torque: geometry_msgs__msg__Vector3 @dataclass class geometry_msgs__msg__TransformStamped: """Class for geometry_msgs/msg/TransformStamped.""" - header: Any - child_frame_id: Any - transform: Any + header: std_msgs__msg__Header + child_frame_id: str + transform: geometry_msgs__msg__Transform @dataclass class geometry_msgs__msg__Accel: """Class for geometry_msgs/msg/Accel.""" - linear: Any - angular: Any + linear: geometry_msgs__msg__Vector3 + angular: geometry_msgs__msg__Vector3 @dataclass class geometry_msgs__msg__TwistWithCovariance: """Class for geometry_msgs/msg/TwistWithCovariance.""" - twist: Any - covariance: Any + twist: geometry_msgs__msg__Twist + covariance: numpy.ndarray[Any, numpy.dtype[numpy.float64]] @dataclass class libstatistics_collector__msg__DummyMessage: """Class for libstatistics_collector/msg/DummyMessage.""" - header: Any + header: std_msgs__msg__Header @dataclass class lifecycle_msgs__msg__TransitionDescription: """Class for lifecycle_msgs/msg/TransitionDescription.""" - transition: Any - start_state: Any - goal_state: Any + transition: lifecycle_msgs__msg__Transition + start_state: lifecycle_msgs__msg__State + goal_state: lifecycle_msgs__msg__State @dataclass class lifecycle_msgs__msg__State: """Class for lifecycle_msgs/msg/State.""" - id: Any - label: Any + id: int + label: str @dataclass class lifecycle_msgs__msg__TransitionEvent: """Class for lifecycle_msgs/msg/TransitionEvent.""" - timestamp: Any - transition: Any - start_state: Any - goal_state: Any + timestamp: int + transition: lifecycle_msgs__msg__Transition + start_state: lifecycle_msgs__msg__State + goal_state: lifecycle_msgs__msg__State @dataclass class lifecycle_msgs__msg__Transition: """Class for lifecycle_msgs/msg/Transition.""" - id: Any - label: Any + id: int + label: str @dataclass class nav_msgs__msg__MapMetaData: """Class for nav_msgs/msg/MapMetaData.""" - map_load_time: Any - resolution: Any - width: Any - height: Any - origin: Any + map_load_time: builtin_interfaces__msg__Time + resolution: float + width: int + height: int + origin: geometry_msgs__msg__Pose @dataclass class nav_msgs__msg__GridCells: """Class for nav_msgs/msg/GridCells.""" - header: Any - cell_width: Any - cell_height: Any - cells: Any + header: std_msgs__msg__Header + cell_width: float + cell_height: float + cells: list[geometry_msgs__msg__Point] @dataclass class nav_msgs__msg__Odometry: """Class for nav_msgs/msg/Odometry.""" - header: Any - child_frame_id: Any - pose: Any - twist: Any + header: std_msgs__msg__Header + child_frame_id: str + pose: geometry_msgs__msg__PoseWithCovariance + twist: geometry_msgs__msg__TwistWithCovariance @dataclass class nav_msgs__msg__Path: """Class for nav_msgs/msg/Path.""" - header: Any - poses: Any + header: std_msgs__msg__Header + poses: list[geometry_msgs__msg__PoseStamped] @dataclass class nav_msgs__msg__OccupancyGrid: """Class for nav_msgs/msg/OccupancyGrid.""" - header: Any - info: Any - data: Any + header: std_msgs__msg__Header + info: nav_msgs__msg__MapMetaData + data: numpy.ndarray[Any, numpy.dtype[numpy.int8]] @dataclass class rcl_interfaces__msg__ListParametersResult: """Class for rcl_interfaces/msg/ListParametersResult.""" - names: Any - prefixes: Any + names: list[str] + prefixes: list[str] @dataclass class rcl_interfaces__msg__ParameterType: """Class for rcl_interfaces/msg/ParameterType.""" - structure_needs_at_least_one_member: Any + structure_needs_at_least_one_member: int @dataclass class rcl_interfaces__msg__ParameterEventDescriptors: """Class for rcl_interfaces/msg/ParameterEventDescriptors.""" - new_parameters: Any - changed_parameters: Any - deleted_parameters: Any + new_parameters: list[rcl_interfaces__msg__ParameterDescriptor] + changed_parameters: list[rcl_interfaces__msg__ParameterDescriptor] + deleted_parameters: list[rcl_interfaces__msg__ParameterDescriptor] @dataclass class rcl_interfaces__msg__ParameterEvent: """Class for rcl_interfaces/msg/ParameterEvent.""" - stamp: Any - node: Any - new_parameters: Any - changed_parameters: Any - deleted_parameters: Any + stamp: builtin_interfaces__msg__Time + node: str + new_parameters: list[rcl_interfaces__msg__Parameter] + changed_parameters: list[rcl_interfaces__msg__Parameter] + deleted_parameters: list[rcl_interfaces__msg__Parameter] @dataclass class rcl_interfaces__msg__IntegerRange: """Class for rcl_interfaces/msg/IntegerRange.""" - from_value: Any - to_value: Any - step: Any + from_value: int + to_value: int + step: int @dataclass class rcl_interfaces__msg__Parameter: """Class for rcl_interfaces/msg/Parameter.""" - name: Any - value: Any + name: str + value: rcl_interfaces__msg__ParameterValue @dataclass class rcl_interfaces__msg__ParameterValue: """Class for rcl_interfaces/msg/ParameterValue.""" - type: Any - bool_value: Any - integer_value: Any - double_value: Any - string_value: Any - byte_array_value: Any - bool_array_value: Any - integer_array_value: Any - double_array_value: Any - string_array_value: Any + type: int + bool_value: bool + integer_value: int + double_value: float + string_value: str + byte_array_value: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] + bool_array_value: numpy.ndarray[Any, numpy.dtype[numpy.bool8]] + 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] @dataclass class rcl_interfaces__msg__FloatingPointRange: """Class for rcl_interfaces/msg/FloatingPointRange.""" - from_value: Any - to_value: Any - step: Any + from_value: float + to_value: float + step: float @dataclass class rcl_interfaces__msg__SetParametersResult: """Class for rcl_interfaces/msg/SetParametersResult.""" - successful: Any - reason: Any + successful: bool + reason: str @dataclass class rcl_interfaces__msg__Log: """Class for rcl_interfaces/msg/Log.""" - stamp: Any - level: Any - name: Any - msg: Any - file: Any - function: Any - line: Any + stamp: builtin_interfaces__msg__Time + level: int + name: str + msg: str + file: str + function: str + line: int @dataclass class rcl_interfaces__msg__ParameterDescriptor: """Class for rcl_interfaces/msg/ParameterDescriptor.""" - name: Any - type: Any - description: Any - additional_constraints: Any - read_only: Any - floating_point_range: Any - integer_range: Any + name: str + type: int + description: str + additional_constraints: str + read_only: bool + floating_point_range: list[rcl_interfaces__msg__FloatingPointRange] + integer_range: list[rcl_interfaces__msg__IntegerRange] @dataclass class rmw_dds_common__msg__Gid: """Class for rmw_dds_common/msg/Gid.""" - data: Any + data: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] @dataclass class rmw_dds_common__msg__NodeEntitiesInfo: """Class for rmw_dds_common/msg/NodeEntitiesInfo.""" - node_namespace: Any - node_name: Any - reader_gid_seq: Any - writer_gid_seq: Any + node_namespace: str + node_name: str + reader_gid_seq: list[rmw_dds_common__msg__Gid] + writer_gid_seq: list[rmw_dds_common__msg__Gid] @dataclass class rmw_dds_common__msg__ParticipantEntitiesInfo: """Class for rmw_dds_common/msg/ParticipantEntitiesInfo.""" - gid: Any - node_entities_info_seq: Any + gid: rmw_dds_common__msg__Gid + node_entities_info_seq: list[rmw_dds_common__msg__NodeEntitiesInfo] @dataclass class rosgraph_msgs__msg__Clock: """Class for rosgraph_msgs/msg/Clock.""" - clock: Any + clock: builtin_interfaces__msg__Time @dataclass class sensor_msgs__msg__Temperature: """Class for sensor_msgs/msg/Temperature.""" - header: Any - temperature: Any - variance: Any + header: std_msgs__msg__Header + temperature: float + variance: float @dataclass class sensor_msgs__msg__Range: """Class for sensor_msgs/msg/Range.""" - header: Any - radiation_type: Any - field_of_view: Any - min_range: Any - max_range: Any - range: Any + header: std_msgs__msg__Header + radiation_type: int + field_of_view: float + min_range: float + max_range: float + range: float @dataclass class sensor_msgs__msg__RegionOfInterest: """Class for sensor_msgs/msg/RegionOfInterest.""" - x_offset: Any - y_offset: Any - height: Any - width: Any - do_rectify: Any + x_offset: int + y_offset: int + height: int + width: int + do_rectify: bool @dataclass class sensor_msgs__msg__JoyFeedbackArray: """Class for sensor_msgs/msg/JoyFeedbackArray.""" - array: Any + array: list[sensor_msgs__msg__JoyFeedback] @dataclass class sensor_msgs__msg__TimeReference: """Class for sensor_msgs/msg/TimeReference.""" - header: Any - time_ref: Any - source: Any + header: std_msgs__msg__Header + time_ref: builtin_interfaces__msg__Time + source: str @dataclass class sensor_msgs__msg__CompressedImage: """Class for sensor_msgs/msg/CompressedImage.""" - header: Any - format: Any - data: Any + header: std_msgs__msg__Header + format: str + data: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] @dataclass class sensor_msgs__msg__MultiEchoLaserScan: """Class for sensor_msgs/msg/MultiEchoLaserScan.""" - header: Any - angle_min: Any - angle_max: Any - angle_increment: Any - time_increment: Any - scan_time: Any - range_min: Any - range_max: Any - ranges: Any - intensities: Any + header: std_msgs__msg__Header + angle_min: float + angle_max: float + angle_increment: float + time_increment: float + scan_time: float + range_min: float + range_max: float + ranges: list[sensor_msgs__msg__LaserEcho] + intensities: list[sensor_msgs__msg__LaserEcho] @dataclass class sensor_msgs__msg__LaserEcho: """Class for sensor_msgs/msg/LaserEcho.""" - echoes: Any + echoes: numpy.ndarray[Any, numpy.dtype[numpy.float32]] @dataclass class sensor_msgs__msg__ChannelFloat32: """Class for sensor_msgs/msg/ChannelFloat32.""" - name: Any - values: Any + name: str + values: numpy.ndarray[Any, numpy.dtype[numpy.float32]] @dataclass class sensor_msgs__msg__CameraInfo: """Class for sensor_msgs/msg/CameraInfo.""" - header: Any - height: Any - width: Any - distortion_model: Any - d: Any - k: Any - r: Any - p: Any - binning_x: Any - binning_y: Any - roi: Any + header: std_msgs__msg__Header + height: int + width: int + distortion_model: str + d: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + k: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + r: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + p: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + binning_x: int + binning_y: int + roi: sensor_msgs__msg__RegionOfInterest @dataclass class sensor_msgs__msg__RelativeHumidity: """Class for sensor_msgs/msg/RelativeHumidity.""" - header: Any - relative_humidity: Any - variance: Any + header: std_msgs__msg__Header + relative_humidity: float + variance: float @dataclass class sensor_msgs__msg__FluidPressure: """Class for sensor_msgs/msg/FluidPressure.""" - header: Any - fluid_pressure: Any - variance: Any + header: std_msgs__msg__Header + fluid_pressure: float + variance: float @dataclass class sensor_msgs__msg__LaserScan: """Class for sensor_msgs/msg/LaserScan.""" - header: Any - angle_min: Any - angle_max: Any - angle_increment: Any - time_increment: Any - scan_time: Any - range_min: Any - range_max: Any - ranges: Any - intensities: Any + header: std_msgs__msg__Header + angle_min: float + angle_max: float + angle_increment: float + time_increment: float + scan_time: float + range_min: float + range_max: float + ranges: numpy.ndarray[Any, numpy.dtype[numpy.float32]] + intensities: numpy.ndarray[Any, numpy.dtype[numpy.float32]] @dataclass class sensor_msgs__msg__BatteryState: """Class for sensor_msgs/msg/BatteryState.""" - header: Any - voltage: Any - temperature: Any - current: Any - charge: Any - capacity: Any - design_capacity: Any - percentage: Any - power_supply_status: Any - power_supply_health: Any - power_supply_technology: Any - present: Any - cell_voltage: Any - cell_temperature: Any - location: Any - serial_number: Any + header: std_msgs__msg__Header + voltage: float + temperature: float + current: float + charge: float + capacity: float + design_capacity: float + percentage: float + power_supply_status: int + power_supply_health: int + power_supply_technology: int + present: bool + cell_voltage: numpy.ndarray[Any, numpy.dtype[numpy.float32]] + cell_temperature: numpy.ndarray[Any, numpy.dtype[numpy.float32]] + location: str + serial_number: str @dataclass class sensor_msgs__msg__Image: """Class for sensor_msgs/msg/Image.""" - header: Any - height: Any - width: Any - encoding: Any - is_bigendian: Any - step: Any - data: Any + header: std_msgs__msg__Header + height: int + width: int + encoding: str + is_bigendian: int + step: int + data: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] @dataclass class sensor_msgs__msg__PointCloud: """Class for sensor_msgs/msg/PointCloud.""" - header: Any - points: Any - channels: Any + header: std_msgs__msg__Header + points: list[geometry_msgs__msg__Point32] + channels: list[sensor_msgs__msg__ChannelFloat32] @dataclass class sensor_msgs__msg__Imu: """Class for sensor_msgs/msg/Imu.""" - header: Any - orientation: Any - orientation_covariance: Any - angular_velocity: Any - angular_velocity_covariance: Any - linear_acceleration: Any - linear_acceleration_covariance: Any + header: std_msgs__msg__Header + orientation: geometry_msgs__msg__Quaternion + orientation_covariance: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + angular_velocity: geometry_msgs__msg__Vector3 + 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]] @dataclass class sensor_msgs__msg__NavSatStatus: """Class for sensor_msgs/msg/NavSatStatus.""" - status: Any - service: Any + status: int + service: int @dataclass class sensor_msgs__msg__Illuminance: """Class for sensor_msgs/msg/Illuminance.""" - header: Any - illuminance: Any - variance: Any + header: std_msgs__msg__Header + illuminance: float + variance: float @dataclass class sensor_msgs__msg__Joy: """Class for sensor_msgs/msg/Joy.""" - header: Any - axes: Any - buttons: Any + header: std_msgs__msg__Header + axes: numpy.ndarray[Any, numpy.dtype[numpy.float32]] + buttons: numpy.ndarray[Any, numpy.dtype[numpy.int32]] @dataclass class sensor_msgs__msg__NavSatFix: """Class for sensor_msgs/msg/NavSatFix.""" - header: Any - status: Any - latitude: Any - longitude: Any - altitude: Any - position_covariance: Any - position_covariance_type: Any + header: std_msgs__msg__Header + status: sensor_msgs__msg__NavSatStatus + latitude: float + longitude: float + altitude: float + position_covariance: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + position_covariance_type: int @dataclass class sensor_msgs__msg__MultiDOFJointState: """Class for sensor_msgs/msg/MultiDOFJointState.""" - header: Any - joint_names: Any - transforms: Any - twist: Any - wrench: Any + header: std_msgs__msg__Header + joint_names: list[str] + transforms: list[geometry_msgs__msg__Transform] + twist: list[geometry_msgs__msg__Twist] + wrench: list[geometry_msgs__msg__Wrench] @dataclass class sensor_msgs__msg__MagneticField: """Class for sensor_msgs/msg/MagneticField.""" - header: Any - magnetic_field: Any - magnetic_field_covariance: Any + header: std_msgs__msg__Header + magnetic_field: geometry_msgs__msg__Vector3 + magnetic_field_covariance: numpy.ndarray[Any, numpy.dtype[numpy.float64]] @dataclass class sensor_msgs__msg__JointState: """Class for sensor_msgs/msg/JointState.""" - header: Any - name: Any - position: Any - velocity: Any - effort: Any + header: std_msgs__msg__Header + name: list[str] + position: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + velocity: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + effort: numpy.ndarray[Any, numpy.dtype[numpy.float64]] @dataclass class sensor_msgs__msg__PointField: """Class for sensor_msgs/msg/PointField.""" - name: Any - offset: Any - datatype: Any - count: Any + name: str + offset: int + datatype: int + count: int @dataclass class sensor_msgs__msg__PointCloud2: """Class for sensor_msgs/msg/PointCloud2.""" - header: Any - height: Any - width: Any - fields: Any - is_bigendian: Any - point_step: Any - row_step: Any - data: Any - is_dense: Any + header: std_msgs__msg__Header + height: int + width: int + fields: list[sensor_msgs__msg__PointField] + is_bigendian: bool + point_step: int + row_step: int + data: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] + is_dense: bool @dataclass class sensor_msgs__msg__JoyFeedback: """Class for sensor_msgs/msg/JoyFeedback.""" - type: Any - id: Any - intensity: Any + type: int + id: int + intensity: float @dataclass class shape_msgs__msg__SolidPrimitive: """Class for shape_msgs/msg/SolidPrimitive.""" - type: Any - dimensions: Any + type: int + dimensions: numpy.ndarray[Any, numpy.dtype[numpy.float64]] @dataclass class shape_msgs__msg__Mesh: """Class for shape_msgs/msg/Mesh.""" - triangles: Any - vertices: Any + triangles: list[shape_msgs__msg__MeshTriangle] + vertices: list[geometry_msgs__msg__Point] @dataclass class shape_msgs__msg__Plane: """Class for shape_msgs/msg/Plane.""" - coef: Any + coef: numpy.ndarray[Any, numpy.dtype[numpy.float64]] @dataclass class shape_msgs__msg__MeshTriangle: """Class for shape_msgs/msg/MeshTriangle.""" - vertex_indices: Any + vertex_indices: numpy.ndarray[Any, numpy.dtype[numpy.uint32]] @dataclass class statistics_msgs__msg__StatisticDataType: """Class for statistics_msgs/msg/StatisticDataType.""" - structure_needs_at_least_one_member: Any + structure_needs_at_least_one_member: int @dataclass class statistics_msgs__msg__StatisticDataPoint: """Class for statistics_msgs/msg/StatisticDataPoint.""" - data_type: Any - data: Any + data_type: int + data: float @dataclass class statistics_msgs__msg__MetricsMessage: """Class for statistics_msgs/msg/MetricsMessage.""" - measurement_source_name: Any - metrics_source: Any - unit: Any - window_start: Any - window_stop: Any - statistics: Any + measurement_source_name: str + metrics_source: str + unit: str + window_start: builtin_interfaces__msg__Time + window_stop: builtin_interfaces__msg__Time + statistics: list[statistics_msgs__msg__StatisticDataPoint] @dataclass class std_msgs__msg__UInt8: """Class for std_msgs/msg/UInt8.""" - data: Any + data: int @dataclass class std_msgs__msg__Float32MultiArray: """Class for std_msgs/msg/Float32MultiArray.""" - layout: Any - data: Any + layout: std_msgs__msg__MultiArrayLayout + data: numpy.ndarray[Any, numpy.dtype[numpy.float32]] @dataclass class std_msgs__msg__Int8: """Class for std_msgs/msg/Int8.""" - data: Any + data: int @dataclass class std_msgs__msg__Empty: """Class for std_msgs/msg/Empty.""" - structure_needs_at_least_one_member: Any + structure_needs_at_least_one_member: int @dataclass class std_msgs__msg__String: """Class for std_msgs/msg/String.""" - data: Any + data: str @dataclass class std_msgs__msg__MultiArrayDimension: """Class for std_msgs/msg/MultiArrayDimension.""" - label: Any - size: Any - stride: Any + label: str + size: int + stride: int @dataclass class std_msgs__msg__UInt64: """Class for std_msgs/msg/UInt64.""" - data: Any + data: int @dataclass class std_msgs__msg__UInt16: """Class for std_msgs/msg/UInt16.""" - data: Any + data: int @dataclass class std_msgs__msg__Float32: """Class for std_msgs/msg/Float32.""" - data: Any + data: float @dataclass class std_msgs__msg__Int64: """Class for std_msgs/msg/Int64.""" - data: Any + data: int @dataclass class std_msgs__msg__Int16MultiArray: """Class for std_msgs/msg/Int16MultiArray.""" - layout: Any - data: Any + layout: std_msgs__msg__MultiArrayLayout + data: numpy.ndarray[Any, numpy.dtype[numpy.int16]] @dataclass class std_msgs__msg__Int16: """Class for std_msgs/msg/Int16.""" - data: Any + data: int @dataclass class std_msgs__msg__Float64MultiArray: """Class for std_msgs/msg/Float64MultiArray.""" - layout: Any - data: Any + layout: std_msgs__msg__MultiArrayLayout + data: numpy.ndarray[Any, numpy.dtype[numpy.float64]] @dataclass class std_msgs__msg__MultiArrayLayout: """Class for std_msgs/msg/MultiArrayLayout.""" - dim: Any - data_offset: Any + dim: list[std_msgs__msg__MultiArrayDimension] + data_offset: int @dataclass class std_msgs__msg__UInt32MultiArray: """Class for std_msgs/msg/UInt32MultiArray.""" - layout: Any - data: Any + layout: std_msgs__msg__MultiArrayLayout + data: numpy.ndarray[Any, numpy.dtype[numpy.uint32]] @dataclass class std_msgs__msg__Header: """Class for std_msgs/msg/Header.""" - stamp: Any - frame_id: Any + stamp: builtin_interfaces__msg__Time + frame_id: str @dataclass class std_msgs__msg__ByteMultiArray: """Class for std_msgs/msg/ByteMultiArray.""" - layout: Any - data: Any + layout: std_msgs__msg__MultiArrayLayout + data: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] @dataclass class std_msgs__msg__Int8MultiArray: """Class for std_msgs/msg/Int8MultiArray.""" - layout: Any - data: Any + layout: std_msgs__msg__MultiArrayLayout + data: numpy.ndarray[Any, numpy.dtype[numpy.int8]] @dataclass class std_msgs__msg__Float64: """Class for std_msgs/msg/Float64.""" - data: Any + data: float @dataclass class std_msgs__msg__UInt8MultiArray: """Class for std_msgs/msg/UInt8MultiArray.""" - layout: Any - data: Any + layout: std_msgs__msg__MultiArrayLayout + data: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] @dataclass class std_msgs__msg__Byte: """Class for std_msgs/msg/Byte.""" - data: Any + data: int @dataclass class std_msgs__msg__Char: """Class for std_msgs/msg/Char.""" - data: Any + data: int @dataclass class std_msgs__msg__UInt64MultiArray: """Class for std_msgs/msg/UInt64MultiArray.""" - layout: Any - data: Any + layout: std_msgs__msg__MultiArrayLayout + data: numpy.ndarray[Any, numpy.dtype[numpy.uint64]] @dataclass class std_msgs__msg__Int32MultiArray: """Class for std_msgs/msg/Int32MultiArray.""" - layout: Any - data: Any + layout: std_msgs__msg__MultiArrayLayout + data: numpy.ndarray[Any, numpy.dtype[numpy.int32]] @dataclass class std_msgs__msg__ColorRGBA: """Class for std_msgs/msg/ColorRGBA.""" - r: Any - g: Any - b: Any - a: Any + r: float + g: float + b: float + a: float @dataclass class std_msgs__msg__Bool: """Class for std_msgs/msg/Bool.""" - data: Any + data: bool @dataclass class std_msgs__msg__UInt32: """Class for std_msgs/msg/UInt32.""" - data: Any + data: int @dataclass class std_msgs__msg__Int64MultiArray: """Class for std_msgs/msg/Int64MultiArray.""" - layout: Any - data: Any + layout: std_msgs__msg__MultiArrayLayout + data: numpy.ndarray[Any, numpy.dtype[numpy.int64]] @dataclass class std_msgs__msg__Int32: """Class for std_msgs/msg/Int32.""" - data: Any + data: int @dataclass class std_msgs__msg__UInt16MultiArray: """Class for std_msgs/msg/UInt16MultiArray.""" - layout: Any - data: Any + layout: std_msgs__msg__MultiArrayLayout + data: numpy.ndarray[Any, numpy.dtype[numpy.uint16]] @dataclass class stereo_msgs__msg__DisparityImage: """Class for stereo_msgs/msg/DisparityImage.""" - header: Any - image: Any - f: Any - t: Any - valid_window: Any - min_disparity: Any - max_disparity: Any - delta_d: Any + header: std_msgs__msg__Header + image: sensor_msgs__msg__Image + f: float + t: float + valid_window: sensor_msgs__msg__RegionOfInterest + min_disparity: float + max_disparity: float + delta_d: float @dataclass class tf2_msgs__msg__TF2Error: """Class for tf2_msgs/msg/TF2Error.""" - error: Any - error_string: Any + error: int + error_string: str @dataclass class tf2_msgs__msg__TFMessage: """Class for tf2_msgs/msg/TFMessage.""" - transforms: Any + transforms: list[geometry_msgs__msg__TransformStamped] @dataclass class trajectory_msgs__msg__MultiDOFJointTrajectory: """Class for trajectory_msgs/msg/MultiDOFJointTrajectory.""" - header: Any - joint_names: Any - points: Any + header: std_msgs__msg__Header + joint_names: list[str] + points: list[trajectory_msgs__msg__MultiDOFJointTrajectoryPoint] @dataclass class trajectory_msgs__msg__JointTrajectory: """Class for trajectory_msgs/msg/JointTrajectory.""" - header: Any - joint_names: Any - points: Any + header: std_msgs__msg__Header + joint_names: list[str] + points: list[trajectory_msgs__msg__JointTrajectoryPoint] @dataclass class trajectory_msgs__msg__JointTrajectoryPoint: """Class for trajectory_msgs/msg/JointTrajectoryPoint.""" - positions: Any - velocities: Any - accelerations: Any - effort: Any - time_from_start: Any + positions: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + velocities: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + accelerations: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + effort: numpy.ndarray[Any, numpy.dtype[numpy.float64]] + time_from_start: builtin_interfaces__msg__Duration @dataclass class trajectory_msgs__msg__MultiDOFJointTrajectoryPoint: """Class for trajectory_msgs/msg/MultiDOFJointTrajectoryPoint.""" - transforms: Any - velocities: Any - accelerations: Any - time_from_start: Any + transforms: list[geometry_msgs__msg__Transform] + velocities: list[geometry_msgs__msg__Twist] + accelerations: list[geometry_msgs__msg__Twist] + time_from_start: builtin_interfaces__msg__Duration @dataclass class unique_identifier_msgs__msg__UUID: """Class for unique_identifier_msgs/msg/UUID.""" - uuid: Any + uuid: numpy.ndarray[Any, numpy.dtype[numpy.uint8]] @dataclass class visualization_msgs__msg__Marker: """Class for visualization_msgs/msg/Marker.""" - header: Any - ns: Any - id: Any - type: Any - action: Any - pose: Any - scale: Any - color: Any - lifetime: Any - frame_locked: Any - points: Any - colors: Any - text: Any - mesh_resource: Any - mesh_use_embedded_materials: Any + header: std_msgs__msg__Header + ns: str + id: int + type: int + action: int + pose: geometry_msgs__msg__Pose + scale: geometry_msgs__msg__Vector3 + color: std_msgs__msg__ColorRGBA + lifetime: builtin_interfaces__msg__Duration + frame_locked: bool + points: list[geometry_msgs__msg__Point] + colors: list[std_msgs__msg__ColorRGBA] + text: str + mesh_resource: str + mesh_use_embedded_materials: bool @dataclass class visualization_msgs__msg__InteractiveMarkerInit: """Class for visualization_msgs/msg/InteractiveMarkerInit.""" - server_id: Any - seq_num: Any - markers: Any + server_id: str + seq_num: int + markers: list[visualization_msgs__msg__InteractiveMarker] @dataclass class visualization_msgs__msg__MenuEntry: """Class for visualization_msgs/msg/MenuEntry.""" - id: Any - parent_id: Any - title: Any - command: Any - command_type: Any + id: int + parent_id: int + title: str + command: str + command_type: int @dataclass class visualization_msgs__msg__MarkerArray: """Class for visualization_msgs/msg/MarkerArray.""" - markers: Any + markers: list[visualization_msgs__msg__Marker] @dataclass class visualization_msgs__msg__InteractiveMarkerUpdate: """Class for visualization_msgs/msg/InteractiveMarkerUpdate.""" - server_id: Any - seq_num: Any - type: Any - markers: Any - poses: Any - erases: Any + server_id: str + seq_num: int + type: int + markers: list[visualization_msgs__msg__InteractiveMarker] + poses: list[visualization_msgs__msg__InteractiveMarkerPose] + erases: list[str] @dataclass class visualization_msgs__msg__InteractiveMarker: """Class for visualization_msgs/msg/InteractiveMarker.""" - header: Any - pose: Any - name: Any - description: Any - scale: Any - menu_entries: Any - controls: Any + header: std_msgs__msg__Header + pose: geometry_msgs__msg__Pose + name: str + description: str + scale: float + menu_entries: list[visualization_msgs__msg__MenuEntry] + controls: list[visualization_msgs__msg__InteractiveMarkerControl] @dataclass class visualization_msgs__msg__InteractiveMarkerFeedback: """Class for visualization_msgs/msg/InteractiveMarkerFeedback.""" - header: Any - client_id: Any - marker_name: Any - control_name: Any - event_type: Any - pose: Any - menu_entry_id: Any - mouse_point: Any - mouse_point_valid: Any + header: std_msgs__msg__Header + client_id: str + marker_name: str + control_name: str + event_type: int + pose: geometry_msgs__msg__Pose + menu_entry_id: int + mouse_point: geometry_msgs__msg__Point + mouse_point_valid: bool @dataclass class visualization_msgs__msg__ImageMarker: """Class for visualization_msgs/msg/ImageMarker.""" - header: Any - ns: Any - id: Any - type: Any - action: Any - position: Any - scale: Any - outline_color: Any - filled: Any - fill_color: Any - lifetime: Any - points: Any - outline_colors: Any + header: std_msgs__msg__Header + ns: str + id: int + type: int + action: int + position: geometry_msgs__msg__Point + scale: float + outline_color: std_msgs__msg__ColorRGBA + filled: int + fill_color: std_msgs__msg__ColorRGBA + lifetime: builtin_interfaces__msg__Duration + points: list[geometry_msgs__msg__Point] + outline_colors: list[std_msgs__msg__ColorRGBA] @dataclass class visualization_msgs__msg__InteractiveMarkerControl: """Class for visualization_msgs/msg/InteractiveMarkerControl.""" - name: Any - orientation: Any - orientation_mode: Any - interaction_mode: Any - always_visible: Any - markers: Any - independent_marker_orientation: Any - description: Any + name: str + orientation: geometry_msgs__msg__Quaternion + orientation_mode: int + interaction_mode: int + always_visible: bool + markers: list[visualization_msgs__msg__Marker] + independent_marker_orientation: bool + description: str @dataclass class visualization_msgs__msg__InteractiveMarkerPose: """Class for visualization_msgs/msg/InteractiveMarkerPose.""" - header: Any - pose: Any - name: Any + header: std_msgs__msg__Header + pose: geometry_msgs__msg__Pose + name: str FIELDDEFS = {