diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/action_client.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/action_client.py index 0ae6214..68b6d41 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/action_client.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/action_client.py @@ -30,7 +30,10 @@ def __init__(self, action_type: Type[Action], action_name: str, node: Optional[N self._node.get_logger().info("Found server") def send_goal_and_wait( - self, action_name: str, goal: Action.Goal, timeout_sec: Optional[float] = None + self, + action_name: str, + goal: Action.Goal, + timeout_sec: Optional[float] = None, ) -> Optional[Action.Result]: """Sends an action goal and waits for the result @@ -80,8 +83,7 @@ def send_goal_async_handle( feedback_callback: Optional[Callable[[Action.Feedback], None]] = None, on_failure_callback: Optional[Callable[[], None]] = None, ) -> ActionHandle: - """Sends an action goal asynchronously and create an ActionHandle for managing the asynchronous lifecycle of - the action request + """Sends an action goal asynchronously and create an `ActionHandle` Args: action_name (str): A representative name of the action for logging diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/action_handle.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/action_handle.py index da299c2..da74240 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/action_handle.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/action_handle.py @@ -12,8 +12,10 @@ from bdai_ros2_wrappers.type_hints import Action -class ActionHandle(object): - """Handles the two stage process that is getting a result after sending an ActionGoal to an ActionServer as well +class ActionHandle: + """Handle for the lifecycle of an action. + + Handles the two stage process that is getting a result after sending an ActionGoal to an ActionServer as well as holding the various callbacks for sending an ActionGoal (cancel, failure, feedback, result) """ @@ -23,6 +25,7 @@ def __init__(self, action_name: str, logger: Optional[RcutilsLogger] = None, con Args: action_name (str): The name of the action (for logging purposes) logger (Optional[RcutilsLogger]): An optional logger to use. If none is provided, one is created + context (Optional[Context]): An optional ros context """ if context is None: context = get_default_context() @@ -72,8 +75,7 @@ def wait_for_result(self, timeout_sec: Optional[float] = None) -> bool: ) def wait_for_acceptance(self, timeout_sec: Optional[float] = None) -> bool: - """ - Waits until goal is accepted or timeout. + """Waits until goal is accepted or timeout. Args: timeout_sec (Optional[float]): A timeout in seconds. No timeout is used if None @@ -86,8 +88,7 @@ def wait_for_acceptance(self, timeout_sec: Optional[float] = None) -> bool: ) def set_send_goal_future(self, send_goal_future: Future) -> None: - """Sets the future received from sending the Action.Goal and sets up the callback for when a response is - received""" + """Sets the future received from sending the `Action.Goal`""" self._send_goal_future = send_goal_future self._send_goal_future.add_done_callback(self._goal_response_callback) diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/callback_groups.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/callback_groups.py index 036b8db..2322748 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/callback_groups.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/callback_groups.py @@ -8,9 +8,7 @@ class NonReentrantCallbackGroup(rclpy.callback_groups.CallbackGroup): - """ - A callback group to prevent concurrent execution of the same callback - while allowing it for different callbacks. + """A callback group to prevent concurrent execution of the same callback while allowing it for different callbacks. Note this behavior sits in between that offered by rclpy.callback_groups.MutuallyExclusiveCallbackGroup and @@ -23,16 +21,36 @@ class NonReentrantCallbackGroup(rclpy.callback_groups.CallbackGroup): """ def __init__(self) -> None: + """Constructor""" super().__init__() self._active_entities: typing.Set[rclpy.executors.WaitableEntityType] = set() self._lock = threading.Lock() def can_execute(self, entity: rclpy.executors.WaitableEntityType) -> bool: + """Determine if a callback for an entity can be executed. + + Args: + entity: A subscription, timer, client, service, or waitable instance. + + Returns: + `True` if entity callback can be executed, `False` otherwise. + """ with self._lock: assert weakref.ref(entity) in self.entities return entity not in self._active_entities def beginning_execution(self, entity: rclpy.executors.WaitableEntityType) -> bool: + """Get permission for the callback from the group to begin executing an entity. + + If this returns `True` then `CallbackGroup.ending_execution` must be called after + the callback has been executed. + + Arg: + entity:A subscription, timer, client, service, or waitable instance. + + Returns: + `True` if the callback can be executed, `False` otherwise. + """ with self._lock: assert weakref.ref(entity) in self.entities if entity not in self._active_entities: @@ -41,6 +59,11 @@ def beginning_execution(self, entity: rclpy.executors.WaitableEntityType) -> boo return False def ending_execution(self, entity: rclpy.executors.WaitableEntityType) -> None: + """Notify group that a callback has finished executing. + + Args: + entity: A subscription, timer, client, service, or waitable instance. + """ with self._lock: assert entity in self._active_entities self._active_entities.remove(entity) diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/context.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/context.py index b47a04e..47f76d4 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/context.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/context.py @@ -7,8 +7,7 @@ def wait_for_shutdown(*, timeout_sec: Optional[float] = None, context: Optional[Context] = None) -> bool: - """ - Wait for context shutdown. + """Wait for context shutdown. Args: timeout_sec: optional timeout for wait, wait indefinitely by default. diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/executors.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/executors.py index 95b5ceb..3f5a819 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/executors.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/executors.py @@ -18,8 +18,7 @@ class AutoScalingThreadPool(concurrent.futures.Executor): - """ - A concurrent.futures.Executor subclass based on a thread pool. + """A concurrent.futures.Executor subclass based on a thread pool. Akin to the concurrent.futures.ThreadPoolExecutor class but with autoscaling capabilities. Within a given range, the number of @@ -109,8 +108,7 @@ class Worker(threading.Thread): """A worker in its own daemonized OS thread.""" def __init__(self, executor_weakref: weakref.ref, stop_on_timeout: bool = True) -> None: - """ - Initializes the worker. + """Initializes the worker. Args: executor_weakref: a weak reference to the parent autoscaling thread pool. @@ -209,8 +207,7 @@ def __init__( max_idle_time: typing.Optional[float] = None, logger: typing.Optional[logging.Logger] = None, ): - """ - Initializes the thread pool. + """Initializes the thread pool. Args: min_workers: optional minimum number of workers in the pool, 0 by default. @@ -273,7 +270,7 @@ def __init__( self._scaling_event = threading.Condition() self._waitqueues: typing.Dict[typing.Callable[..., typing.Any], collections.deque] = collections.defaultdict( - collections.deque + collections.deque, ) self._runlists: typing.Dict[typing.Callable[..., typing.Any], typing.List[AutoScalingThreadPool.Work]] = ( collections.defaultdict(list) @@ -334,8 +331,7 @@ def capped(self) -> bool: return any(work.pending() for waitqueue in self._waitqueues.values() for work in waitqueue) def wait(self, timeout: typing.Optional[float] = None) -> bool: - """ - Waits for all work in the pool to complete. + """Waits for all work in the pool to complete. Only ongoing work at the time of invocation is watched after. Work added during the wait will not be considered. @@ -403,10 +399,13 @@ def _do_submit(self, work: "AutoScalingThreadPool.Work") -> None: # NOTE(hidmic): cannot recreate type signature for method override # See https://github.com/python/typeshed/blob/main/stdlib/concurrent/futures/_base.pyi. def submit( # type: ignore - self, fn: typing.Callable[..., typing.Any], /, *args: typing.Any, **kwargs: typing.Any + self, + fn: typing.Callable[..., typing.Any], + /, + *args: typing.Any, + **kwargs: typing.Any, ) -> concurrent.futures.Future: - """ - Submits work to the pool. + """Submits work to the pool. Args: fn: a callable to execute. Must be immutable and hashable for @@ -457,8 +456,7 @@ def submit( # type: ignore return future def shutdown(self, wait: bool = True, *, cancel_futures: bool = False) -> None: - """ - Shuts down the pool. + """Shuts down the pool. Args: wait: whether to wait for all worker threads to shutdown. @@ -499,8 +497,7 @@ def predicate() -> bool: class AutoScalingMultiThreadedExecutor(rclpy.executors.Executor): - """ - An rclpy.executors.Executor subclass based on an AutoScalingThreadPool. + """An rclpy.executors.Executor subclass based on an AutoScalingThreadPool. Akin to the rclpy.executors.MultiThreadedExecutor class but with autoscaling capabilities. Moreover, a concurrency quota can be defined on a per callback + callback group basis to @@ -519,12 +516,17 @@ def __init__(self, task: rclpy.task.Task, entity: typing.Optional[rclpy.executor self.callback_group = entity.callback_group if entity is not None else None def __call__(self) -> None: + """Run or resume a task + + See rclpy.task.Task documentation for further reference. + """ self.task.__call__() def __getattr__(self, name: str) -> typing.Any: return getattr(self.task, name) def cancel(self) -> None: + """Cancels the task""" # This is a re-implementation to cope with rclpy.task.Task # leaving coroutines unawaited upon cancellation. schedule_callbacks = False @@ -552,8 +554,7 @@ def __init__( context: typing.Optional[rclpy.context.Context] = None, logger: typing.Optional[logging.Logger] = None, ) -> None: - """ - Initializes the executor. + """Initializes the executor. Args: max_threads: optional maximum number of threads to spin at any given time. @@ -564,6 +565,8 @@ def __init__( max_threads_per_callback_group: optional maximum number of concurrent callbacks to service for a given callback group. Useful to avoid reentrant callback groups from starving the pool. + context: An optional instance of the ros context + logger: An optional logger instance """ super().__init__(context=context) if logger is None: @@ -610,11 +613,11 @@ def _do_spin_once(self, *args: typing.Any, **kwargs: typing.Any) -> None: for task in list(self._wip): if task.done(): del self._wip[task] - try: + + # ignore concurrent entity destruction + with contextlib.suppress(rclpy.executors.InvalidHandle): task.result() - except rclpy.executors.InvalidHandle: - # ignore concurrent entity destruction - pass + except rclpy.executors.ConditionReachedException: pass except rclpy.executors.ExternalShutdownException: @@ -625,15 +628,29 @@ def _do_spin_once(self, *args: typing.Any, **kwargs: typing.Any) -> None: pass def spin_once(self, timeout_sec: typing.Optional[float] = None) -> None: + """Complete all immediately available work""" self._do_spin_once(timeout_sec) def spin_once_until_future_complete( - self, future: rclpy.task.Future, timeout_sec: typing.Optional[float] = None + self, + future: rclpy.task.Future, + timeout_sec: typing.Optional[float] = None, ) -> None: + """Complete all work until the provided future is done. + + Args: + future: The ros future instance + timeout_sec: The timeout for working + """ future.add_done_callback(lambda f: self.wake()) self._do_spin_once(timeout_sec, condition=future.done) def shutdown(self, timeout_sec: typing.Optional[float] = None) -> bool: + """Shutdown the executor. + + Args: + timeout_sec: The timeout for shutting down + """ with self._shutdown_lock: # Before actual shutdown and resource cleanup, all pending work # must be waited on. Work tracking in rclpy.executors.Executor @@ -656,8 +673,7 @@ def shutdown(self, timeout_sec: typing.Optional[float] = None) -> bool: @contextlib.contextmanager def background(executor: rclpy.executors.Executor) -> typing.Iterator[rclpy.executors.Executor]: - """ - Pushes an executor to a background thread. + """Pushes an executor to a background thread. Upon context entry, the executor starts spinning in a background thread. Upon context exit, the executor is shutdown and the background thread is joined. @@ -673,7 +689,8 @@ def background(executor: rclpy.executors.Executor) -> typing.Iterator[rclpy.exec executor.spin_once = bind_to_thread(executor.spin_once, background_thread) executor.spin_until_future_complete = bind_to_thread(executor.spin_until_future_complete, background_thread) executor.spin_once_until_future_complete = bind_to_thread( - executor.spin_once_until_future_complete, background_thread + executor.spin_once_until_future_complete, + background_thread, ) background_thread.start() try: @@ -685,8 +702,7 @@ def background(executor: rclpy.executors.Executor) -> typing.Iterator[rclpy.exec @contextlib.contextmanager def foreground(executor: rclpy.executors.Executor) -> typing.Iterator[rclpy.executors.Executor]: - """ - Manages an executor in the current thread. + """Manages an executor in the current thread. Upon context exit, the executor is shutdown. diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/logging.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/logging.py index 5af1073..6c23b37 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/logging.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/logging.py @@ -34,7 +34,7 @@ tree = ET.parse(os.path.join(share_directory, "package.xml")) version = tree.getroot().find("version") if packaging.version.parse(version.text) >= packaging.version.parse("3.9.0"): - warnings.warn("TODO: use subloggers in RcutilsLogHandler implementation") + warnings.warn("TODO: use subloggers in RcutilsLogHandler implementation", stacklevel=1) class RcutilsLogHandler(logging.Handler): @@ -43,6 +43,7 @@ class RcutilsLogHandler(logging.Handler): default_formatter = logging.Formatter("(logging.%(name)s) %(message)s") def __init__(self, node: Node, level: typing.Union[int, str] = logging.NOTSET) -> None: + """Constructor""" super().__init__(level=level) self.node = node self.logger = node.get_logger() @@ -51,17 +52,28 @@ def __init__(self, node: Node, level: typing.Union[int, str] = logging.NOTSET) - self.setFormatter(self.default_formatter) def setLevel(self, level: typing.Union[int, str]) -> None: + """Sets the threshold for this handler to level. + + Logging messages which are less severe than level will be ignored. When a handler is created, the level is set + to NOTSET (which causes all messages to be processed). + """ super().setLevel(level) self.logger.set_level(SEVERITY_MAP[self.level]) def emit(self, record: logging.LogRecord) -> None: + """Do whatever it takes to actually log the specified logging record.""" try: message = self.format(record) severity = SEVERITY_MAP[record.levelno] # NOTE(hidmic): this bypasses the rclpy logger API to avoid the extra meaningless # computations (e.g. call stack inspection). impl.rclpy_logging_rcutils_log( - severity, self.logger.name, message, record.funcName, record.pathname, record.lineno + severity, + self.logger.name, + message, + record.funcName, + record.pathname, + record.lineno, ) except Exception: self.handleError(record) @@ -69,8 +81,7 @@ def emit(self, record: logging.LogRecord) -> None: @contextlib.contextmanager def logs_to_ros(node: Node) -> typing.Iterator[None]: - """ - Forwards root `logging.Logger` logs to the ROS 2 logging system. + """Forwards root `logging.Logger` logs to the ROS 2 logging system. Note that logs are subject to severity level thresholds and propagation semantics at both the `logging` module and the ROS 2 logging system. For diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/node.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/node.py index 7a5c0ca..185cc28 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/node.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/node.py @@ -8,20 +8,20 @@ class Node(BaseNode): - """ - An rclpy.node.Node subclass that: + """An rclpy.node.Node subclass that: * changes the default callback group to be non-reentrant. """ def __init__(self, *args: Any, default_callback_group: Optional[CallbackGroup] = None, **kwargs: Any) -> None: - """ - Initializes the node. + """Initializes the node. Args: + args: positional arguments for a ros Node default_callback_group: optional callback group to use as default for all subsequently created entities, such as subscriptions and clients. + kwargs: keyword arguments for a ros Node See rclpy.node.Node documentation for further reference on available arguments. """ @@ -32,8 +32,6 @@ def __init__(self, *args: Any, default_callback_group: Optional[CallbackGroup] = @property def default_callback_group(self) -> CallbackGroup: - """ - Get the default callback group. - """ + """Get the default callback group.""" # NOTE(hidmic): this overrides the hardcoded default group in rclpy.node.Node implementation return self._default_callback_group_override diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/process.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/process.py index 7e6316f..47e49e8 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/process.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/process.py @@ -29,8 +29,7 @@ class ROSAwareProcess: - """ - A ``main``-like function wrapper that binds a ROS 2 aware scope to each function invocation. + """A ``main``-like function wrapper that binds a ROS 2 aware scope to each function invocation. Only one process can be invoked at a time, becoming the ``current`` process. This enables global access to the process and, in consequence, to its scope. @@ -54,8 +53,7 @@ def __init__( cli: typing.Optional[argparse.ArgumentParser] = None, **init_arguments: typing.Any, ): - """ - Initializes the ROS 2 aware process. + """Initializes the ROS 2 aware process. Args: func: a ``main``-like function to wrap ie. a callable taking a sequence of strings, @@ -76,27 +74,25 @@ def __init__( without its extension (or CLI program name if one is specified) will be used. Defaults to True for prebaked processes. cli: optional command-line interface argument parser. + init_arguments: Keyword arguments for the scope. Raises: ValueError: if a prebaked process is configured without autospin. """ - if cli is None: - program_name = os.path.basename(sys.argv[0]) - else: - program_name = cli.prog + program_name = os.path.basename(sys.argv[0]) if cli is None else cli.prog name, _ = os.path.splitext(program_name) if prebaked is True: try: validate_node_name(name) prebaked = name except InvalidNodeNameException: - warnings.warn(f"'{name}' cannot be used as node name, using scope default") + warnings.warn(f"'{name}' cannot be used as node name, using scope default", stacklevel=1) if namespace is True: try: validate_namespace(name) namespace = name except InvalidNamespaceException: - warnings.warn(f"'{name}' cannot be used as namespace, using scope default") + warnings.warn(f"'{name}' cannot be used as namespace, using scope default", stacklevel=1) if forward_logging is None: forward_logging = bool(prebaked) self._func = func @@ -114,8 +110,7 @@ def __init__( functools.update_wrapper(self, self._func) def __getattr__(self, name: str) -> typing.Any: - """ - Gets missing attributes from the underlying scope. + """Gets missing attributes from the underlying scope. Raises: RuntimeError: if the process is not executing. @@ -126,8 +121,7 @@ def __getattr__(self, name: str) -> typing.Any: return getattr(self._scope, name) def __setattr__(self, name: str, value: typing.Any) -> None: - """ - Sets public attributes on the underlying scope when possible. + """Sets public attributes on the underlying scope when possible. Args: name: name of the attribute to be set @@ -139,8 +133,7 @@ def __setattr__(self, name: str, value: typing.Any) -> None: super().__setattr__(name, value) def __call__(self, argv: typing.Optional[typing.Sequence[str]] = None) -> typing.Optional[int]: - """ - Invokes wrapped process function in a ROS 2 aware scope. + """Invokes wrapped process function in a ROS 2 aware scope. Args: argv: optional command line-like arguments. @@ -190,8 +183,7 @@ def __call__(self, argv: typing.Optional[typing.Sequence[str]] = None) -> typing ROSAwareProcess.lock.release() def wait_for_shutdown(self, *, timeout_sec: typing.Optional[float] = None) -> bool: - """ - Wait for shutdown of the underlying scope context. + """Wait for shutdown of the underlying scope context. Args: timeout_sec: optional timeout for wait, wait indefinitely by default. @@ -242,8 +234,7 @@ def tf_listener() -> typing.Optional[TFListenerWrapper]: def load(factory: AnyEntityFactoryCallable, *args: typing.Any, **kwargs: typing.Any) -> AnyEntity: - """ - Loads a ROS 2 node (or a collection thereof) within the current ROS 2 aware process scope. + """Loads a ROS 2 node (or a collection thereof) within the current ROS 2 aware process scope. See `ROSAwareProcess` and `ROSAwareScope.load` documentation for further reference on positional and keyword arguments taken by this function. @@ -258,8 +249,7 @@ def load(factory: AnyEntityFactoryCallable, *args: typing.Any, **kwargs: typing. def unload(loaded: AnyEntity) -> None: - """ - Unloads a ROS 2 node (or a collection thereof) from the current ROS 2 aware process scope. + """Unloads a ROS 2 node (or a collection thereof) from the current ROS 2 aware process scope. See `ROSAwareProcess` and `ROSAwareScope.unload` documentation for further reference on positional and keyword arguments taken by this function. @@ -274,10 +264,11 @@ def unload(loaded: AnyEntity) -> None: def managed( - factory: AnyEntityFactoryCallable, *args: typing.Any, **kwargs: typing.Any + factory: AnyEntityFactoryCallable, + *args: typing.Any, + **kwargs: typing.Any, ) -> typing.ContextManager[AnyEntity]: - """ - Manages a ROS 2 node (or a collection thereof) within the current ROS 2 aware process scope. + """Manages a ROS 2 node (or a collection thereof) within the current ROS 2 aware process scope. See `ROSAwareProcess` and `ROSAwareScope.managed` documentation for further reference on positional and keyword arguments taken by this function. @@ -292,8 +283,7 @@ def managed( def spin(factory: typing.Optional[AnyEntityFactoryCallable] = None, *args: typing.Any, **kwargs: typing.Any) -> None: - """ - Spins current ROS 2 aware process executor (and all ROS 2 nodes in it). + """Spins current ROS 2 aware process executor (and all ROS 2 nodes in it). Optionally, manages a ROS 2 node (or a collection thereof) for as long as it spins. @@ -310,7 +300,8 @@ def spin(factory: typing.Optional[AnyEntityFactoryCallable] = None, *args: typin def main( - cli: typing.Optional[argparse.ArgumentParser] = None, **kwargs: typing.Any + cli: typing.Optional[argparse.ArgumentParser] = None, + **kwargs: typing.Any, ) -> typing.Callable[[MainCallable], ROSAwareProcess]: """Wraps a ``main``-like function in a `ROSAwareProcess` instance.""" @@ -329,8 +320,7 @@ def try_shutdown() -> None: def wait_for_shutdown(*, timeout_sec: typing.Optional[float] = None) -> bool: - """ - Wait for current ROS 2 aware process to shutdown. + """Wait for current ROS 2 aware process to shutdown. See `ROSAwareProcess.wait_for_shutdown` documentation for further reference on positional and keyword arguments taken by this function. diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/scope.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/scope.py index 47775ad..999c20a 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/scope.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/scope.py @@ -22,9 +22,9 @@ class ROSAwareScope(typing.ContextManager["ROSAwareScope"]): - """ - A context manager to enable ROS 2 code in a given scope by providing - an `rclpy` node and an autoscaling multi-threaded executor spinning + """A context manager to enable ROS 2 code in a given scope. + + This is accomplished by providing an `rclpy` node and an autoscaling multi-threaded executor spinning in a background thread. """ @@ -46,8 +46,7 @@ def __init__( namespace: typing.Optional[typing.Union[typing.Literal[True], str]] = None, context: typing.Optional[rclpy.context.Context] = None, ) -> None: - """ - Initializes the ROS 2 aware scope. + """Initializes the ROS 2 aware scope. Args: prebaked: whether to include an implicit main node in the scope graph or not, @@ -93,8 +92,7 @@ def context(self) -> typing.Optional[rclpy.context.Context]: return self._context def __enter__(self) -> "ROSAwareScope": - """ - Enters scope. + """Enters scope. Scopes are not reentrant. @@ -144,8 +142,7 @@ def __enter__(self) -> "ROSAwareScope": return self def __exit__(self, *exc: typing.Any) -> None: - """ - Exits scope. + """Exits scope. Raises: RuntimeError: if scope has not been entered (or already exited) @@ -186,8 +183,7 @@ def executor(self) -> typing.Optional[rclpy.executors.Executor]: @executor.setter def executor(self, executor: rclpy.executors.Executor) -> None: - """ - Sets scope executor. + """Sets scope executor. Args: executor: executor to be used. @@ -210,8 +206,7 @@ def tf_listener(self) -> typing.Optional[TFListenerWrapper]: @tf_listener.setter def tf_listener(self, tf_listener: TFListenerWrapper) -> None: - """ - Sets scope tf listener. + """Sets scope tf listener. Args: tf_listener: tf listener to be used as tf listener in scope. @@ -235,8 +230,7 @@ def node(self) -> typing.Optional[rclpy.node.Node]: @node.setter def node(self, node: rclpy.node.Node) -> None: - """ - Sets scope main node. + """Sets scope main node. Args: node: node to be promoted to main node. It must be a node known to the scope. @@ -260,10 +254,12 @@ def node(self, node: rclpy.node.Node) -> None: @typing.overload def managed( - self, factory: NodeFactoryCallable, *args: typing.Any, **kwargs: typing.Any + self, + factory: NodeFactoryCallable, + *args: typing.Any, + **kwargs: typing.Any, ) -> typing.ContextManager[rclpy.node.Node]: - """ - Manages a ROS 2 node within scope. + """Manages a ROS 2 node within scope. Upon context entry, a ROS 2 node is instantiated and loaded. Upon context exit, that ROS 2 node is unloaded and destroyed. @@ -277,10 +273,12 @@ def managed( @typing.overload def managed( - self, factory: GraphFactoryCallable, *args: typing.Any, **kwargs: typing.Any + self, + factory: GraphFactoryCallable, + *args: typing.Any, + **kwargs: typing.Any, ) -> typing.ContextManager[typing.List[rclpy.node.Node]]: - """ - Manages a collection (or graph) of ROS 2 nodes within scope. + """Manages a collection (or graph) of ROS 2 nodes within scope. Upon context entry, ROS 2 nodes are instantiated and loaded. Upon context exit, those ROS 2 nodes are unloaded and destroyed. @@ -294,8 +292,12 @@ def managed( @contextlib.contextmanager def managed( - self, factory: AnyEntityFactoryCallable, *args: typing.Any, **kwargs: typing.Any + self, + factory: AnyEntityFactoryCallable, + *args: typing.Any, + **kwargs: typing.Any, ) -> typing.Iterator[AnyEntity]: + """Overloaded method. See above for documentation.""" loaded = self.load(factory, *args, **kwargs) try: yield loaded @@ -304,8 +306,7 @@ def managed( @typing.overload def load(self, factory: NodeFactoryCallable, *args: typing.Any, **kwargs: typing.Any) -> rclpy.node.Node: - """ - Instantiates and loads a ROS 2 node. + """Instantiates and loads a ROS 2 node. Args: factory: callable to instantiate a ROS 2 node. @@ -324,10 +325,12 @@ def load(self, factory: NodeFactoryCallable, *args: typing.Any, **kwargs: typing @typing.overload def load( - self, factory: GraphFactoryCallable, *args: typing.Any, **kwargs: typing.Any + self, + factory: GraphFactoryCallable, + *args: typing.Any, + **kwargs: typing.Any, ) -> typing.List[rclpy.node.Node]: - """ - Instantiates and loads a collection (or graph) of ROS 2 nodes. + """Instantiates and loads a collection (or graph) of ROS 2 nodes. Args: factory: callable to instantiate a collection of ROS 2 nodes. @@ -350,15 +353,13 @@ def load( namespace: typing.Optional[str] = None, **kwargs: typing.Any, ) -> AnyEntity: + """Overloaded method. See above for documentation.""" with self._lock: if self._stack is None: raise RuntimeError("scope has not been entered (or was already exited)") if self._executor is None: raise RuntimeError("scope executor has not been set") - if namespace: - namespace = namespace_with(self._namespace, namespace) - else: - namespace = self._namespace + namespace = namespace_with(self._namespace, namespace) if namespace else self._namespace node_or_graph = factory(*args, context=self._context, namespace=namespace, **kwargs) if not isinstance(node_or_graph, rclpy.node.Node): graph = list(node_or_graph) @@ -372,8 +373,7 @@ def load( return node def unload(self, loaded: AnyEntity) -> None: - """ - Unloads and destroys ROS 2 nodes. + """Unloads and destroys ROS 2 nodes. Args: loaded: ROS 2 node or a collection thereof to unload. @@ -398,8 +398,7 @@ def unload(self, loaded: AnyEntity) -> None: @typing.overload def spin(self) -> None: - """ - Spins scope executor (and all nodes in it). + """Spins scope executor (and all nodes in it). If no scope executor was set, a default one is. @@ -410,8 +409,7 @@ def spin(self) -> None: @typing.overload def spin(self, factory: NodeFactoryCallable, *args: typing.Any, **kwargs: typing.Any) -> None: - """ - Spins scope executor (and all nodes in it). + """Spins scope executor (and all nodes in it). Additionally, and for as long as it spins, a ROS 2 node is loaded. If no scope executor was set, a default one is. @@ -430,8 +428,7 @@ def spin(self, factory: NodeFactoryCallable, *args: typing.Any, **kwargs: typing @typing.overload def spin(self, factory: GraphFactoryCallable, *args: typing.Any, **kwargs: typing.Any) -> None: - """ - Spins scope executor (and all nodes in it). + """Spins scope executor (and all nodes in it). Additionally, and for as long as it spins, a collection of ROS 2 nodes is loaded. If no scope executor was set, a default one is. @@ -448,8 +445,12 @@ def spin(self, factory: GraphFactoryCallable, *args: typing.Any, **kwargs: typin """ def spin( - self, factory: typing.Optional[AnyEntityFactoryCallable] = None, *args: typing.Any, **kwargs: typing.Any + self, + factory: typing.Optional[AnyEntityFactoryCallable] = None, + *args: typing.Any, + **kwargs: typing.Any, ) -> None: + """Overloaded method. See above for documentation.""" if self._stack is None: raise RuntimeError("scope has not been entered (or already exited)") if self._autospin: @@ -458,7 +459,7 @@ def spin( if self._executor is None: logger = rclpy.logging.get_logger(self._namespace or fqn(self.__class__)) self._executor = self._stack.enter_context( - foreground(AutoScalingMultiThreadedExecutor(logger=logger, context=self._context)) + foreground(AutoScalingMultiThreadedExecutor(logger=logger, context=self._context)), ) with contextlib.ExitStack() as stack: if factory is not None: @@ -476,13 +477,15 @@ def top( domain_id: typing.Optional[int] = None, **kwargs: typing.Any, ) -> typing.Iterator[ROSAwareScope]: - """ - Manages a ROS 2 aware scope, handling ROS 2 context lifecycle as well. + """Manages a ROS 2 aware scope, handling ROS 2 context lifecycle as well. Args: args: optional command-line arguments for context initialization. context: optional context to manage. If none is provided, one will be created. For global scopes, the default context will be used. + global_: Whether to use the global context or a locally constructed one if one is not provided. + domain_id: A domain id used for initializing rclpy. + kwargs: keyword arguments to pass to `ROSAwareScope`. See `ROSAwareScope` documentation for further reference on positional and keyword arguments taken by this function. @@ -530,8 +533,7 @@ def executor() -> typing.Optional[rclpy.executors.Executor]: def load(factory: AnyEntityFactoryCallable, *args: typing.Any, **kwargs: typing.Any) -> AnyEntity: - """ - Loads a ROS 2 node (or a collection thereof) within the current ROS 2 aware scope. + """Loads a ROS 2 node (or a collection thereof) within the current ROS 2 aware scope. See `ROSAwareScope.load` documentation for further reference on positional and keyword arguments taken by this function. @@ -546,8 +548,7 @@ def load(factory: AnyEntityFactoryCallable, *args: typing.Any, **kwargs: typing. def unload(loaded: AnyEntity) -> None: - """ - Unloads a ROS 2 node (or a collection thereof) from the current ROS 2 aware scope. + """Unloads a ROS 2 node (or a collection thereof) from the current ROS 2 aware scope. See `ROSAwareScope.unload` documentation for further reference on positional and keyword arguments taken by this function. @@ -562,10 +563,11 @@ def unload(loaded: AnyEntity) -> None: def managed( - factory: AnyEntityFactoryCallable, *args: typing.Any, **kwargs: typing.Any + factory: AnyEntityFactoryCallable, + *args: typing.Any, + **kwargs: typing.Any, ) -> typing.ContextManager[AnyEntity]: - """ - Manages a ROS 2 node (or a collection thereof) within the current ROS 2 aware scope. + """Manages a ROS 2 node (or a collection thereof) within the current ROS 2 aware scope. See `ROSAwareScope.managed` documentation for further reference on positional and keyword arguments taken by this function. @@ -580,8 +582,7 @@ def managed( def spin(factory: typing.Optional[AnyEntityFactoryCallable] = None, *args: typing.Any, **kwargs: typing.Any) -> None: - """ - Spins current ROS 2 aware scope executor (and all the ROS 2 nodes in it). + """Spins current ROS 2 aware scope executor (and all the ROS 2 nodes in it). Optionally, manages a ROS 2 node (or a collection thereof) for as long as it spins. diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/service_handle.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/service_handle.py index d6b0f50..52cf05e 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/service_handle.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/service_handle.py @@ -10,12 +10,21 @@ from bdai_ros2_wrappers.type_hints import SrvTypeResponse -class ServiceHandle(object): - """Handles getting a result after sending an ServiceRequest to Service +class ServiceHandle: + """A handle for the lifecycle of a service. + + Handles getting a result after sending an ServiceRequest to Service as holding the various callbacks for sending an ServiceRequest (result, failure) """ def __init__(self, service_name: str, logger: Optional[RcutilsLogger] = None, context: Optional[Context] = None): + """Constructor + + Args: + service_name: The name of the service handle to be used in logging + logger: An optional ros logger + context: An optional ros context + """ if context is None: context = get_default_context() self._service_name = service_name @@ -32,6 +41,7 @@ def __init__(self, service_name: str, logger: Optional[RcutilsLogger] = None, co @property def result(self) -> Optional[SrvTypeResponse]: + """Returns the result if one has been received from the service""" return self._result def set_result_callback(self, result_callback: Callable) -> None: @@ -39,8 +49,7 @@ def set_result_callback(self, result_callback: Callable) -> None: self._result_callback = result_callback def set_send_service_future(self, send_service_future: Future) -> None: - """Sets the future received from sending the Action.Goal and sets up the callback for when a response is - received""" + """Sets the future received from sending the Action.Goal""" self._send_service_future = send_service_future self._send_service_future.add_done_callback(self._service_result_callback) diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/single_goal_action_server.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/single_goal_action_server.py index de8b327..f3b5ef6 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/single_goal_action_server.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/single_goal_action_server.py @@ -8,15 +8,14 @@ from bdai_ros2_wrappers.single_goal_multiple_action_servers import SingleGoalMultipleActionServers from bdai_ros2_wrappers.type_hints import ActionType -# Note: for this to work correctly you must use a multi-threaded executor when spinning the node! E.g.: -# from rclpy.executors import MultiThreadedExecutor -# executor = MultiThreadedExecutor() -# rclpy.spin(node, executor=executor) +# Note: for this to work correctly you must use a multi-threaded executor when spinning the node! class SingleGoalActionServer(SingleGoalMultipleActionServers): - """Wrapper around a single action server that only allows a single Action to be executing at one time. If a new - Action.Goal is received, the existing Action (if there is one) is preemptively canceled""" + """An action server that only allows a single Action to be executing at one time. + + If a new Action.Goal is received, the existing Action (if there is one) is preemptively canceled. + """ def __init__( self, @@ -27,5 +26,6 @@ def __init__( callback_group: Optional[CallbackGroup] = None, ) -> None: super().__init__( - node=node, action_server_parameters=[(action_type, action_topic, execute_callback, callback_group)] + node=node, + action_server_parameters=[(action_type, action_topic, execute_callback, callback_group)], ) diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/single_goal_multiple_action_servers.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/single_goal_multiple_action_servers.py index b8c458f..b3118f3 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/single_goal_multiple_action_servers.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/single_goal_multiple_action_servers.py @@ -11,14 +11,19 @@ from bdai_ros2_wrappers.type_hints import Action, ActionType -class SingleGoalMultipleActionServers(object): - """Wrapper around multiple action servers that only allows a single Action to be executing at one time. If a new - Action.Goal is received by any of the action servers, the existing Action (if there is one) is preemptively - canceled""" +class SingleGoalMultipleActionServers: + """Wrapper around multiple action servers that only allows a single Action to be executing at one time. + + If a new Action.Goal is received by any of the action servers, the existing Action (if there is one) is preemptively + canceled. + """ def __init__( - self, node: Node, action_server_parameters: List[Tuple[ActionType, str, Callable, Optional[CallbackGroup]]] + self, + node: Node, + action_server_parameters: List[Tuple[ActionType, str, Callable, Optional[CallbackGroup]]], ) -> None: + """Constructor""" self._node = node self._goal_handle: Optional[ServerGoalHandle] = None self._goal_lock = threading.Lock() @@ -34,13 +39,15 @@ def __init__( handle_accepted_callback=self.handle_accepted_callback, cancel_callback=self.cancel_callback, callback_group=callback_group, - ) + ), ) def get_logger(self) -> RcutilsLogger: + """Returns the ros logger""" return self._node.get_logger() def destroy(self) -> None: + """Destroy all of the internal action servers""" for action_server in self._action_servers: action_server.destroy() @@ -50,6 +57,7 @@ def goal_callback(self, goal: Action.Goal) -> GoalResponse: return GoalResponse.ACCEPT def handle_accepted_callback(self, goal_handle: ServerGoalHandle) -> None: + """Callback triggered when an action is accepted.""" with self._goal_lock: # This server only allows one goal at a time if self._goal_handle is not None and self._goal_handle.is_active: diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/static_transform_broadcaster.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/static_transform_broadcaster.py index 392f56f..939102f 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/static_transform_broadcaster.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/static_transform_broadcaster.py @@ -8,16 +8,15 @@ class StaticTransformBroadcaster: - """ - A modified :class:`tf2_ros.StaticTransformBroadcaster` that stores transforms - sent through it, matching ``rclcpp::StaticTransformBroadcaster`` behavior. + """A modified :class:`tf2_ros.StaticTransformBroadcaster` that stores transforms sent through it. + + This matches ``rclcpp::StaticTransformBroadcaster`` behavior. """ DEFAULT_QOS = QoSProfile(depth=1, durability=DurabilityPolicy.TRANSIENT_LOCAL, history=HistoryPolicy.KEEP_LAST) def __init__(self, node: Node, qos: Optional[Union[QoSProfile, int]] = None) -> None: - """ - Constructor. + """Constructor. :param node: The ROS2 node. :param qos: A QoSProfile or a history depth to apply to the publisher. @@ -28,6 +27,11 @@ def __init__(self, node: Node, qos: Optional[Union[QoSProfile, int]] = None) -> self._pub = node.create_publisher(TFMessage, "/tf_static", qos) def sendTransform(self, transform: Union[TransformStamped, Iterable[TransformStamped]]) -> None: + """Send a transform, or a list of transforms, to the Buffer associated with this TransformBroadcaster. + + Args: + transform: A transform or list of transforms to send. + """ try: transforms = list(transform) except TypeError: # in which case, transform is not iterable diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/subscription.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/subscription.py index e1d00fb..8c0e7ac 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/subscription.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/subscription.py @@ -18,8 +18,7 @@ def wait_for_message_async( qos_profile: typing.Union[rclpy.qos.QoSProfile, int] = 1, node: typing.Optional[rclpy.node.Node] = None, ) -> rclpy.task.Future: - """ - Wait for message on a given topic asynchronously. + """Wait for message on a given topic asynchronously. Args: msg_type: type of message to wait for. @@ -56,13 +55,14 @@ def wait_for_message( node: typing.Optional[rclpy.node.Node] = None, **kwargs: typing.Any, ) -> typing.Optional[MessageT]: - """ - Wait for message on a given topic synchronously. + """Wait for message on a given topic synchronously. Args: msg_type: type of message to wait for. topic_name: name of the topic to wait on. timeout_sec: optional timeout, in seconds, for the wait. + node: An optional Node to provide. If none is provided, the one from the scope is used. + kwargs: keyword argument to pass to `wait_for_message_async` See `wait_for_message_async` documentation for a reference on additional keyword arguments. diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/tf_listener_wrapper.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/tf_listener_wrapper.py index b545b62..1e81957 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/tf_listener_wrapper.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/tf_listener_wrapper.py @@ -17,12 +17,16 @@ @runtime_checkable class StampLike(Protocol): + """A protocol similar to the Time msg""" + sec: int nanosec: int @runtime_checkable class TimeLike(Protocol): + """A protocol similar to to rclpy.time.Time""" + nanoseconds: int @@ -36,8 +40,7 @@ def from_time_like(obj: Union[StampLike, TimeLike]) -> Time: class TFListenerWrapper: - """ - A `tf2_ros` lookup device, wrapping both a buffer and a listener. + """A `tf2_ros` lookup device, wrapping both a buffer and a listener. When using process-wide machinery: @@ -62,8 +65,7 @@ def callback(self): """ def __init__(self, node: Optional[Node] = None, cache_time_s: Optional[float] = None) -> None: - """ - Initializes the wrapper. + """Initializes the wrapper. Args: node: optional node for transform listening, defaults to the current scope node. @@ -83,18 +85,22 @@ def __init__(self, node: Optional[Node] = None, cache_time_s: Optional[float] = @property def buffer(self) -> Buffer: + """Returns the tf buffer""" return self._tf_buffer def shutdown(self) -> None: + """Shutdown the tf listener""" self._tf_listener.unregister() def wait_for_a_tform_b_async( - self, frame_a: str, frame_b: str, transform_time: Optional[Union[StampLike, TimeLike]] = None + self, + frame_a: str, + frame_b: str, + transform_time: Optional[Union[StampLike, TimeLike]] = None, ) -> Future: - """ - Wait asynchronously for the transform from from_frame to to_frame to become available. + """Wait asynchronously for the transform from from_frame to to_frame to become available. - Parameters: + Args: frame_a: Base frame for transform. The transform returned will be frame_a_t_frame_b frame_b: Tip frame for transform. The transform returned will be frame_a_t_frame_b transform_time: The time at which to look up the transform. If left at None, the most @@ -113,12 +119,11 @@ def wait_for_a_tform_b( transform_time: Optional[Union[StampLike, TimeLike]] = None, timeout_sec: Optional[float] = None, ) -> bool: - """ - Wait for a transform from frame_a to frame_b to become available. + """Wait for a transform from frame_a to frame_b to become available. Note this is a blocking call. If the underlying node is not spinning, an indefinite wait may block forever. - Parameters: + Args: frame_a: Base frame for transform. The transform returned will be frame_a_t_frame_b frame_b: Tip frame for transform. The transform returned will be frame_a_t_frame_b transform_time: The time at which to look up the transform. If left at None, the most @@ -131,9 +136,9 @@ def wait_for_a_tform_b( """ if self._node.executor is None: if timeout_sec is None: - warnings.warn("Node is not spinning yet, wait may block forever") + warnings.warn("Node is not spinning yet, wait may block forever", stacklevel=1) elif timeout_sec > 0.0: - warnings.warn("Node is not spinning yet, wait may be futile") + warnings.warn("Node is not spinning yet, wait may be futile", stacklevel=1) future = self.wait_for_a_tform_b_async(frame_a, frame_b, transform_time) if not wait_for_future(future, timeout_sec, context=self._node.context): future.cancel() @@ -148,10 +153,9 @@ def lookup_a_tform_b( timeout_sec: Optional[float] = None, wait_for_frames: bool = False, ) -> TransformStamped: - """ - Looks up the transform from frame_a to frame_b at the specified time. + """Looks up the transform from frame_a to frame_b at the specified time. - Parameters: + Args: frame_a: Base frame for transform. The transform returned will be frame_a_t_frame_b frame_b: Tip frame for transform. The transform returned will be frame_a_t_frame_b transform_time: The time at which to look up the transform. If left at None, the most @@ -190,12 +194,15 @@ def lookup_a_tform_b( return self._tf_buffer.lookup_transform(frame_a, frame_b, transform_time) def lookup_latest_timestamp( - self, frame_a: str, frame_b: str, timeout_sec: Optional[float] = None, wait_for_frames: bool = False + self, + frame_a: str, + frame_b: str, + timeout_sec: Optional[float] = None, + wait_for_frames: bool = False, ) -> Time: - """ - Looks up the latest time at which a transform from frame_a to frame_b is available. + """Looks up the latest time at which a transform from frame_a to frame_b is available. - Parameters: + Args: frame_a: Base frame for transform. The transform returned will be frame_a_t_frame_b frame_b: Tip frame for transform. The transform returned will be frame_a_t_frame_b timeout_sec: The time to wait for the transform to become available if the requested time is beyond diff --git a/bdai_ros2_wrappers/bdai_ros2_wrappers/utilities.py b/bdai_ros2_wrappers/bdai_ros2_wrappers/utilities.py index bb5b9c1..0bc95fa 100644 --- a/bdai_ros2_wrappers/bdai_ros2_wrappers/utilities.py +++ b/bdai_ros2_wrappers/bdai_ros2_wrappers/utilities.py @@ -21,8 +21,7 @@ def namespace_with(*args: typing.Optional[str]) -> str: def either_or(obj: typing.Any, name: str, default: typing.Any) -> typing.Any: - """ - Gets either an object attribute's value or a default value. + """Gets either an object attribute's value or a default value. Unlike `getattr`, callable attributes are applied as getters on `obj`. """ diff --git a/bdai_ros2_wrappers/examples/background_action_example.py b/bdai_ros2_wrappers/examples/background_action_example.py index 2dd3798..2801bc8 100644 --- a/bdai_ros2_wrappers/examples/background_action_example.py +++ b/bdai_ros2_wrappers/examples/background_action_example.py @@ -1,7 +1,6 @@ # Copyright (c) 2023 Boston Dynamics AI Institute Inc. All rights reserved. -""" -An example of a ROS 2 aware executable using process-wide machinery. +"""An example of a ROS 2 aware executable using process-wide machinery. Run with: @@ -47,8 +46,7 @@ def execute_callback(self, goal_handle: ServerGoalHandle) -> Fibonacci.Result: @ros_process.main() def main() -> None: - """ - Example entrypoint. + """Example entrypoint. It is configured almost as a prebaked ROS 2 aware process. That is, including a process-wide (ie. globally accessible) node, an autoscaling multi-threaded executor diff --git a/bdai_ros2_wrappers/examples/logs_to_ros_example.py b/bdai_ros2_wrappers/examples/logs_to_ros_example.py index 2cf6c5c..e236115 100644 --- a/bdai_ros2_wrappers/examples/logs_to_ros_example.py +++ b/bdai_ros2_wrappers/examples/logs_to_ros_example.py @@ -1,7 +1,6 @@ # Copyright (c) 2023 Boston Dynamics AI Institute Inc. All rights reserved. -""" -An example of `logging` logs forward to the ROS 2 logging system. +"""An example of `logging` logs forward to the ROS 2 logging system. Run with: diff --git a/bdai_ros2_wrappers/examples/talker_example.py b/bdai_ros2_wrappers/examples/talker_example.py index 77ff0ff..61ba8ad 100644 --- a/bdai_ros2_wrappers/examples/talker_example.py +++ b/bdai_ros2_wrappers/examples/talker_example.py @@ -1,7 +1,6 @@ # Copyright (c) 2023 Boston Dynamics AI Institute Inc. All rights reserved. -""" -An example of a ROS 2 single node process using process-wide machinery. +"""An example of a ROS 2 single node process using process-wide machinery. Run with: @@ -39,8 +38,7 @@ def callback(self) -> None: @ros_process.main(prebaked=False) def main(args: typing.Sequence[str]) -> None: - """ - Example entrypoint, taking command-line arguments. + """Example entrypoint, taking command-line arguments. It is configured as a regular ROS 2 aware process. That is, no process-wide node, no background autoscaling multi-threaded executor, no log forwarding to the ROS 2 diff --git a/bdai_ros2_wrappers/examples/talker_listener_example.py b/bdai_ros2_wrappers/examples/talker_listener_example.py index 5834a14..73384cb 100644 --- a/bdai_ros2_wrappers/examples/talker_listener_example.py +++ b/bdai_ros2_wrappers/examples/talker_listener_example.py @@ -1,7 +1,6 @@ # Copyright (c) 2023 Boston Dynamics AI Institute Inc. All rights reserved. -""" -An example of a ROS 2 multi-node process using process-wide machinery. +"""An example of a ROS 2 multi-node process using process-wide machinery. Run with: @@ -51,8 +50,7 @@ def graph(**kwargs: typing.Any) -> typing.Iterable[Node]: @ros_process.main(prebaked=False, namespace=True) def main() -> None: - """ - Example entrypoint. + """Example entrypoint. It is configured almost as a regular ROS 2 aware process. That is, no process-wide node, no background autoscaling multi-threaded executor, and no log forwarding to the ROS 2 diff --git a/bdai_ros2_wrappers/examples/tf_cli_example.py b/bdai_ros2_wrappers/examples/tf_cli_example.py index fe04470..8bf4833 100644 --- a/bdai_ros2_wrappers/examples/tf_cli_example.py +++ b/bdai_ros2_wrappers/examples/tf_cli_example.py @@ -1,7 +1,6 @@ # Copyright (c) 2023 Boston Dynamics AI Institute Inc. All rights reserved. -""" -An example of a ROS 2 aware command using process-wide machinery. +"""An example of a ROS 2 aware command using process-wide machinery. Run with: @@ -95,8 +94,7 @@ def run(args: argparse.Namespace) -> None: @ros_process.main(cli(), prebaked=False) def main(args: argparse.Namespace) -> None: - """ - Example entrypoint. + """Example entrypoint. It is first configured as a regular ROS 2 aware process, but process-wide (i.e. globally accessible) executor and node are set immediately on start. @@ -109,10 +107,9 @@ def main(args: argparse.Namespace) -> None: and loaded, one of which is assigned as process-wide node. These are used indirectly by the actual console application. """ - with background(SingleThreadedExecutor()) as main.executor: - with ros_process.managed(graph, args) as (_, main.node): - main.tf_listener = TFListenerWrapper(main.node, cache_time_s=args.cache_time) - run(args) + with background(SingleThreadedExecutor()) as main.executor, ros_process.managed(graph, args) as (_, main.node): + main.tf_listener = TFListenerWrapper(main.node, cache_time_s=args.cache_time) + run(args) if __name__ == "__main__": diff --git a/bdai_ros2_wrappers/test/test_action_client.py b/bdai_ros2_wrappers/test/test_action_client.py index 54897fe..1c45e79 100644 --- a/bdai_ros2_wrappers/test/test_action_client.py +++ b/bdai_ros2_wrappers/test/test_action_client.py @@ -12,8 +12,7 @@ class FibonacciActionServer(ActionServer): - """ - Action server to used for testing mostly pulled from ROS2 Action Server tutorial + """Action server to used for testing mostly pulled from ROS2 Action Server tutorial Some changes made to allow special testing of timeouts and goal rejections """ @@ -40,9 +39,7 @@ def execute_callback(self, goal_handle: ServerGoalHandle) -> Fibonacci.Result: def test_send_goal_and_wait(ros: ROSAwareScope) -> None: - """ - Test standard operation of send_goal_and_wait - """ + """Test standard operation of send_goal_and_wait""" assert ros.node is not None FibonacciActionServer(ros.node, "fibonacci") action_client = ActionClientWrapper(Fibonacci, "fibonacci", ros.node) @@ -56,9 +53,7 @@ def test_send_goal_and_wait(ros: ROSAwareScope) -> None: def test_timeout_send_goal_wait(ros: ROSAwareScope) -> None: - """ - Test out the timeout of the send_goal_and_wait - """ + """Test out the timeout of the send_goal_and_wait""" assert ros.node is not None FibonacciActionServer(ros.node, "fibonacci") action_client = ActionClientWrapper(Fibonacci, "fibonacci", ros.node) @@ -70,14 +65,10 @@ def test_timeout_send_goal_wait(ros: ROSAwareScope) -> None: def test_goal_not_accepted(ros: ROSAwareScope) -> None: - """ - Test for the goal not accepted pathway should return None - """ + """Test for the goal not accepted pathway should return None""" def do_not_accept_goal(goal_request: Fibonacci.Goal) -> GoalResponse: - """ - Helper callback function for rejecting goals to help test - """ + """Helper callback function for rejecting goals to help test""" return GoalResponse.REJECT assert ros.node is not None diff --git a/bdai_ros2_wrappers/test/test_action_handle.py b/bdai_ros2_wrappers/test/test_action_handle.py index eb815a3..480e029 100644 --- a/bdai_ros2_wrappers/test/test_action_handle.py +++ b/bdai_ros2_wrappers/test/test_action_handle.py @@ -73,14 +73,17 @@ def _cancel_callback_accepted(cancel_request: Any) -> CancelResponse: class FibonacciActionServer(ActionServer): - """ - Action server to used for testing mostly pulled from ROS2 Action Server tutorial + """Action server to used for testing mostly pulled from ROS2 Action Server tutorial Some changes made to allow special testing of timeouts and goal rejections """ def __init__( - self, node: Node, name: str, execute_callback: Callable = _default_execute_callback, **kwargs: Any + self, + node: Node, + name: str, + execute_callback: Callable = _default_execute_callback, + **kwargs: Any, ) -> None: super().__init__(node, Fibonacci, name, execute_callback, **kwargs) @@ -107,7 +110,9 @@ class ActionHandleMocks: def do_send_goal( - action_client: ActionClient, goal: Action.Goal, label: Optional[str] = None + action_client: ActionClient, + goal: Action.Goal, + label: Optional[str] = None, ) -> Tuple[ActionHandle, ActionHandleMocks]: if label is None: label = inspect.stack()[1].function diff --git a/bdai_ros2_wrappers/test/test_executors.py b/bdai_ros2_wrappers/test/test_executors.py index 2033447..06ce02e 100644 --- a/bdai_ros2_wrappers/test/test_executors.py +++ b/bdai_ros2_wrappers/test/test_executors.py @@ -37,10 +37,7 @@ def ros_node(ros_context: Context) -> Generator[Node, None, None]: def test_autoscaling_thread_pool() -> None: - """ - Asserts that the autoscaling thread pool scales and de-scales on demand. - """ - + """Asserts that the autoscaling thread pool scales and de-scales on demand.""" with AutoScalingThreadPool(max_idle_time=2.0) as pool: assert len(pool.workers) == 0 assert not pool.working @@ -64,9 +61,7 @@ def predicate() -> bool: def test_autoscaling_thread_pool_checks_arguments() -> None: - """ - Asserts that the autoscaling thread pool checks for valid arguments on construction. - """ + """Asserts that the autoscaling thread pool checks for valid arguments on construction.""" with pytest.raises(ValueError): AutoScalingThreadPool(min_workers=-1) @@ -84,9 +79,7 @@ def test_autoscaling_thread_pool_checks_arguments() -> None: def test_autoscaling_thread_pool_when_shutdown() -> None: - """ - Asserts that the autoscaling thread no longer accepts work when shutdown. - """ + """Asserts that the autoscaling thread no longer accepts work when shutdown.""" pool = AutoScalingThreadPool() pool.shutdown() @@ -96,10 +89,7 @@ def test_autoscaling_thread_pool_when_shutdown() -> None: def test_autoscaling_thread_pool_with_limits() -> None: - """ - Asserts that the autoscaling thread pool enforces the user-defined range on the number of workers. - """ - + """Asserts that the autoscaling thread pool enforces the user-defined range on the number of workers.""" with AutoScalingThreadPool(min_workers=2, max_workers=5, max_idle_time=0.1) as pool: assert len(pool.workers) == 2 assert not pool.working @@ -122,10 +112,7 @@ def predicate() -> bool: def test_autoscaling_thread_pool_with_quota() -> None: - """ - Asserts that the autoscaling thread pool respects submission quotas. - """ - + """Asserts that the autoscaling thread pool respects submission quotas.""" with AutoScalingThreadPool(submission_quota=5, submission_patience=1.0, max_idle_time=2.0) as pool: assert len(pool.workers) == 0 assert not pool.working @@ -156,8 +143,7 @@ def predicate() -> bool: def test_autoscaling_executor(ros_context: Context, ros_node: Node) -> None: - """ - Asserts that the autoscaling multithreaded executor scales to attend a + """Asserts that the autoscaling multithreaded executor scales to attend a synchronous service call from a "one-shot" timer callback, serviced by the same executor. """ @@ -167,7 +153,10 @@ def dummy_server_callback(_: Trigger.Request, response: Trigger.Response) -> Tri return response ros_node.create_service( - Trigger, "/dummy/trigger", dummy_server_callback, callback_group=MutuallyExclusiveCallbackGroup() + Trigger, + "/dummy/trigger", + dummy_server_callback, + callback_group=MutuallyExclusiveCallbackGroup(), ) client = ros_node.create_client(Trigger, "/dummy/trigger", callback_group=MutuallyExclusiveCallbackGroup()) diff --git a/bdai_ros2_wrappers/test/test_integration.py b/bdai_ros2_wrappers/test/test_integration.py index 4101466..37b3ced 100644 --- a/bdai_ros2_wrappers/test/test_integration.py +++ b/bdai_ros2_wrappers/test/test_integration.py @@ -88,8 +88,7 @@ def ros_graph(ros: ROSAwareScope) -> None: def test_blocking_sequence(ros: ROSAwareScope) -> None: - """ - Asserts that a blocking call sequence (single-nested if you follow the execution path + """Asserts that a blocking call sequence (single-nested if you follow the execution path across callbacks) is possible when using a multi-threaded executor and callback isolation. """ assert ros.node is not None @@ -109,7 +108,8 @@ def blocking_sequence() -> TransformStamped: assert action_client.wait_for_server(timeout_sec=5) feedback = [] result = action_client.send_goal( - Fibonacci.Goal(order=response.sum), feedback_callback=lambda f: feedback.append(f.feedback) + Fibonacci.Goal(order=response.sum), + feedback_callback=lambda f: feedback.append(f.feedback), ).result assert len(feedback) > 0 partial_sequence = feedback[-1].sequence @@ -117,14 +117,20 @@ def blocking_sequence() -> TransformStamped: timeout = Duration(seconds=5) assert tf_buffer.can_transform( - MinimalTransformPublisher.frame_id, MinimalTransformPublisher.child_frame_id, Time(), timeout + MinimalTransformPublisher.frame_id, + MinimalTransformPublisher.child_frame_id, + Time(), + timeout, ) assert ros.node is not None time = ros.node.get_clock().now() time += Duration(seconds=result.sequence[-1] * 10e-3) return tf_buffer.lookup_transform( - MinimalTransformPublisher.frame_id, MinimalTransformPublisher.child_frame_id, time, timeout + MinimalTransformPublisher.frame_id, + MinimalTransformPublisher.child_frame_id, + time, + timeout, ) assert ros.executor is not None @@ -136,15 +142,15 @@ def blocking_sequence() -> TransformStamped: def test_chain_sequence(ros: ROSAwareScope) -> None: - """ - Asserts that a chained call sequence (double-nested if you follow the execution path + """Asserts that a chained call sequence (double-nested if you follow the execution path across callbacks) is possible when using a multi-threaded executor and callback isolation. """ assert ros.node is not None action_client = ActionClient(ros.node, Fibonacci, "compute_fibonacci_sequence") def add_fibonacci_sequences_server_callback( - request: AddTwoInts.Request, response: AddTwoInts.Response + request: AddTwoInts.Request, + response: AddTwoInts.Response, ) -> AddTwoInts.Response: if not action_client.wait_for_server(timeout_sec=5): response.sum = -1 diff --git a/bdai_ros2_wrappers/test/test_service_handle.py b/bdai_ros2_wrappers/test/test_service_handle.py index e5cd1ea..5d3d076 100644 --- a/bdai_ros2_wrappers/test/test_service_handle.py +++ b/bdai_ros2_wrappers/test/test_service_handle.py @@ -11,7 +11,9 @@ def do_request( - client: Client, request: SrvTypeRequest, label: Optional[str] = None + client: Client, + request: SrvTypeRequest, + label: Optional[str] = None, ) -> Tuple[bool, Optional[SrvTypeResponse]]: if label is None: label = inspect.stack()[1].function diff --git a/bdai_ros2_wrappers/test/test_single_goal_action_server.py b/bdai_ros2_wrappers/test/test_single_goal_action_server.py index 0c075b6..6a3f077 100644 --- a/bdai_ros2_wrappers/test/test_single_goal_action_server.py +++ b/bdai_ros2_wrappers/test/test_single_goal_action_server.py @@ -10,14 +10,10 @@ def test_single_goal_action_server(ros: ROSAwareScope) -> None: - """ - Tests normal operation of a single action server - """ + """Tests normal operation of a single action server""" def execute_callback(goal_handle: ServerGoalHandle) -> Fibonacci.Result: - """ - Executor for normal fibonacci sequence - """ + """Executor for normal fibonacci sequence""" sequence = [0, 1] for i in range(1, goal_handle.request.order): sequence.append(sequence[i] + sequence[i - 1]) diff --git a/bdai_ros2_wrappers/test/test_single_goal_multiple_action_servers.py b/bdai_ros2_wrappers/test/test_single_goal_multiple_action_servers.py index aae3abf..43ecd7a 100644 --- a/bdai_ros2_wrappers/test/test_single_goal_multiple_action_servers.py +++ b/bdai_ros2_wrappers/test/test_single_goal_multiple_action_servers.py @@ -13,9 +13,7 @@ def execute_callback(goal_handle: ServerGoalHandle) -> Fibonacci.Result: - """ - Executor callback for a server that does fibonacci - """ + """Executor callback for a server that does fibonacci""" sequence = [0, 1] for i in range(1, goal_handle.request.order): sequence.append(sequence[i] + sequence[i - 1]) @@ -28,9 +26,7 @@ def execute_callback(goal_handle: ServerGoalHandle) -> Fibonacci.Result: def execute_callback_wrong_fib(goal_handle: ServerGoalHandle) -> Fibonacci.Result: - """ - Different executor for another server that does fibonacci wrong - """ + """Different executor for another server that does fibonacci wrong""" # time delay to make interrupting easier time.sleep(1) sequence = [0, 1] @@ -65,11 +61,9 @@ def action_triplet( def test_actions_in_sequence( - action_triplet: Tuple[SingleGoalMultipleActionServers, ActionClientWrapper, ActionClientWrapper] + action_triplet: Tuple[SingleGoalMultipleActionServers, ActionClientWrapper, ActionClientWrapper], ) -> None: - """ - Tests out normal operation with multiple action servers and clients - """ + """Tests out normal operation with multiple action servers and clients""" _, action_client_a, action_client_b = action_triplet goal = Fibonacci.Goal() goal.order = 5 @@ -86,10 +80,10 @@ def test_actions_in_sequence( def test_action_interruption( - ros: ROSAwareScope, action_triplet: Tuple[SingleGoalMultipleActionServers, ActionClientWrapper, ActionClientWrapper] + ros: ROSAwareScope, + action_triplet: Tuple[SingleGoalMultipleActionServers, ActionClientWrapper, ActionClientWrapper], ) -> None: - """ - This test should start a delayed request from another client + """This test should start a delayed request from another client then make an immediate request to interrupt the last request. Due to the threading and reliance on sleeps this test might be diff --git a/bdai_ros2_wrappers/test/test_tf_listener_wrapper.py b/bdai_ros2_wrappers/test/test_tf_listener_wrapper.py index 3a6e6a9..a2f34e5 100644 --- a/bdai_ros2_wrappers/test/test_tf_listener_wrapper.py +++ b/bdai_ros2_wrappers/test/test_tf_listener_wrapper.py @@ -68,7 +68,8 @@ def test_non_existant_transform(ros: ROSAwareScope, tf_pair: Tuple[MockTfPublish def test_non_existant_transform_timeout( - ros: ROSAwareScope, tf_pair: Tuple[MockTfPublisherNode, TFListenerWrapper] + ros: ROSAwareScope, + tf_pair: Tuple[MockTfPublisherNode, TFListenerWrapper], ) -> None: tf_publisher, tf_listener = tf_pair assert ros.node is not None @@ -91,7 +92,8 @@ def test_existing_transform(ros: ROSAwareScope, tf_pair: Tuple[MockTfPublisherNo def test_future_transform_extrapolation_exception( - ros: ROSAwareScope, tf_pair: Tuple[MockTfPublisherNode, TFListenerWrapper] + ros: ROSAwareScope, + tf_pair: Tuple[MockTfPublisherNode, TFListenerWrapper], ) -> None: tf_publisher, tf_listener = tf_pair assert ros.node is not None @@ -105,7 +107,8 @@ def test_future_transform_extrapolation_exception( def test_future_transform_insufficient_wait( - ros: ROSAwareScope, tf_pair: Tuple[MockTfPublisherNode, TFListenerWrapper] + ros: ROSAwareScope, + tf_pair: Tuple[MockTfPublisherNode, TFListenerWrapper], ) -> None: tf_publisher, tf_listener = tf_pair assert ros.node is not None @@ -168,6 +171,9 @@ def delayed_publish() -> None: ros.executor.create_task(delayed_publish) latest_timestamp = tf_listener.lookup_latest_timestamp( - FRAME_ID, CHILD_FRAME_ID, timeout_sec=2.0, wait_for_frames=True + FRAME_ID, + CHILD_FRAME_ID, + timeout_sec=2.0, + wait_for_frames=True, ) assert latest_timestamp == timestamp diff --git a/configs/ruff.toml b/configs/ruff.toml index 3ef8f55..0e4406f 100644 --- a/configs/ruff.toml +++ b/configs/ruff.toml @@ -1,6 +1,6 @@ -# Enable pycodestyle (`E`), Pyflakes (`F`), and import sorting (`I`) -select = ["E", "F", "I"] -ignore = [] +# See https://docs.astral.sh/ruff/rules/ for ruff rules +select = ["A", "B", "COM", "D101", "D102", "D103", "D2", "D3", "D402", "D417", "D419", "E", "ERA", "F", "I", "NPY", "RET", "RUF100", "SIM"] +ignore = ["D203", "D213"] # Allow autofix for all enabled rules (when `--fix`) is provided. fixable = ["A", "B", "C", "D", "E", "F", "G", "I", "N", "Q", "S", "T", "W", "ANN", "ARG", "BLE", "COM", "DJ", "DTZ", "EM", "ERA", "EXE", "FBT", "ICN", "INP", "ISC", "NPY", "PD", "PGH", "PIE", "PL", "PT", "PTH", "PYI", "RET", "RSE", "RUF", "SIM", "SLF", "TCH", "TID", "TRY", "UP", "YTT"] @@ -44,6 +44,13 @@ target-version = "py310" [per-file-ignores] "__init__.py" = ["F401"] +# We don't require docstrings in tests +"**/conftest.py" = ["D"] +"**/test_*.py" = ["D"] +"proto2ros_tests/*" = ["D"] + +"bdai_ros2_wrappers/examples/*" = ["D"] + [mccabe] # Unlike Flake8, default to a complexity level of 10. max-complexity = 10 diff --git a/proto2ros/proto2ros/cli/generate.py b/proto2ros/proto2ros/cli/generate.py index 563cf45..99b6545 100644 --- a/proto2ros/proto2ros/cli/generate.py +++ b/proto2ros/proto2ros/cli/generate.py @@ -25,6 +25,7 @@ def do_generate(args: argparse.Namespace) -> int: + """Primary function to execute conversion of protobufs to ros msgs.""" # Fetch baseline configuration. config = Configuration.from_file(args.config_file) @@ -77,8 +78,8 @@ def do_generate(args: argparse.Namespace) -> int: f"{spec.annotations['proto-type']} maps to {spec.base_type}" for spec in known_message_specifications if spec.base_type in message_type_duplicates - ] - ) + ], + ), ), " ", ), @@ -109,7 +110,7 @@ def do_generate(args: argparse.Namespace) -> int: conversions_python_file = args.output_directory / "conversions.py" if not args.dry: conversions_python_file.write_text( - dump_conversions_python_module(message_specifications, known_message_specifications, config) + "\n" + dump_conversions_python_module(message_specifications, known_message_specifications, config) + "\n", ) files_written.append(conversions_python_file) @@ -120,9 +121,14 @@ def do_generate(args: argparse.Namespace) -> int: def main() -> int: + """Entrypoint for proto2ros""" parser = argparse.ArgumentParser(description="Generate Protobuf <-> ROS 2 interoperability interfaces") parser.add_argument( - "-O", "--output-directory", type=pathlib.Path, default=".", help="Output directory for all generated files." + "-O", + "--output-directory", + type=pathlib.Path, + default=".", + help="Output directory for all generated files.", ) parser.add_argument( "-c", diff --git a/proto2ros/proto2ros/configuration/__init__.py b/proto2ros/proto2ros/configuration/__init__.py index 6ff48ba..7bf6518 100644 --- a/proto2ros/proto2ros/configuration/__init__.py +++ b/proto2ros/proto2ros/configuration/__init__.py @@ -12,8 +12,7 @@ @dataclasses.dataclass class Configuration: - """ - Mutable Protobuf <-> ROS configuration. + """Mutable Protobuf <-> ROS configuration. Attributes: diff --git a/proto2ros/proto2ros/conversions/basic.py b/proto2ros/proto2ros/conversions/basic.py index 44e193b..9340b99 100644 --- a/proto2ros/proto2ros/conversions/basic.py +++ b/proto2ros/proto2ros/conversions/basic.py @@ -19,8 +19,7 @@ @convert.register(proto2ros.msg.AnyProto, object) def convert_proto2ros_any_proto_message_to_some_proto(ros_msg: proto2ros.msg.AnyProto, proto_msg: Any) -> None: - """ - Unpacks a proto2ros/AnyProto ROS message into any Protobuf message. + """Unpacks a proto2ros/AnyProto ROS message into any Protobuf message. Raises: ValueError: if the given ROS message cannot be unpacked onto the given Protobuf message. @@ -50,7 +49,8 @@ def _(proto_msg: proto2ros.msg.AnyProto, ros_msg: proto2ros.msg.AnyProto) -> Non @convert.register(proto2ros.msg.AnyProto, google.protobuf.any_pb2.Any) def convert_proto2ros_any_proto_message_to_google_protobuf_any_proto( - ros_msg: proto2ros.msg.AnyProto, proto_msg: google.protobuf.any_pb2.Any + ros_msg: proto2ros.msg.AnyProto, + proto_msg: google.protobuf.any_pb2.Any, ) -> None: """Converts from proto2ros/AnyProto ROS message to google.protobuf.Any Protobuf messages.""" proto_msg.Clear() @@ -60,7 +60,8 @@ def convert_proto2ros_any_proto_message_to_google_protobuf_any_proto( @convert.register(google.protobuf.any_pb2.Any, proto2ros.msg.AnyProto) def convert_google_protobuf_any_proto_to_proto2ros_any_proto_message( - proto_msg: google.protobuf.any_pb2.Any, ros_msg: proto2ros.msg.AnyProto + proto_msg: google.protobuf.any_pb2.Any, + ros_msg: proto2ros.msg.AnyProto, ) -> None: """Converts from google.protobuf.Any Protobuf messages to proto2ros/AnyProto ROS messages.""" ros_msg.type_url = proto_msg.type_url @@ -69,7 +70,8 @@ def convert_google_protobuf_any_proto_to_proto2ros_any_proto_message( @convert.register(builtin_interfaces.msg.Duration, google.protobuf.duration_pb2.Duration) def convert_builtin_interfaces_duration_message_to_google_protobuf_duration_proto( - ros_msg: builtin_interfaces.msg.Duration, proto_msg: google.protobuf.duration_pb2.Duration + ros_msg: builtin_interfaces.msg.Duration, + proto_msg: google.protobuf.duration_pb2.Duration, ) -> None: """Converts from google.protobuf.Any Protobuf messages to proto2ros/AnyProto ROS messages.""" proto_msg.seconds = ros_msg.sec @@ -83,7 +85,8 @@ def convert_builtin_interfaces_duration_message_to_google_protobuf_duration_prot @convert.register(google.protobuf.duration_pb2.Duration, builtin_interfaces.msg.Duration) def convert_google_protobuf_duration_proto_to_builtin_interfaces_duration_message( - proto_msg: google.protobuf.duration_pb2.Duration, ros_msg: builtin_interfaces.msg.Duration + proto_msg: google.protobuf.duration_pb2.Duration, + ros_msg: builtin_interfaces.msg.Duration, ) -> None: """Converts from google.protobuf.Duration Protobuf messages to builtin_interfaces/Duration ROS messages.""" ros_msg.sec = proto_msg.seconds @@ -97,7 +100,8 @@ def convert_google_protobuf_duration_proto_to_builtin_interfaces_duration_messag @convert.register(builtin_interfaces.msg.Time, google.protobuf.timestamp_pb2.Timestamp) def convert_builtin_interfaces_time_message_to_google_protobuf_timestamp_proto( - ros_msg: builtin_interfaces.msg.Time, proto_msg: google.protobuf.timestamp_pb2.Timestamp + ros_msg: builtin_interfaces.msg.Time, + proto_msg: google.protobuf.timestamp_pb2.Timestamp, ) -> None: """Converts from builtin_interfaces/Time ROS messages to google.protobuf.Timestamp Protobuf messages.""" proto_msg.seconds = ros_msg.sec @@ -109,7 +113,8 @@ def convert_builtin_interfaces_time_message_to_google_protobuf_timestamp_proto( @convert.register(google.protobuf.timestamp_pb2.Timestamp, builtin_interfaces.msg.Time) def convert_google_protobuf_timestamp_proto_to_builtin_interfaces_time_message( - proto_msg: google.protobuf.timestamp_pb2.Timestamp, ros_msg: builtin_interfaces.msg.Time + proto_msg: google.protobuf.timestamp_pb2.Timestamp, + ros_msg: builtin_interfaces.msg.Time, ) -> None: """Converts from google.protobuf.Timestamp Protobuf messages to builtin_interfaces/Time ROS messages.""" ros_msg.sec = proto_msg.seconds @@ -121,7 +126,8 @@ def convert_google_protobuf_timestamp_proto_to_builtin_interfaces_time_message( @convert.register(std_msgs.msg.Float64, google.protobuf.wrappers_pb2.DoubleValue) def convert_std_msgs_float64_message_to_google_protobuf_double_value_proto( - ros_msg: std_msgs.msg.Float64, proto_msg: google.protobuf.wrappers_pb2.DoubleValue + ros_msg: std_msgs.msg.Float64, + proto_msg: google.protobuf.wrappers_pb2.DoubleValue, ) -> None: """Converts from std_msgs/Float64 ROS messages to google.protobuf.DoubleValue Protobuf messages.""" proto_msg.value = ros_msg.data @@ -132,7 +138,8 @@ def convert_std_msgs_float64_message_to_google_protobuf_double_value_proto( @convert.register(google.protobuf.wrappers_pb2.DoubleValue, std_msgs.msg.Float64) def convert_google_protobuf_double_value_proto_to_std_msgs_float64_message( - proto_msg: google.protobuf.wrappers_pb2.DoubleValue, ros_msg: std_msgs.msg.Float64 + proto_msg: google.protobuf.wrappers_pb2.DoubleValue, + ros_msg: std_msgs.msg.Float64, ) -> None: """Converts from google.protobuf.DoubleValue Protobuf messages to std_msgs/Float64 ROS messages.""" ros_msg.data = proto_msg.value @@ -143,7 +150,8 @@ def convert_google_protobuf_double_value_proto_to_std_msgs_float64_message( @convert.register(std_msgs.msg.Float32, google.protobuf.wrappers_pb2.FloatValue) def convert_std_msgs_float32_message_to_google_protobuf_float_value_proto( - ros_msg: std_msgs.msg.Float32, proto_msg: google.protobuf.wrappers_pb2.FloatValue + ros_msg: std_msgs.msg.Float32, + proto_msg: google.protobuf.wrappers_pb2.FloatValue, ) -> None: """Converts from std_msgs/Float32 ROS messages to google.protobuf.FloatValue Protobuf messages.""" proto_msg.value = ros_msg.data @@ -154,7 +162,8 @@ def convert_std_msgs_float32_message_to_google_protobuf_float_value_proto( @convert.register(google.protobuf.wrappers_pb2.FloatValue, std_msgs.msg.Float32) def convert_google_protobuf_float_value_proto_to_std_msgs_float32_message( - proto_msg: google.protobuf.wrappers_pb2.FloatValue, ros_msg: std_msgs.msg.Float32 + proto_msg: google.protobuf.wrappers_pb2.FloatValue, + ros_msg: std_msgs.msg.Float32, ) -> None: """Converts from google.protobuf.FloatValue Protobuf messages to std_msgs/Float32 ROS messages.""" ros_msg.data = proto_msg.value @@ -165,7 +174,8 @@ def convert_google_protobuf_float_value_proto_to_std_msgs_float32_message( @convert.register(std_msgs.msg.Int64, google.protobuf.wrappers_pb2.Int64Value) def convert_std_msgs_int64_message_to_google_protobuf_int64_value_proto( - ros_msg: std_msgs.msg.Int64, proto_msg: google.protobuf.wrappers_pb2.Int64Value + ros_msg: std_msgs.msg.Int64, + proto_msg: google.protobuf.wrappers_pb2.Int64Value, ) -> None: """Converts from std_msgs/Int64 ROS messages to google.protobuf.Int64Value Protobuf messages.""" proto_msg.value = ros_msg.data @@ -176,7 +186,8 @@ def convert_std_msgs_int64_message_to_google_protobuf_int64_value_proto( @convert.register(google.protobuf.wrappers_pb2.Int64Value, std_msgs.msg.Int64) def convert_google_protobuf_int64_value_proto_to_std_msgs_int64_message( - proto_msg: google.protobuf.wrappers_pb2.Int64Value, ros_msg: std_msgs.msg.Int64 + proto_msg: google.protobuf.wrappers_pb2.Int64Value, + ros_msg: std_msgs.msg.Int64, ) -> None: """Converts from google.protobuf.Int64Value Protobuf messages to std_msgs/Int64 ROS messages.""" ros_msg.data = proto_msg.value @@ -187,7 +198,8 @@ def convert_google_protobuf_int64_value_proto_to_std_msgs_int64_message( @convert.register(std_msgs.msg.Int32, google.protobuf.wrappers_pb2.Int32Value) def convert_std_msgs_int32_message_to_google_protobuf_int32_value_proto( - ros_msg: std_msgs.msg.Int32, proto_msg: google.protobuf.wrappers_pb2.Int32Value + ros_msg: std_msgs.msg.Int32, + proto_msg: google.protobuf.wrappers_pb2.Int32Value, ) -> None: """Converts from std_msgs/Int32 ROS messages to google.protobuf.Int32Value Protobuf messages.""" proto_msg.value = ros_msg.data @@ -198,7 +210,8 @@ def convert_std_msgs_int32_message_to_google_protobuf_int32_value_proto( @convert.register(google.protobuf.wrappers_pb2.Int32Value, std_msgs.msg.Int32) def convert_google_protobuf_int32_value_proto_to_std_msgs_int32_message( - proto_msg: google.protobuf.wrappers_pb2.Int32Value, ros_msg: std_msgs.msg.Int32 + proto_msg: google.protobuf.wrappers_pb2.Int32Value, + ros_msg: std_msgs.msg.Int32, ) -> None: """Converts from google.protobuf.Int32Value Protobuf messages to std_msgs/Int32 ROS messages.""" ros_msg.data = proto_msg.value @@ -209,7 +222,8 @@ def convert_google_protobuf_int32_value_proto_to_std_msgs_int32_message( @convert.register(std_msgs.msg.UInt64, google.protobuf.wrappers_pb2.UInt64Value) def convert_std_msgs_uint64_message_to_google_protobuf_uint64_value_proto( - ros_msg: std_msgs.msg.UInt64, proto_msg: google.protobuf.wrappers_pb2.UInt64Value + ros_msg: std_msgs.msg.UInt64, + proto_msg: google.protobuf.wrappers_pb2.UInt64Value, ) -> None: """Converts from std_msgs/UInt64 ROS messages to google.protobuf.UInt64Value Protobuf messages.""" proto_msg.value = ros_msg.data @@ -220,7 +234,8 @@ def convert_std_msgs_uint64_message_to_google_protobuf_uint64_value_proto( @convert.register(google.protobuf.wrappers_pb2.UInt64Value, std_msgs.msg.UInt64) def convert_google_protobuf_uint64_value_proto_to_std_msgs_uint64_message( - proto_msg: google.protobuf.wrappers_pb2.UInt64Value, ros_msg: std_msgs.msg.UInt64 + proto_msg: google.protobuf.wrappers_pb2.UInt64Value, + ros_msg: std_msgs.msg.UInt64, ) -> None: """Converts from google.protobuf.UInt64Value Protobuf messages to std_msgs/UInt64 ROS messages.""" ros_msg.data = proto_msg.value @@ -231,7 +246,8 @@ def convert_google_protobuf_uint64_value_proto_to_std_msgs_uint64_message( @convert.register(std_msgs.msg.UInt32, google.protobuf.wrappers_pb2.UInt32Value) def convert_std_msgs_uint32_message_to_google_protobuf_uint32_value_proto( - ros_msg: std_msgs.msg.UInt32, proto_msg: google.protobuf.wrappers_pb2.UInt32Value + ros_msg: std_msgs.msg.UInt32, + proto_msg: google.protobuf.wrappers_pb2.UInt32Value, ) -> None: """Converts from std_msgs/UInt32 ROS messages to google.protobuf.UInt32Value Protobuf messages.""" proto_msg.value = ros_msg.data @@ -242,7 +258,8 @@ def convert_std_msgs_uint32_message_to_google_protobuf_uint32_value_proto( @convert.register(google.protobuf.wrappers_pb2.UInt32Value, std_msgs.msg.UInt32) def convert_google_protobuf_uint32_value_proto_to_std_msgs_uint32_message( - proto_msg: google.protobuf.wrappers_pb2.UInt32Value, ros_msg: std_msgs.msg.UInt32 + proto_msg: google.protobuf.wrappers_pb2.UInt32Value, + ros_msg: std_msgs.msg.UInt32, ) -> None: """Converts from google.protobuf.UInt32Value Protobuf messages to std_msgs/UInt32 ROS messages.""" ros_msg.data = proto_msg.value @@ -253,7 +270,8 @@ def convert_google_protobuf_uint32_value_proto_to_std_msgs_uint32_message( @convert.register(std_msgs.msg.Bool, google.protobuf.wrappers_pb2.BoolValue) def convert_std_msgs_bool_message_to_google_protobuf_bool_value_proto( - ros_msg: std_msgs.msg.Bool, proto_msg: google.protobuf.wrappers_pb2.BoolValue + ros_msg: std_msgs.msg.Bool, + proto_msg: google.protobuf.wrappers_pb2.BoolValue, ) -> None: """Converts from std_msgs/Bool ROS messages to google.protobuf.BoolValue Protobuf messages.""" proto_msg.value = ros_msg.data @@ -264,7 +282,8 @@ def convert_std_msgs_bool_message_to_google_protobuf_bool_value_proto( @convert.register(google.protobuf.wrappers_pb2.BoolValue, std_msgs.msg.Bool) def convert_google_protobuf_bool_value_proto_to_std_msgs_bool_message( - proto_msg: google.protobuf.wrappers_pb2.BoolValue, ros_msg: std_msgs.msg.Bool + proto_msg: google.protobuf.wrappers_pb2.BoolValue, + ros_msg: std_msgs.msg.Bool, ) -> None: """Converts from google.protobuf.BoolValue Protobuf messages to std_msgs/Bool ROS messages.""" ros_msg.data = proto_msg.value @@ -275,7 +294,8 @@ def convert_google_protobuf_bool_value_proto_to_std_msgs_bool_message( @convert.register(std_msgs.msg.String, google.protobuf.wrappers_pb2.StringValue) def convert_std_msgs_string_message_to_google_protobuf_string_value_proto( - ros_msg: std_msgs.msg.String, proto_msg: google.protobuf.wrappers_pb2.StringValue + ros_msg: std_msgs.msg.String, + proto_msg: google.protobuf.wrappers_pb2.StringValue, ) -> None: """Converts from std_msgs/String ROS messages to google.protobuf.StringValue Protobuf messages.""" proto_msg.value = ros_msg.data @@ -286,7 +306,8 @@ def convert_std_msgs_string_message_to_google_protobuf_string_value_proto( @convert.register(google.protobuf.wrappers_pb2.StringValue, std_msgs.msg.String) def convert_google_protobuf_string_value_proto_to_std_msgs_string_message( - proto_msg: google.protobuf.wrappers_pb2.StringValue, ros_msg: std_msgs.msg.String + proto_msg: google.protobuf.wrappers_pb2.StringValue, + ros_msg: std_msgs.msg.String, ) -> None: """Converts from google.protobuf.StringValue Protobuf messages to std_msgs/String ROS messages.""" ros_msg.data = proto_msg.value @@ -297,7 +318,8 @@ def convert_google_protobuf_string_value_proto_to_std_msgs_string_message( @convert.register(proto2ros.msg.Bytes, google.protobuf.wrappers_pb2.BytesValue) def convert_proto2ros_bytes_message_to_google_protobuf_bytes_value_proto( - ros_msg: proto2ros.msg.Bytes, proto_msg: google.protobuf.wrappers_pb2.BytesValue + ros_msg: proto2ros.msg.Bytes, + proto_msg: google.protobuf.wrappers_pb2.BytesValue, ) -> None: """Converts from proto2ros/Bytes ROS messages to google.protobuf.BytesValue Protobuf messages.""" proto_msg.value = ros_msg.data.tobytes() @@ -308,7 +330,8 @@ def convert_proto2ros_bytes_message_to_google_protobuf_bytes_value_proto( @convert.register(google.protobuf.wrappers_pb2.BytesValue, proto2ros.msg.Bytes) def convert_google_protobuf_bytes_value_proto_to_proto2ros_bytes_message( - proto_msg: google.protobuf.wrappers_pb2.BytesValue, ros_msg: proto2ros.msg.Bytes + proto_msg: google.protobuf.wrappers_pb2.BytesValue, + ros_msg: proto2ros.msg.Bytes, ) -> None: """Converts from google.protobuf.BytesValue Protobuf messages to proto2ros/Bytes ROS messages.""" ros_msg.data = proto_msg.value @@ -319,7 +342,8 @@ def convert_google_protobuf_bytes_value_proto_to_proto2ros_bytes_message( @convert.register(proto2ros.msg.Value, google.protobuf.struct_pb2.Value) def convert_proto2ros_value_message_to_google_protobuf_value_proto( - ros_msg: proto2ros.msg.Value, proto_msg: google.protobuf.struct_pb2.Value + ros_msg: proto2ros.msg.Value, + proto_msg: google.protobuf.struct_pb2.Value, ) -> None: """Converts from proto2ros/Value ROS messages to google.protobuf.Value Protobuf messages.""" match ros_msg.kind: @@ -332,24 +356,28 @@ def convert_proto2ros_value_message_to_google_protobuf_value_proto( case proto2ros.msg.Value.STRUCT_VALUE_SET: if proto_msg.struct_value.type_name != "proto2ros/Struct": raise ValueError( - f"expected proto2ros/Struct message for struct_value member, got {proto_msg.struct_value.type}" + f"expected proto2ros/Struct message for struct_value member, got {proto_msg.struct_value.type}", ) typed_field_message = rclpy.serialization.deserialize_message( - proto_msg.struct_value.value.tobytes(), proto2ros.msg.Struct + proto_msg.struct_value.value.tobytes(), + proto2ros.msg.Struct, ) convert_proto2ros_struct_message_to_google_protobuf_struct_proto( - typed_field_message, proto_msg.struct_value + typed_field_message, + proto_msg.struct_value, ) case proto2ros.msg.Value.LIST_VALUE_SET: if proto_msg.list_value.type_name != "proto2ros/List": raise ValueError( - f"expected proto2ros/Struct message for list_value member, got {proto_msg.list_value.type}" + f"expected proto2ros/Struct message for list_value member, got {proto_msg.list_value.type}", ) typed_field_message = rclpy.serialization.deserialize_message( - proto_msg.list_value.value.tobytes(), proto2ros.msg.List + proto_msg.list_value.value.tobytes(), + proto2ros.msg.List, ) convert_proto2ros_list_message_to_google_protobuf_list_value_proto( - typed_field_message, proto_msg.list_value + typed_field_message, + proto_msg.list_value, ) case proto2ros.msg.Value.NO_VALUE_SET: proto_msg.null_value = google.protobuf.struct_pb2.NullValue.NULL_VALUE @@ -362,7 +390,8 @@ def convert_proto2ros_value_message_to_google_protobuf_value_proto( @convert.register(google.protobuf.struct_pb2.Value, proto2ros.msg.Value) def convert_google_protobuf_value_proto_to_proto2ros_value_message( - proto_msg: google.protobuf.struct_pb2.Value, ros_msg: proto2ros.msg.Value + proto_msg: google.protobuf.struct_pb2.Value, + ros_msg: proto2ros.msg.Value, ) -> None: """Converts from google.protobuf.Value Protobuf messages to proto2ros/Value ROS messages.""" match proto_msg.WhichOneOf("kind"): @@ -380,7 +409,8 @@ def convert_google_protobuf_value_proto_to_proto2ros_value_message( case "struct_value": typed_struct_message = proto2ros.msg.Struct() convert_google_protobuf_struct_proto_to_proto2ros_struct_message( - proto_msg.struct_value, typed_struct_message + proto_msg.struct_value, + typed_struct_message, ) ros_msg.struct_value.value = rclpy.serialization.serialize_message(typed_struct_message) ros_msg.struct_value.type_name = "proto2ros/Struct" @@ -400,7 +430,8 @@ def convert_google_protobuf_value_proto_to_proto2ros_value_message( @convert.register(proto2ros.msg.List, google.protobuf.struct_pb2.ListValue) def convert_proto2ros_list_message_to_google_protobuf_list_value_proto( - ros_msg: proto2ros.msg.List, proto_msg: google.protobuf.struct_pb2.ListValue + ros_msg: proto2ros.msg.List, + proto_msg: google.protobuf.struct_pb2.ListValue, ) -> None: """Converts from proto2ros/List ROS messages to google.protobuf.ListValue Protobuf messages.""" proto_msg.Clear() @@ -414,7 +445,8 @@ def convert_proto2ros_list_message_to_google_protobuf_list_value_proto( @convert.register(google.protobuf.struct_pb2.ListValue, proto2ros.msg.List) def convert_google_protobuf_list_value_proto_to_proto2ros_list_message( - proto_msg: google.protobuf.struct_pb2.ListValue, ros_msg: proto2ros.msg.List + proto_msg: google.protobuf.struct_pb2.ListValue, + ros_msg: proto2ros.msg.List, ) -> None: """Converts from google.protobuf.ListValue Protobuf messages to proto2ros/List ROS messages.""" for input_item in proto_msg.values: @@ -428,7 +460,8 @@ def convert_google_protobuf_list_value_proto_to_proto2ros_list_message( @convert.register(proto2ros.msg.Struct, google.protobuf.struct_pb2.Struct) def convert_proto2ros_struct_message_to_google_protobuf_struct_proto( - ros_msg: proto2ros.msg.Struct, proto_msg: google.protobuf.struct_pb2.Struct + ros_msg: proto2ros.msg.Struct, + proto_msg: google.protobuf.struct_pb2.Struct, ) -> None: """Converts from proto2ros/Struct ROS messages to google.protobuf.Struct Protobuf messages.""" proto_msg.Clear() @@ -441,7 +474,8 @@ def convert_proto2ros_struct_message_to_google_protobuf_struct_proto( @convert.register(google.protobuf.struct_pb2.Struct, proto2ros.msg.Struct) def convert_google_protobuf_struct_proto_to_proto2ros_struct_message( - proto_msg: google.protobuf.struct_pb2.Struct, ros_msg: proto2ros.msg.Struct + proto_msg: google.protobuf.struct_pb2.Struct, + ros_msg: proto2ros.msg.Struct, ) -> None: """Converts from google.protobuf.Struct Protobuf messages to proto2ros/Struct ROS messages.""" for key, value in proto_msg.fields.items(): diff --git a/proto2ros/proto2ros/dependencies.py b/proto2ros/proto2ros/dependencies.py index a52cf7f..1b20741 100644 --- a/proto2ros/proto2ros/dependencies.py +++ b/proto2ros/proto2ros/dependencies.py @@ -1,8 +1,6 @@ # Copyright (c) 2023 Boston Dynamics AI Institute LLC. All rights reserved. -""" -This module provides APIs to manipulate dependencies between Protobuf <-> ROS message equivalences. -""" +"""This module provides APIs to manipulate dependencies between Protobuf <-> ROS message equivalences.""" import warnings from typing import List @@ -14,8 +12,7 @@ def message_dependency_graph(message_specs: List[MessageSpecification]) -> nx.DiGraph: - """ - Returns the dependency graph for the given ROS message specifications. + """Returns the dependency graph for the given ROS message specifications. This dependency graph is a directed multi-graph where message types make up nodes and composition relationships (has-a) make up edges. Nodes are annotated with the @@ -33,8 +30,7 @@ def message_dependency_graph(message_specs: List[MessageSpecification]) -> nx.Di def fix_dependency_cycles(message_specs: List[MessageSpecification], quiet: bool = True) -> None: - """ - Fixes dependency cycles among ROS message specifications. + """Fixes dependency cycles among ROS message specifications. ROS messages do not support recursive definitions, this functions works around this limitation by type erasing the thinnest link (least number of offending fields) for @@ -46,7 +42,7 @@ def fix_dependency_cycles(message_specs: List[MessageSpecification], quiet: bool if not quiet: message_types = [dependency_graph.nodes[node]["message"].base_type for node in cycle] dependency_cycle_depiction = " -> ".join(str(type_) for type_ in message_types) - warnings.warn("Dependency cycle found: " + dependency_cycle_depiction) + warnings.warn("Dependency cycle found: " + dependency_cycle_depiction, stacklevel=1) explicit_edges = [] for parent, child in pairwise(cycle): @@ -59,5 +55,5 @@ def fix_dependency_cycles(message_specs: List[MessageSpecification], quiet: bool field = data["field"] if not quiet: message_type = dependency_graph.nodes[parent]["message"].base_type - warnings.warn(f"Type erasing {field.name} member in {message_type} to break recursion") + warnings.warn(f"Type erasing {field.name} member in {message_type} to break recursion", stacklevel=1) field.annotations["type-erased"] = True diff --git a/proto2ros/proto2ros/descriptors/sources.py b/proto2ros/proto2ros/descriptors/sources.py index 8631b41..da30459 100644 --- a/proto2ros/proto2ros/descriptors/sources.py +++ b/proto2ros/proto2ros/descriptors/sources.py @@ -11,8 +11,7 @@ @functools.singledispatch def read_source_descriptors(source: Any) -> Iterable[FileDescriptorProto]: - """ - Reads Protobuf file source descriptors. + """Reads Protobuf file source descriptors. Note this function operates as the entrypoint to all corresponding overloads (via single dispatch). @@ -27,11 +26,10 @@ def read_source_descriptors(source: Any) -> Iterable[FileDescriptorProto]: @read_source_descriptors.register def read_source_descriptors_from_bytes(blob: bytes) -> Iterable[FileDescriptorProto]: - """ - Reads Protobuf file source descriptors from a binary blob. + """Reads Protobuf file source descriptors from a binary blob. Args: - source: a binary blob, typically read from a .desc file. + blob: a binary blob, typically read from a .desc file. Returns: an iterable over all file source descriptors found. @@ -43,8 +41,7 @@ def read_source_descriptors_from_bytes(blob: bytes) -> Iterable[FileDescriptorPr @read_source_descriptors.register def read_source_descriptors_from_file(path: os.PathLike) -> Iterable[FileDescriptorProto]: - """ - Reads Protobuf file source descriptors from binary file. + """Reads Protobuf file source descriptors from binary file. Args: path: path to binary file, typically a .desc file. diff --git a/proto2ros/proto2ros/descriptors/utilities.py b/proto2ros/proto2ros/descriptors/utilities.py index 06ca6f9..9d30aab 100644 --- a/proto2ros/proto2ros/descriptors/utilities.py +++ b/proto2ros/proto2ros/descriptors/utilities.py @@ -1,7 +1,6 @@ # Copyright (c) 2023 Boston Dynamics AI Institute LLC. All rights reserved. -""" -This module provides utilities to work with Protobuf descriptors. +"""This module provides utilities to work with Protobuf descriptors. Many of these utilities trade in terms of paths and locations. @@ -36,8 +35,7 @@ def index_source_code_locations(file_descriptor: FileDescriptorProto) -> Dict[Tu def walk(proto: Any, path: Sequence[int]) -> Iterable[Any]: - """ - Iterates a Protobuf message down a given path. + """Iterates a Protobuf message down a given path. Args: proto: a Protobuf message instance to visit. @@ -56,8 +54,7 @@ def walk(proto: Any, path: Sequence[int]) -> Iterable[Any]: def locate_repeated(member: str, proto: Any) -> Iterable[Tuple[Sequence[int], Any]]: - """ - Iterates over items of a repeated Protobuf message member, also yield their local paths. + """Iterates over items of a repeated Protobuf message member, also yield their local paths. Local paths are tuples of member field number and item index. @@ -78,10 +75,11 @@ def locate_repeated(member: str, proto: Any) -> Iterable[Tuple[Sequence[int], An def resolve( - source: FileDescriptorProto, path: Iterable[int], root: Optional[SourceCodeInfo.Location] = None + source: FileDescriptorProto, + path: Iterable[int], + root: Optional[SourceCodeInfo.Location] = None, ) -> SourceCodeInfo.Location: - """ - Resolves a source path to a location. + """Resolves a source path to a location. Args: source: source file descriptor. @@ -103,8 +101,7 @@ def resolve( def protofqn(source: FileDescriptorProto, location: SourceCodeInfo.Location) -> str: - """ - Returns the fully qualified name of a Protobuf composite type. + """Returns the fully qualified name of a Protobuf composite type. This type is to be found at a given `location` in a given `source` file. """ diff --git a/proto2ros/proto2ros/equivalences.py b/proto2ros/proto2ros/equivalences.py index 2cecdb4..38acb55 100644 --- a/proto2ros/proto2ros/equivalences.py +++ b/proto2ros/proto2ros/equivalences.py @@ -1,7 +1,6 @@ # Copyright (c) 2023 Boston Dynamics AI Institute LLC. All rights reserved. -""" -This module provides APIs to extract Protobuf <-> ROS message equivalences. +"""This module provides APIs to extract Protobuf <-> ROS message equivalences. These equivalences are defined in terms of Protobuf composite descriptors and ROS message specifications. See Protobuf descriptor messages and ROS 2 @@ -35,8 +34,7 @@ @dataclasses.dataclass class Equivalence: - """ - An equivalence relation between a Protobuf composite (message or enum) and a ROS message. + """An equivalence relation between a Protobuf composite (message or enum) and a ROS message. More than one ROS message specification may be required to represent a single Protobuf composite. Auxiliary message specifications may be listed in that case. @@ -76,10 +74,12 @@ def extract_leading_comments(location: SourceCodeInfo.Location) -> str: @functools.singledispatch def compute_equivalence( - descriptor: Any, source: FileDescriptorProto, location: SourceCodeInfo.Location, config: Configuration + descriptor: Any, + source: FileDescriptorProto, + location: SourceCodeInfo.Location, + config: Configuration, ) -> Equivalence: - """ - Computes a suitable equivalence relation for some Protobuf composite type. + """Computes a suitable equivalence relation for some Protobuf composite type. Note this function operates as the entrypoint to all corresponding overloads (via single dispatch). @@ -102,8 +102,7 @@ def compute_equivalence_for_enum( location: SourceCodeInfo.Location, config: Configuration, ) -> Equivalence: - """ - Computes a suitable equivalence relation for a Protobuf enum type. + """Computes a suitable equivalence relation for a Protobuf enum type. Args: descriptor: the descriptor of the Protobuf enum of interest. @@ -136,8 +135,7 @@ def compute_equivalence_for_enum( def translate_type_name(name: str, config: Configuration) -> str: - """ - Translates a Protobuf type name to its ROS equivalent. + """Translates a Protobuf type name to its ROS equivalent. Args: name: fully qualified Protobuf type name. @@ -194,8 +192,7 @@ def translate_type_name(name: str, config: Configuration) -> str: def translate_type(name: str, repeated: bool, config: Configuration) -> Type: - """ - Translates a Protobuf type to its ROS equivalent. + """Translates a Protobuf type to its ROS equivalent. Args: name: Protobuf type name. @@ -218,8 +215,7 @@ def translate_type(name: str, repeated: bool, config: Configuration) -> Type: def translate_any_type(any_expansion: Union[Set[str], str], repeated: bool, config: Configuration) -> Type: - """ - Translates a ``google.protobuf.Any`` type to its ROS equivalent given an any expansion. + """Translates a ``google.protobuf.Any`` type to its ROS equivalent given an any expansion. Args: any_expansion: a Protobuf message type set that the given ``google.protobuf.Any`` @@ -248,8 +244,7 @@ def translate_field( location: SourceCodeInfo.Location, config: Configuration, ) -> Field: - """ - Translates a Protobuf field descriptor to its ROS equivalent. + """Translates a Protobuf field descriptor to its ROS equivalent. Args: descriptor: a Protobuf field descriptor. @@ -314,10 +309,12 @@ def translate_field( @compute_equivalence.register def compute_equivalence_for_message( - descriptor: DescriptorProto, source: FileDescriptorProto, location: SourceCodeInfo.Location, config: Configuration + descriptor: DescriptorProto, + source: FileDescriptorProto, + location: SourceCodeInfo.Location, + config: Configuration, ) -> Equivalence: - """ - Computes a suitable equivalence relation for a Protobuf message type. + """Computes a suitable equivalence relation for a Protobuf message type. Currently, this function supports optional, repeated, and oneof fields of primitive, enum, map, message, and `google.protobuf.Any` type. Recursive or cyclic type dependencies may ensue @@ -371,7 +368,11 @@ def compute_equivalence_for_message( constants.append(mask_constant) fields.append(field) - for (oneof_path, oneof_decl), oneof_fields in zip(locate_repeated("oneof_decl", descriptor), oneof_field_sets): + for (oneof_path, oneof_decl), oneof_fields in zip( + locate_repeated("oneof_decl", descriptor), + oneof_field_sets, + strict=True, + ): oneof_name = inflection.underscore(oneof_decl.name) oneof_type_name = inflection.camelize(f"{name}_one_of_{oneof_name}") oneof_type = Type(f"{ros_package_name}/{oneof_type_name}") @@ -389,11 +390,14 @@ def compute_equivalence_for_message( oneof_fields.append(which_field) oneof_message_spec = MessageSpecification( - oneof_type.pkg_name, oneof_type.type, oneof_fields, oneof_constants + oneof_type.pkg_name, + oneof_type.type, + oneof_fields, + oneof_constants, ) oneof_message_spec.annotations["proto-type"] = protofqn(source, location) + f"[one-of {oneof_decl.name}]" oneof_message_spec.annotations["proto-class"] = "one-of" - oneof_message_spec.annotations["tagged"] = list(zip(oneof_constants[1:], oneof_fields[:-1])) + oneof_message_spec.annotations["tagged"] = list(zip(oneof_constants[1:], oneof_fields[:-2], strict=True)) oneof_message_spec.annotations["tag"] = which_field auxiliary_message_specs.append(oneof_message_spec) @@ -411,7 +415,7 @@ def compute_equivalence_for_message( field.annotations["optional"] = False # field presence mask must always be present fields.append(field) else: - for i, (field_path, field_descriptor) in enumerate(locate_repeated("field", descriptor)): + for field_path, field_descriptor in locate_repeated("field", descriptor): if field_descriptor.options.deprecated and config.drop_deprecated: continue field_location = resolve(source, field_path, location) @@ -432,19 +436,21 @@ def compute_equivalence_for_message( if descriptor.options.map_entry: message_spec.annotations["map-inplace"] = map_inplace return Equivalence( - proto_spec=descriptor, message_spec=message_spec, auxiliary_message_specs=auxiliary_message_specs + proto_spec=descriptor, + message_spec=message_spec, + auxiliary_message_specs=auxiliary_message_specs, ) @functools.singledispatch def extract_equivalences(descriptor: Any, *args: Any) -> Iterable[Equivalence]: - """ - Extracts equivalence relations for all Protobuf composite types in some Protobuf descriptor. + """Extracts equivalence relations for all Protobuf composite types in some Protobuf descriptor. Note this function operates as the entrypoint to all corresponding overloads (via single dispatch). Args: descriptor: the descriptor bearing Protobuf composite types. + args: place holder for arguments Returns: an iterable over equivalence relations. @@ -459,8 +465,7 @@ def extract_equivalences_from_message( location: SourceCodeInfo.Location, config: Configuration, ) -> Iterable[Equivalence]: - """ - Extracts equivalence relations for a Protobuf message type and all nested composite types (if any). + """Extracts equivalence relations for a Protobuf message type and all nested composite types (if any). Args: message_descriptor: the descriptor of the Protobuf message of interest. @@ -482,13 +487,13 @@ def extract_equivalences_from_message( @extract_equivalences.register def extract_equivalences_from_source( - source_descriptor: FileDescriptorProto, config: Configuration + source_descriptor: FileDescriptorProto, + config: Configuration, ) -> Iterable[Equivalence]: - """ - Extracts all equivalence relations from a Protobuf source descriptor. + """Extracts all equivalence relations from a Protobuf source descriptor. Args: - source: the descriptor of the Protobuf source file. + source_descriptor: the descriptor of the Protobuf source file. config: a suitable configuration for the procedure. Returns: diff --git a/proto2ros/proto2ros/output/interfaces.py b/proto2ros/proto2ros/output/interfaces.py index d0dc79a..12c39c5 100644 --- a/proto2ros/proto2ros/output/interfaces.py +++ b/proto2ros/proto2ros/output/interfaces.py @@ -48,10 +48,10 @@ def dump_message_specification(message_spec: MessageSpecification) -> str: def which_message_specification( - message_spec: MessageSpecification, root: Optional[Union[str, os.PathLike[str]]] = None + message_spec: MessageSpecification, + root: Optional[Union[str, os.PathLike[str]]] = None, ) -> pathlib.Path: - """ - Returns an .msg file path for a given ROS message specification. + """Returns an .msg file path for a given ROS message specification. ROS .msg file name conversions are observed in the process. diff --git a/proto2ros/proto2ros/output/python.py b/proto2ros/proto2ros/output/python.py index 1834f04..f07bc84 100644 --- a/proto2ros/proto2ros/output/python.py +++ b/proto2ros/proto2ros/output/python.py @@ -67,8 +67,7 @@ def to_pb2_python_module_name(source_path: os.PathLike) -> str: def build_pb2_python_type_lut(module_names: Iterable[str], inline_module_names: Iterable[str]) -> Dict[str, str]: - """ - Builds a lookup table to go from Protobuf message type names to Python class name. + """Builds a lookup table to go from Protobuf message type names to Python class name. For instance, if `google.protobuf.any_pb2` is listed as an imported module name and `google.protobuf.timestamp_pb2` is listed as an inline imported module name, the @@ -120,8 +119,7 @@ def dump_conversions_python_module( known_message_specifications: List[MessageSpecification], config: Configuration, ) -> str: - """ - Dumps the Python module source for Protobuf <-> ROS conversion APIs. + """Dumps the Python module source for Protobuf <-> ROS conversion APIs. Args: message_specifications: annotated ROS message specifications, @@ -155,8 +153,7 @@ def lookup_pb2_python_type(type_name: str) -> str: def dump_specifications_python_module(message_specifications: List[MessageSpecification], config: Configuration) -> str: - """ - Dumps the Python module source bearing message specifications. + """Dumps the Python module source bearing message specifications. This is the mechanism that enables proto2ros generated packages to depend on other proto2ros generated packages. diff --git a/proto2ros/proto2ros/utilities.py b/proto2ros/proto2ros/utilities.py index 8288d13..6260c2f 100644 --- a/proto2ros/proto2ros/utilities.py +++ b/proto2ros/proto2ros/utilities.py @@ -47,7 +47,7 @@ def pairwise(iterable: Iterable[Any]) -> Iterable[Tuple[Any, Any]]: """Yields an iterable over consecutive pairs.""" a, b = itertools.tee(iterable) next(b, None) - return zip(a, b) + return zip(a, b) # noqa: B905 def to_ros_base_type(type_: Union[str, BaseType]) -> str: diff --git a/proto2ros_tests/proto2ros_tests/manual_conversions.py b/proto2ros_tests/proto2ros_tests/manual_conversions.py index 841f02b..8ca692a 100644 --- a/proto2ros_tests/proto2ros_tests/manual_conversions.py +++ b/proto2ros_tests/proto2ros_tests/manual_conversions.py @@ -8,7 +8,8 @@ @convert.register(geometry_msgs.msg.Vector3, bosdyn.api.geometry_pb2.Vec3) def convert_geometry_msgs_vector3_message_to_bosdyn_api_vec3_proto( - ros_msg: geometry_msgs.msg.Vector3, proto_msg: bosdyn.api.geometry_pb2.Vec3 + ros_msg: geometry_msgs.msg.Vector3, + proto_msg: bosdyn.api.geometry_pb2.Vec3, ) -> None: proto_msg.x = ros_msg.x proto_msg.y = ros_msg.y @@ -17,7 +18,8 @@ def convert_geometry_msgs_vector3_message_to_bosdyn_api_vec3_proto( @convert.register(bosdyn.api.geometry_pb2.Vec3, geometry_msgs.msg.Vector3) def convert_bosdyn_api_vec3_proto_to_geometry_msgs_vector3_message( - proto_msg: bosdyn.api.geometry_pb2.Vec3, ros_msg: geometry_msgs.msg.Vector3 + proto_msg: bosdyn.api.geometry_pb2.Vec3, + ros_msg: geometry_msgs.msg.Vector3, ) -> None: ros_msg.x = proto_msg.x ros_msg.y = proto_msg.y @@ -26,7 +28,8 @@ def convert_bosdyn_api_vec3_proto_to_geometry_msgs_vector3_message( @convert.register(geometry_msgs.msg.Quaternion, bosdyn.api.geometry_pb2.Quaternion) def convert_geometry_msgs_quaternion_message_to_bosdyn_api_quaternion_proto( - ros_msg: geometry_msgs.msg.Quaternion, proto_msg: bosdyn.api.geometry_pb2.Quaternion + ros_msg: geometry_msgs.msg.Quaternion, + proto_msg: bosdyn.api.geometry_pb2.Quaternion, ) -> None: proto_msg.w = ros_msg.w proto_msg.x = ros_msg.x @@ -36,7 +39,8 @@ def convert_geometry_msgs_quaternion_message_to_bosdyn_api_quaternion_proto( @convert.register(bosdyn.api.geometry_pb2.Quaternion, geometry_msgs.msg.Quaternion) def convert_bosdyn_api_quaternion_proto_to_geometry_msgs_quaternion_message( - proto_msg: bosdyn.api.geometry_pb2.Quaternion, ros_msg: geometry_msgs.msg.Quaternion + proto_msg: bosdyn.api.geometry_pb2.Quaternion, + ros_msg: geometry_msgs.msg.Quaternion, ) -> None: ros_msg.w = proto_msg.w ros_msg.x = proto_msg.x @@ -46,7 +50,8 @@ def convert_bosdyn_api_quaternion_proto_to_geometry_msgs_quaternion_message( @convert.register(geometry_msgs.msg.Pose, bosdyn.api.geometry_pb2.SE3Pose) def convert_geometry_msgs_pose_message_to_bosdyn_api_se3_pose_proto( - ros_msg: geometry_msgs.msg.Pose, proto_msg: bosdyn.api.geometry_pb2.SE3Pose + ros_msg: geometry_msgs.msg.Pose, + proto_msg: bosdyn.api.geometry_pb2.SE3Pose, ) -> None: convert_geometry_msgs_vector3_message_to_bosdyn_api_vec3_proto(ros_msg.position, proto_msg.position) convert_geometry_msgs_quaternion_message_to_bosdyn_api_quaternion_proto(ros_msg.orientation, proto_msg.rotation) @@ -54,7 +59,8 @@ def convert_geometry_msgs_pose_message_to_bosdyn_api_se3_pose_proto( @convert.register(bosdyn.api.geometry_pb2.SE3Pose, geometry_msgs.msg.Pose) def convert_bosdyn_api_se3_pose_proto_to_geometry_msgs_pose_message( - proto_msg: bosdyn.api.geometry_pb2.SE3Pose, ros_msg: geometry_msgs.msg.Pose + proto_msg: bosdyn.api.geometry_pb2.SE3Pose, + ros_msg: geometry_msgs.msg.Pose, ) -> None: convert_bosdyn_api_vec3_proto_to_geometry_msgs_vector3_message(proto_msg.position, ros_msg.position) convert_bosdyn_api_quaternion_proto_to_geometry_msgs_quaternion_message(proto_msg.rotation, ros_msg.orientation) @@ -62,7 +68,8 @@ def convert_bosdyn_api_se3_pose_proto_to_geometry_msgs_pose_message( @convert.register(geometry_msgs.msg.Pose, bosdyn.api.geometry_pb2.SE2Pose) def convert_geometry_msgs_pose_message_to_bosdyn_api_se2_pose_proto( - ros_msg: geometry_msgs.msg.Pose, proto_msg: bosdyn.api.geometry_pb2.SE2Pose + ros_msg: geometry_msgs.msg.Pose, + proto_msg: bosdyn.api.geometry_pb2.SE2Pose, ) -> None: proto_msg.position.x = ros_msg.position.x proto_msg.position.y = ros_msg.position.y @@ -71,7 +78,8 @@ def convert_geometry_msgs_pose_message_to_bosdyn_api_se2_pose_proto( @convert.register(bosdyn.api.geometry_pb2.SE2Pose, geometry_msgs.msg.Pose) def convert_bosdyn_api_se2_pose_proto_to_geometry_msgs_pose_message( - proto_msg: bosdyn.api.geometry_pb2.SE2Pose, ros_msg: geometry_msgs.msg.Pose + proto_msg: bosdyn.api.geometry_pb2.SE2Pose, + ros_msg: geometry_msgs.msg.Pose, ) -> None: ros_msg.position.x = proto_msg.position.x ros_msg.position.y = proto_msg.position.y @@ -81,7 +89,8 @@ def convert_bosdyn_api_se2_pose_proto_to_geometry_msgs_pose_message( @convert.register(geometry_msgs.msg.Polygon, bosdyn.api.geometry_pb2.Polygon) def convert_geometry_msgs_polygon_message_to_bosdyn_api_polygon_proto( - ros_msg: geometry_msgs.msg.Polygon, proto_msg: bosdyn.api.geometry_pb2.Polygon + ros_msg: geometry_msgs.msg.Polygon, + proto_msg: bosdyn.api.geometry_pb2.Polygon, ) -> None: proto_msg.Clear() for point in ros_msg.points: @@ -92,14 +101,16 @@ def convert_geometry_msgs_polygon_message_to_bosdyn_api_polygon_proto( @convert.register(bosdyn.api.geometry_pb2.Polygon, geometry_msgs.msg.Polygon) def convert_bosdyn_api_polygon_proto_to_geometry_msgs_polygon_message( - proto_msg: bosdyn.api.geometry_pb2.Polygon, ros_msg: geometry_msgs.msg.Polygon + proto_msg: bosdyn.api.geometry_pb2.Polygon, + ros_msg: geometry_msgs.msg.Polygon, ) -> None: ros_msg.points = [geometry_msgs.msg.Point32(x=vertex.x, y=vertex.y, z=0.0) for vertex in proto_msg.vertexes] @convert.register(geometry_msgs.msg.Vector3, bosdyn.api.geometry_pb2.Circle) def convert_geometry_msgs_vector3_message_to_bosdyn_api_circle_proto( - ros_msg: geometry_msgs.msg.Vector3, proto_msg: bosdyn.api.geometry_pb2.Circle + ros_msg: geometry_msgs.msg.Vector3, + proto_msg: bosdyn.api.geometry_pb2.Circle, ) -> None: proto_msg.center_pt.x = ros_msg.x proto_msg.center_pt.y = ros_msg.y @@ -108,7 +119,8 @@ def convert_geometry_msgs_vector3_message_to_bosdyn_api_circle_proto( @convert.register(bosdyn.api.geometry_pb2.Circle, geometry_msgs.msg.Vector3) def convert_bosdyn_api_circle_proto_to_geometry_msgs_vector3_message( - proto_msg: bosdyn.api.geometry_pb2.Circle, ros_msg: geometry_msgs.msg.Vector3 + proto_msg: bosdyn.api.geometry_pb2.Circle, + ros_msg: geometry_msgs.msg.Vector3, ) -> None: ros_msg.x = proto_msg.center_pt.x ros_msg.y = proto_msg.center_pt.y @@ -117,7 +129,8 @@ def convert_bosdyn_api_circle_proto_to_geometry_msgs_vector3_message( @convert.register(geometry_msgs.msg.Twist, bosdyn.api.geometry_pb2.SE3Velocity) def convert_geometry_msgs_twist_message_to_bosdyn_api_se3_velocity_proto( - ros_msg: geometry_msgs.msg.Twist, proto_msg: bosdyn.api.geometry_pb2.SE3Velocity + ros_msg: geometry_msgs.msg.Twist, + proto_msg: bosdyn.api.geometry_pb2.SE3Velocity, ) -> None: convert_geometry_msgs_vector3_message_to_bosdyn_api_vec3_proto(ros_msg.linear, proto_msg.linear) convert_geometry_msgs_vector3_message_to_bosdyn_api_vec3_proto(ros_msg.angular, proto_msg.angular) @@ -125,7 +138,8 @@ def convert_geometry_msgs_twist_message_to_bosdyn_api_se3_velocity_proto( @convert.register(bosdyn.api.geometry_pb2.SE3Velocity, geometry_msgs.msg.Twist) def convert_bosdyn_api_se3_velocity_proto_to_geometry_msgs_twist_message( - proto_msg: bosdyn.api.geometry_pb2.SE3Velocity, ros_msg: geometry_msgs.msg.Twist + proto_msg: bosdyn.api.geometry_pb2.SE3Velocity, + ros_msg: geometry_msgs.msg.Twist, ) -> None: convert_bosdyn_api_vec3_proto_to_geometry_msgs_vector3_message(proto_msg.linear, ros_msg.linear) convert_bosdyn_api_vec3_proto_to_geometry_msgs_vector3_message(proto_msg.angular, ros_msg.angular) @@ -133,7 +147,8 @@ def convert_bosdyn_api_se3_velocity_proto_to_geometry_msgs_twist_message( @convert.register(geometry_msgs.msg.Wrench, bosdyn.api.geometry_pb2.Wrench) def convert_geometry_msgs_wrench_message_to_bosdyn_api_wrench_proto( - ros_msg: geometry_msgs.msg.Wrench, proto_msg: bosdyn.api.geometry_pb2.Wrench + ros_msg: geometry_msgs.msg.Wrench, + proto_msg: bosdyn.api.geometry_pb2.Wrench, ) -> None: convert_geometry_msgs_vector3_message_to_bosdyn_api_vec3_proto(ros_msg.force, proto_msg.force) convert_geometry_msgs_vector3_message_to_bosdyn_api_vec3_proto(ros_msg.torque, proto_msg.torque) @@ -141,7 +156,8 @@ def convert_geometry_msgs_wrench_message_to_bosdyn_api_wrench_proto( @convert.register(bosdyn.api.geometry_pb2.Wrench, geometry_msgs.msg.Wrench) def convert_bosdyn_api_wrench_proto_to_geometry_msgs_wrench_messagey( - proto_msg: bosdyn.api.geometry_pb2.Wrench, ros_msg: geometry_msgs.msg.Wrench + proto_msg: bosdyn.api.geometry_pb2.Wrench, + ros_msg: geometry_msgs.msg.Wrench, ) -> None: convert_bosdyn_api_vec3_proto_to_geometry_msgs_vector3_message(proto_msg.force, ros_msg.force) convert_bosdyn_api_vec3_proto_to_geometry_msgs_vector3_message(proto_msg.torque, ros_msg.torque) diff --git a/proto2ros_tests/test/test_proto2ros.py b/proto2ros_tests/test/test_proto2ros.py index 71e2924..192ac00 100644 --- a/proto2ros_tests/test/test_proto2ros.py +++ b/proto2ros_tests/test/test_proto2ros.py @@ -344,5 +344,5 @@ def test_messages_with_expanded_any_fields() -> None: other_proto_roi = bosdyn.api.geometry_pb2.Polygon() other_proto_goal.roi.Unpack(other_proto_roi) assert len(other_proto_roi.vertexes) == 4 - for a, b in zip(proto_roi.vertexes, other_proto_roi.vertexes): + for a, b in zip(proto_roi.vertexes, other_proto_roi.vertexes, strict=True): assert a.x == b.x and a.y == b.y