diff --git a/prover_rclpy/setup.py b/prover_rclpy/setup.py index 0d8723a..6564197 100644 --- a/prover_rclpy/setup.py +++ b/prover_rclpy/setup.py @@ -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', ], }, diff --git a/prover_rclpy/src/rclpy_1163_pub.py b/prover_rclpy/src/rclpy_1163_pub.py new file mode 100644 index 0000000..0a31598 --- /dev/null +++ b/prover_rclpy/src/rclpy_1163_pub.py @@ -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() \ No newline at end of file diff --git a/prover_rclpy/src/rclpy_1163_sub.py b/prover_rclpy/src/rclpy_1163_sub.py new file mode 100644 index 0000000..0d0e26d --- /dev/null +++ b/prover_rclpy/src/rclpy_1163_sub.py @@ -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() \ No newline at end of file