Skip to content

The Example Message Publisher

The Code

Copy all the code below into your custom_msg_publisher.py file and review the annotations to see what's different to the basic publisher from Exercise 5.

custom_msg_publisher.py
#!/usr/bin/env python3

import rclpy
from rclpy.node import Node

from part1_pubsub.msg import Example # (1)!

class SimplePublisher(Node):

    def __init__(self):
        super().__init__("simple_publisher")

        self.my_publisher = self.create_publisher(
            msg_type=Example, # (2)!
            topic="my_topic",
            qos_profile=10,
        )

        publish_rate = 1 # Hz
        self.timer = self.create_timer(
            timer_period_sec=1/publish_rate,
            callback=self.timer_callback
        )

        self.get_logger().info(
            f"The '{self.get_name()}' node is initialised."
        )

    def timer_callback(self):
        ros_time = self.get_clock().now().seconds_nanoseconds()

        topic_msg = Example() # (3)!
        topic_msg.info = "The ROS time is..."
        topic_msg.time = ros_time[0]
        self.my_publisher.publish(topic_msg)
        self.get_logger().info(
            f"Publishing: '{topic_msg.info} {topic_msg.time:.0f}'"
        )

def main(args=None):
    rclpy.init(args=args)
    my_simple_publisher = SimplePublisher()
    rclpy.spin(my_simple_publisher)
    my_simple_publisher.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()
  1. We're now importing the Example message from our own part1_pubsub package.

  2. We're also now declaring that "my_topic" will use the Example message data structure to send messages.

  3. We need to deal with the topic messages differently now, to account for the more complex structure.

    We now populate our messages with two fields: info (a string) and time (an int). Identify what has changed here...