From 72de5172bc43c64f1a3e0ff047799db0e0d8356e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jaroslav=20Klap=C3=A1lek?= Date: Fri, 1 Sep 2023 13:37:05 +0200 Subject: [PATCH 01/13] core: Add new component --- CHANGELOG.md | 6 +++ README.md | 35 +++++++++++++++ autopsy/core.py | 110 ++++++++++++++++++++++++++++++++++++++++++++++++ 3 files changed, 151 insertions(+) create mode 100644 autopsy/core.py diff --git a/CHANGELOG.md b/CHANGELOG.md index b025379..30ed64e 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -4,6 +4,12 @@ All notable changes to this project will be documented in this file. The format is based on [Keep a Changelog](http://keepachangelog.com/). ## Unreleased +### Added +- `unicore`: + - New compatibility layer to cover node spinning and initialization. + - Functions: `spin()` and `init()`. + - Decorators: `@ros1_only` and `@ros2_only` with an optional argument to use different function instead. + ## 0.8.1 - 2023-08-08 ### Fixed - `uninode`: diff --git a/README.md b/README.md index cd199ea..e9abe3e 100644 --- a/README.md +++ b/README.md @@ -4,6 +4,7 @@ _Python utilities for the F1tenth project._ Currently, this package contains following modules: - [reconfigure](#reconfigure-module) - [uninode](#uninode-module) +- [unicore](#unicore-module) @@ -393,3 +394,37 @@ class MyNode(Node): def topic_callback(self, msg): print ("Received:", msg.data) ``` + + + +## Unicore module + +Universal core layer for both ROS 1 and ROS 2. + +Universal core (or unicore) serves as a compatibility layer for running a ROS node that is executable from both ROS versions. + +- [Example](#full-example-2) + + +### Full example + +Example: +```python +from autopsy import core +from autopsy.node import Node +from std_msgs.msg import Int32 + +@core.ros2_only(other_callback) +def callback(data): + print("Called from ROS2!") + +def other_callback(data): + print("Called from ROS1!") + +core.init() + +n = Node("testing_node") +n.Subscriber("/topic", Int32, callback) + +core.spin(n) +``` diff --git a/autopsy/core.py b/autopsy/core.py new file mode 100644 index 0000000..6b85c32 --- /dev/null +++ b/autopsy/core.py @@ -0,0 +1,110 @@ +#!/usr/bin/env python +# core.py +"""Universal core class with ROS 1 / ROS 2 support. + +Universal core (or unicore) serves as a compatibility layer for running +a ROS node that is executable from both ROS versions. +""" +###################### +# Imports & Globals +###################### + +# Figure out ROS version +try: + import rospy + + ROS_VERSION = 1 +except: + try: + import rclpy + + ROS_VERSION = 2 + except: + print ("No ROS package detected.") + ROS_VERSION = 0 + + +###################### +# Decorators +###################### + +def _ros_version_only(ros_version, f): + """Decorator for disabling functions that are ROS version dependent. + + Using an optional argument a substitute function may be set. + This function will be called instead of the original one, + when ROS version is not available. + """ + global ROS_VERSION + + func = None + + def substitute_or_block(*args, **kwargs): + # Substitute + if ( len(args) == 1 ) and ( callable(args[0]) ): + + def substitute(*args, **kwargs): + return f ( *args, **kwargs ) + + return substitute + # Block + + def let_pass(*args, **kwargs): + # Let pass function that is decorated without params + if ( len(args) == 0 ) or ( not ( callable(args[0]) ) ): + return f(*args, **kwargs) + # Ignore parameters of a decorator and run original function instead + else: + #nonlocal func + func = args[0] + + def pass_it(*args, **kwargs): + return func(*args, **kwargs) + + return pass_it + + return let_pass if ROS_VERSION == ros_version else substitute_or_block + + +def ros1_only(f): + """Decorator for enabling functions only with ROS1.""" + return _ros_version_only(1, f) + + +def ros2_only(f): + """Decorator for enabling functions only with ROS2.""" + return _ros_version_only(2, f) + + +###################### +# Universal Core functions +###################### + +def init(args = None, context = None): + """Initialize ROS communications for a given context. + + Arguments: + args -- command line arguments, list + context -- context to initialize, if None default is used + + Reference: + https://docs.ros2.org/foxy/api/rclpy/api/init_shutdown.html#rclpy.init + """ + if ROS_VERSION == 2: + rclpy.init(args = args, context = context) + + +def spin(node = None, executor = None): + """Execute work and block until the node is shutdown. + + Arguments: + node -- instance of Node to be checked for work + executor -- executor to use, if None global is used + + Reference: + https://docs.ros2.org/foxy/api/rclpy/api/init_shutdown.html#rclpy.spin + """ + if ROS_VERSION == 1: + rospy.spin() + elif ROS_VERSION == 2: + rclpy.spin(node = node, executor = executor) From 620149587d4c3691234c2edf72c0800eff6a8cf4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jaroslav=20Klap=C3=A1lek?= Date: Fri, 1 Sep 2023 13:37:58 +0200 Subject: [PATCH 02/13] node: Move ROS_VERSION to unicore --- CHANGELOG.md | 4 ++++ autopsy/node.py | 18 +++++------------- 2 files changed, 9 insertions(+), 13 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 30ed64e..c5cdd30 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -10,6 +10,10 @@ The format is based on [Keep a Changelog](http://keepachangelog.com/). - Functions: `spin()` and `init()`. - Decorators: `@ros1_only` and `@ros2_only` with an optional argument to use different function instead. +### Changed +- `uninode`: + - `ROS_VERSION` is determined inside `unicore`. + ## 0.8.1 - 2023-08-08 ### Fixed - `uninode`: diff --git a/autopsy/node.py b/autopsy/node.py index 3eba617..8f070d0 100644 --- a/autopsy/node.py +++ b/autopsy/node.py @@ -86,24 +86,16 @@ def topic_callback(self, msg): # Imports & Globals ###################### -# Figure out ROS version -try: - import rospy +from autopsy.core import ROS_VERSION +if ROS_VERSION == 1: from .ros1_node import Node as NodeI from .ros1_time import Time as TimeI from .ros1_qos import * - ROS_VERSION = 1 -except: - try: - from rclpy.node import Node as NodeI - from rclpy.qos import * - - ROS_VERSION = 2 - except: - print ("No ROS package detected.") - ROS_VERSION = 0 +elif ROS_VERSION == 2: + from rclpy.node import Node as NodeI + from rclpy.qos import * ###################### From 265e3f99cef722ec89658e0c515b93047af57e57 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jaroslav=20Klap=C3=A1lek?= Date: Mon, 4 Sep 2023 15:59:34 +0200 Subject: [PATCH 03/13] core: Move core functions into a class --- CHANGELOG.md | 3 ++- README.md | 8 ++++---- autopsy/core.py | 47 +++++++++++++++++++++++++---------------------- 3 files changed, 31 insertions(+), 27 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index c5cdd30..bbb8cf0 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -7,7 +7,8 @@ The format is based on [Keep a Changelog](http://keepachangelog.com/). ### Added - `unicore`: - New compatibility layer to cover node spinning and initialization. - - Functions: `spin()` and `init()`. + - Object `Core`: + - Functions: `spin()` and `init()`. - Decorators: `@ros1_only` and `@ros2_only` with an optional argument to use different function instead. ### Changed diff --git a/README.md b/README.md index e9abe3e..2feb743 100644 --- a/README.md +++ b/README.md @@ -410,21 +410,21 @@ Universal core (or unicore) serves as a compatibility layer for running a ROS no Example: ```python -from autopsy import core +from autopsy.core import * from autopsy.node import Node from std_msgs.msg import Int32 -@core.ros2_only(other_callback) +@ros2_only(other_callback) def callback(data): print("Called from ROS2!") def other_callback(data): print("Called from ROS1!") -core.init() +Core.init() n = Node("testing_node") n.Subscriber("/topic", Int32, callback) -core.spin(n) +Core.spin(n) ``` diff --git a/autopsy/core.py b/autopsy/core.py index 6b85c32..c516142 100644 --- a/autopsy/core.py +++ b/autopsy/core.py @@ -80,31 +80,34 @@ def ros2_only(f): # Universal Core functions ###################### -def init(args = None, context = None): - """Initialize ROS communications for a given context. +class Core(object): + """Universal core class that supports both ROS 1 and ROS 2.""" - Arguments: - args -- command line arguments, list - context -- context to initialize, if None default is used + def init(args = None, context = None): + """Initialize ROS communications for a given context. - Reference: - https://docs.ros2.org/foxy/api/rclpy/api/init_shutdown.html#rclpy.init - """ - if ROS_VERSION == 2: - rclpy.init(args = args, context = context) + Arguments: + args -- command line arguments, list + context -- context to initialize, if None default is used + Reference: + https://docs.ros2.org/foxy/api/rclpy/api/init_shutdown.html#rclpy.init + """ + if ROS_VERSION == 2: + rclpy.init(args = args, context = context) -def spin(node = None, executor = None): - """Execute work and block until the node is shutdown. - Arguments: - node -- instance of Node to be checked for work - executor -- executor to use, if None global is used + def spin(node = None, executor = None): + """Execute work and block until the node is shutdown. - Reference: - https://docs.ros2.org/foxy/api/rclpy/api/init_shutdown.html#rclpy.spin - """ - if ROS_VERSION == 1: - rospy.spin() - elif ROS_VERSION == 2: - rclpy.spin(node = node, executor = executor) + Arguments: + node -- instance of Node to be checked for work + executor -- executor to use, if None global is used + + Reference: + https://docs.ros2.org/foxy/api/rclpy/api/init_shutdown.html#rclpy.spin + """ + if ROS_VERSION == 1: + rospy.spin() + elif ROS_VERSION == 2: + rclpy.spin(node = node, executor = executor) From 156ce09d73ae6011d4152b1b5b02d1bdc1d55730 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jaroslav=20Klap=C3=A1lek?= Date: Mon, 4 Sep 2023 16:02:31 +0200 Subject: [PATCH 04/13] core: Decorate init() instead of using a condition --- autopsy/core.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/autopsy/core.py b/autopsy/core.py index c516142..dffb9d5 100644 --- a/autopsy/core.py +++ b/autopsy/core.py @@ -83,6 +83,7 @@ def ros2_only(f): class Core(object): """Universal core class that supports both ROS 1 and ROS 2.""" + @ros2_only def init(args = None, context = None): """Initialize ROS communications for a given context. @@ -93,8 +94,7 @@ def init(args = None, context = None): Reference: https://docs.ros2.org/foxy/api/rclpy/api/init_shutdown.html#rclpy.init """ - if ROS_VERSION == 2: - rclpy.init(args = args, context = context) + rclpy.init(args = args, context = context) def spin(node = None, executor = None): From 16218e4cc9ea51c4eee67bd4fc0586da5af5e414 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jaroslav=20Klap=C3=A1lek?= Date: Mon, 4 Sep 2023 16:04:23 +0200 Subject: [PATCH 05/13] core: Add shutdown --- CHANGELOG.md | 2 +- autopsy/core.py | 13 +++++++++++++ 2 files changed, 14 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index bbb8cf0..6530f2d 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -8,7 +8,7 @@ The format is based on [Keep a Changelog](http://keepachangelog.com/). - `unicore`: - New compatibility layer to cover node spinning and initialization. - Object `Core`: - - Functions: `spin()` and `init()`. + - Functions: `spin()`, `init()`, `shutdown()`. - Decorators: `@ros1_only` and `@ros2_only` with an optional argument to use different function instead. ### Changed diff --git a/autopsy/core.py b/autopsy/core.py index dffb9d5..e773b40 100644 --- a/autopsy/core.py +++ b/autopsy/core.py @@ -111,3 +111,16 @@ def spin(node = None, executor = None): rospy.spin() elif ROS_VERSION == 2: rclpy.spin(node = node, executor = executor) + + + @ros2_only + def shutdown(context = None): + """Shutdown a previously initialized context and global executor. + + Arguments: + context -- context to invalidate, if None default is used + + Reference: + https://docs.ros2.org/latest/api/rclpy/api/init_shutdown.html#rclpy.shutdown + """ + rclpy.shutdown(context = context) From d3d1a01588eec37ae5766fd416b2fa5cdfc191e0 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jaroslav=20Klap=C3=A1lek?= Date: Mon, 4 Sep 2023 16:25:35 +0200 Subject: [PATCH 06/13] (F) core: Resolve unbound method error in Py2 --- autopsy/core.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/autopsy/core.py b/autopsy/core.py index e773b40..9e68413 100644 --- a/autopsy/core.py +++ b/autopsy/core.py @@ -124,3 +124,7 @@ def shutdown(context = None): https://docs.ros2.org/latest/api/rclpy/api/init_shutdown.html#rclpy.shutdown """ rclpy.shutdown(context = context) + + +# Workaround for 'unbound method' error in Python 2. +Core = Core() From 15c52c9fd5af8f038b76ded31767a4ca1eb271dc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jaroslav=20Klap=C3=A1lek?= Date: Mon, 4 Sep 2023 16:34:59 +0200 Subject: [PATCH 07/13] (F) core: Add self to core functions --- autopsy/core.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/autopsy/core.py b/autopsy/core.py index 9e68413..36ed000 100644 --- a/autopsy/core.py +++ b/autopsy/core.py @@ -84,7 +84,7 @@ class Core(object): """Universal core class that supports both ROS 1 and ROS 2.""" @ros2_only - def init(args = None, context = None): + def init(self, args = None, context = None): """Initialize ROS communications for a given context. Arguments: @@ -97,7 +97,7 @@ def init(args = None, context = None): rclpy.init(args = args, context = context) - def spin(node = None, executor = None): + def spin(self, node = None, executor = None): """Execute work and block until the node is shutdown. Arguments: @@ -114,7 +114,7 @@ def spin(node = None, executor = None): @ros2_only - def shutdown(context = None): + def shutdown(self, context = None): """Shutdown a previously initialized context and global executor. Arguments: From 80bb8311411e8f68ce0b517c12f6d579984259d8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jaroslav=20Klap=C3=A1lek?= Date: Tue, 5 Sep 2023 06:23:47 +0200 Subject: [PATCH 08/13] node: Add ReliabilityPolicy QoS --- autopsy/ros1_qos.py | 22 +++++++++++++++++++++- 1 file changed, 21 insertions(+), 1 deletion(-) diff --git a/autopsy/ros1_qos.py b/autopsy/ros1_qos.py index ec8c58b..5235500 100644 --- a/autopsy/ros1_qos.py +++ b/autopsy/ros1_qos.py @@ -25,6 +25,22 @@ class DurabilityPolicy(Enum): VOLATILE = 2 +###################### +# QoSReliablityPolicy +###################### + +class ReliabilityPolicy(Enum): + """Enum to mimic ROS2 `ReliabilityPolicy`. + + Reference: + https://docs.ros2.org/foxy/api/rclpy/api/qos.html#rclpy.qos.ReliabilityPolicy + """ + + SYSTEM_DEFAULT = 0 + RELIABLE = 1 + BEST_EFFORT = 2 + + ###################### # QoSProfile class ###################### @@ -37,7 +53,10 @@ class QoSProfile(object): https://docs.ros.org/en/rolling/Concepts/About-Quality-of-Service-Settings.html """ - def __init__(self, depth, durability = DurabilityPolicy.SYSTEM_DEFAULT, **kwargs): + def __init__(self, depth, + durability = DurabilityPolicy.SYSTEM_DEFAULT, + reliability = ReliabilityPolicy.SYSTEM_DEFAULT, + **kwargs): """Initialize the class. Arguments: @@ -50,3 +69,4 @@ def __init__(self, depth, durability = DurabilityPolicy.SYSTEM_DEFAULT, **kwargs """ self.depth = depth self.durability = durability + self.reliability = reliability From defba8e8bf5ec1295ce0aad2b8a73c27efb43a37 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jaroslav=20Klap=C3=A1lek?= Date: Tue, 5 Sep 2023 06:24:20 +0200 Subject: [PATCH 09/13] node: Support tcp_nodelay--best_effort/reliable relation --- autopsy/node.py | 7 +++++-- autopsy/ros1_node.py | 4 ++-- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/autopsy/node.py b/autopsy/node.py index 8f070d0..f4b95ae 100644 --- a/autopsy/node.py +++ b/autopsy/node.py @@ -123,12 +123,14 @@ def Publisher(self, name, data_class, subscriber_listener=None, tcp_nodelay=Fals Arguments (only those that are used): name -- name of the topic to publish to, str data_class -- class of the ROS message + tcp_nodelay -- disable Nagle algorithm on TCPROS to lower latency, bool + latch -- enable latching on the connection, bool queue_size -- number of messages to be kept in queue, int Reference: http://docs.ros.org/en/kinetic/api/rospy/html/rospy.topics.Publisher-class.html """ - return super(Node, self).create_publisher(msg_type = data_class, topic = name, qos_profile = QoSProfile(depth = queue_size, durability = DurabilityPolicy.TRANSIENT_LOCAL if latch else DurabilityPolicy.VOLATILE)) + return super(Node, self).create_publisher(msg_type = data_class, topic = name, qos_profile = QoSProfile(depth = queue_size, durability = DurabilityPolicy.TRANSIENT_LOCAL if latch else DurabilityPolicy.VOLATILE, reliability = ReliabilityPolicy.BEST_EFFORT if tcp_nodelay else ReliabilityPolicy.RELIABLE)) def Subscriber(self, name, data_class, callback=None, callback_args=None, queue_size=10, buff_size=65536, tcp_nodelay=False): @@ -139,11 +141,12 @@ def Subscriber(self, name, data_class, callback=None, callback_args=None, queue_ data_class -- class of the ROS message callback -- function to be called upon receiving a message, Callable[msg_type] queue_size -- number of messages to be kept in queue, int + tcp_nodelay -- disable Nagle algorithm on TCPROS to lower latency, bool Reference: http://docs.ros.org/en/kinetic/api/rospy/html/rospy.topics.Subscriber-class.html """ - return super(Node, self).create_subscription(msg_type = data_class, topic = name, callback = callback, qos_profile = QoSProfile(depth = queue_size)) + return super(Node, self).create_subscription(msg_type = data_class, topic = name, callback = callback, qos_profile = QoSProfile(depth = queue_size, reliability = ReliabilityPolicy.BEST_EFFORT if tcp_nodelay else ReliabilityPolicy.RELIABLE)) def Rate(self, hz, reset=False): diff --git a/autopsy/ros1_node.py b/autopsy/ros1_node.py index 32e7dc9..2ad1ac5 100644 --- a/autopsy/ros1_node.py +++ b/autopsy/ros1_node.py @@ -66,7 +66,7 @@ def create_publisher(self, msg_type, topic, qos_profile, **kwargs): Reference: https://docs.ros2.org/latest/api/rclpy/api/node.html#rclpy.node.Node.create_publisher """ - return rospy.Publisher(name = topic, data_class = msg_type, latch = qos_profile.durability == DurabilityPolicy.TRANSIENT_LOCAL, queue_size = qos_profile.depth) + return rospy.Publisher(name = topic, data_class = msg_type, tcp_nodelay = qos_profile.reliability == ReliabilityPolicy.BEST_EFFORT, latch = qos_profile.durability == DurabilityPolicy.TRANSIENT_LOCAL, queue_size = qos_profile.depth) def create_subscription(self, msg_type, topic, callback, qos_profile, **kwargs): @@ -82,7 +82,7 @@ def create_subscription(self, msg_type, topic, callback, qos_profile, **kwargs): Reference: https://docs.ros2.org/latest/api/rclpy/api/node.html#rclpy.node.Node.create_subscription """ - return rospy.Subscriber(name = topic, data_class = msg_type, callback = callback, queue_size = qos_profile.depth) + return rospy.Subscriber(name = topic, data_class = msg_type, callback = callback, queue_size = qos_profile.depth, tcp_nodelay = qos_profile.reliability == ReliabilityPolicy.BEST_EFFORT) def create_rate(self, frequency, **kwargs): From 74102b41e2faa87a7aa2db193775bf908ff2009c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jaroslav=20Klap=C3=A1lek?= Date: Tue, 5 Sep 2023 06:40:37 +0200 Subject: [PATCH 10/13] core: Add spin_* functions --- autopsy/core.py | 40 ++++++++++++++++++++++++++++++++++++++++ 1 file changed, 40 insertions(+) diff --git a/autopsy/core.py b/autopsy/core.py index 36ed000..d3e5af9 100644 --- a/autopsy/core.py +++ b/autopsy/core.py @@ -113,6 +113,46 @@ def spin(self, node = None, executor = None): rclpy.spin(node = node, executor = executor) + @ros2_only(spin) + def spin_once(self, node, executor = None, timeout_sec = None): + """Execute one item of work or wait until timeout expires. + + Arguments: + node -- instance of Node to be checked for work + executor -- executor to use, if None global is used + timeout_sec -- seconds to wait, if None or <0 block forever + + Reference: + https://docs.ros2.org/foxy/api/rclpy/api/init_shutdown.html#rclpy.spin_once + + Note: + ROS1 (rospy) does not support this. Something similar can be + achieved using `rospy.wait_for_message()`, but it is not the + same. So we translate this into ordinary `rospy.spin()`. + """ + rclpy.spin_once(node = node, executor = executor, timeout_sec = timeout_sec) + + + @ros2_only(spin) + def spin_until_future_complete(self, node, future, executor = None, timeout_sec = None): + """Execute work until the future is complete. + + Arguments: + node -- instance of Node to be checked for work + future -- future object to wait on + executor -- executor to use, if None global is used + timeout_sec -- seconds to wait, if None or <0 block forever + + Reference: + https://docs.ros2.org/foxy/api/rclpy/api/init_shutdown.html#rclpy.spin_until_future_complete + + Note: + ROS1 (rospy) does not support this, so we translate + it into ordinary `rospy.spin()`. + """ + rclpy.spin_until_future_complete(node = node, future = future, executor = executor, timeout_sec = timeout_sec) + + @ros2_only def shutdown(self, context = None): """Shutdown a previously initialized context and global executor. From e942e760f2a8d6f731193dd85b43610057b83b42 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jaroslav=20Klap=C3=A1lek?= Date: Tue, 5 Sep 2023 06:41:14 +0200 Subject: [PATCH 11/13] (F) node: Add missing import --- autopsy/ros1_node.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/autopsy/ros1_node.py b/autopsy/ros1_node.py index 2ad1ac5..3ad53db 100644 --- a/autopsy/ros1_node.py +++ b/autopsy/ros1_node.py @@ -11,7 +11,7 @@ except: pass -from .ros1_qos import DurabilityPolicy +from .ros1_qos import DurabilityPolicy, ReliabilityPolicy from .ros1_time import Time from .ros1_clock import Clock from .ros1_logger import Logger From 2390aaa8c663d1940aa6ae79d5e7b0fd0a82e12f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jaroslav=20Klap=C3=A1lek?= Date: Tue, 5 Sep 2023 06:46:48 +0200 Subject: [PATCH 12/13] Update changelog --- CHANGELOG.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 6530f2d..53a4daa 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -8,8 +8,11 @@ The format is based on [Keep a Changelog](http://keepachangelog.com/). - `unicore`: - New compatibility layer to cover node spinning and initialization. - Object `Core`: - - Functions: `spin()`, `init()`, `shutdown()`. + - Functions: `spin()`, `spin_once()`, `spin_until_future_complete()`, `init()`, `shutdown()`. - Decorators: `@ros1_only` and `@ros2_only` with an optional argument to use different function instead. +- `uninode`: + - Parameter `tcp_nodelay` is now supported for both Publisher and Subscriber. It translates to `BEST_EFFORT` and vice versa. + - QoS ReliabilityPolicy is in ROS1. ### Changed - `uninode`: From 7f79152c008c67ee47f9daea1dd75f1e1781ff5f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jaroslav=20Klap=C3=A1lek?= Date: Tue, 5 Sep 2023 06:47:16 +0200 Subject: [PATCH 13/13] Release version 0.9.0 --- CHANGELOG.md | 1 + package.xml | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 53a4daa..bb8d832 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -4,6 +4,7 @@ All notable changes to this project will be documented in this file. The format is based on [Keep a Changelog](http://keepachangelog.com/). ## Unreleased +## 0.9.0 - 2023-09-05 ### Added - `unicore`: - New compatibility layer to cover node spinning and initialization. diff --git a/package.xml b/package.xml index a8bd2f1..3910725 100644 --- a/package.xml +++ b/package.xml @@ -4,7 +4,7 @@ schematypens="http://www.w3.org/2001/XMLSchema"?> autopsy - 0.8.1 + 0.9.0 A set of Python utils for F1Tenth project. Jaroslav Klapálek