Skip to content

Commit

Permalink
Lifespan not working with transiet_local subscriber
Browse files Browse the repository at this point in the history
  • Loading branch information
fujitatomoya committed Oct 6, 2023
1 parent 16be352 commit 1c8bbc6
Show file tree
Hide file tree
Showing 3 changed files with 90 additions and 0 deletions.
2 changes: 2 additions & 0 deletions prover_rclpy/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -70,6 +70,8 @@
'rclpy_1132 = src.rclpy_1132:main',
'rclpy_1149 = src.rclpy_1149:main',
'rclpy_1159 = src.rclpy_1159:main',
'rclpy_1163_pub = src.rclpy_1163_pub:main',
'rclpy_1163_sub = src.rclpy_1163_sub:main',
'ros2cli_818 = src.ros2cli_818:main',
],
},
Expand Down
40 changes: 40 additions & 0 deletions prover_rclpy/src/rclpy_1163_pub.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
import rclpy
from rclpy.node import Node
from rclpy.qos import (
QoSDurabilityPolicy,
QoSProfile,
QoSReliabilityPolicy,
)

from std_msgs.msg import Bool


class PubNode(Node):
def __init__(self):
super().__init__("pub_node")

qos = QoSProfile(
depth=5,
durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
reliability=QoSReliabilityPolicy.RELIABLE,
)

self.pub = self.create_publisher(Bool, "/some_topic", qos)
self.pub.publish(Bool(data=False))


def main(args=None):
rclpy.init(args=args)
node = PubNode()

try:
rclpy.spin(node)
except KeyboardInterrupt:
pass

node.destroy_node()
rclpy.shutdown()


if __name__ == "__main__":
main()
48 changes: 48 additions & 0 deletions prover_rclpy/src/rclpy_1163_sub.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
from rclpy.node import Node
from rclpy.qos import (
QoSDurabilityPolicy,
QoSProfile,
QoSReliabilityPolicy,
)
from std_msgs.msg import Bool
from rclpy.duration import Duration
import rclpy


class SubNode(Node):
def __init__(self):
super().__init__("sub_node")

qos = QoSProfile(
depth=5,
durability=QoSDurabilityPolicy.TRANSIENT_LOCAL,
reliability=QoSReliabilityPolicy.RELIABLE,
lifespan=Duration(seconds=2),
)
print(qos)
self.sub = self.create_subscription(
Bool,
"/some_topic",
self.my_callback,
qos,
)

def my_callback(self, msg: Bool):
self.get_logger().info("Received: {}".format(msg.data))


def main(args=None):
rclpy.init(args=args)
node = SubNode()

try:
rclpy.spin(node)
except KeyboardInterrupt:
pass

node.destroy_node()
rclpy.shutdown()


if __name__ == "__main__":
main()

0 comments on commit 1c8bbc6

Please sign in to comment.