ROS Nodes, Publisher, and Subscribers
The basic building blocks of ROS are nodes. (referred to as ROS Nodes)
Here is a more in-depth description if interested: Articulated Robotics
Think of them as online accounts where any node can publish posts to some topic and any account can subscribe to any topic to receive updates on new posts.


Let’s create a basic example of one publisher node and one subscriber node.
All the publisher will do is send the message Hello World over and over again to a topic and the subscriber node will listen to the topic and print out the result.
Publisher
create a file called publisher.py
inside import the ROS libraries:
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
Then create a class called MinimalPublisher and have it extend the Node class we imported.
Then in the constructor, we first run the parent class’s constructor, Node, with:
The string we pass in is the name of the node
super().__init__("minimal_publisher")
Then we create a publisher object and a timer object:
self.publisher_ = self.create_publisher(String, "my_topic", 10)
self.timer = self.create_timer(0.5, self.timer_callback)
The publisher object is what actually sends the message "Hello World" to the topic my_topic it takes in the message type, the topic to publish to, and its QoS profile (don’t worry about this).
The timer object is to call the function timer_callback every 0.5 seconds.
Now let us create the function timer_callback and have it send "Hello World"
def timer_callback(self):
msg = String() # create msg object
msg.data = "Hello World" # fill it with data
self.publisher_.publish(msg) # publish the message
self.get_logger().info("Publishing: " + msg.data) # print msg
We first create a msg object and fill it with the string "Hello World"
Then we actually publish the msg with self.publisher_.publish(msg)
finally we printout self.get_logger().info("Publishing: " + msg.data)
To run the node go outside of the class and add the following
def main():
rclpy.init() # initializes the rclpy library
minimal_publisher = MinimalPublisher() # creates our MinimalPublisher object
rclpy.spin(minimal_publisher) # causes it to loop forever
minimal_publisher.destroy_node() # Destroy the node explicitly
rclpy.shutdown()
# makes it so that it only runs the main function
# when the file is being called directly
if __name__ == '__main__':
main()
Solution
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
class MinimalPublisher(Node):
def __init__(self):
super().__init__('minimal_publisher')
self.publisher_ = self.create_publisher(String, 'my_topic', 10)
self.timer = self.create_timer(0.5, self.timer_callback)
def timer_callback(self):
msg = String() # create msg object
msg.data = 'Hello World' # fill it with data
self.publisher_.publish(msg) # publish the message
self.get_logger().info('Publishing: ' + msg.data) # print msg
def main():
rclpy.init() # initializes the rclpy library
minimal_publisher = MinimalPublisher() # creates our MinimalPublisher object
rclpy.spin(minimal_publisher) # causes it to loop forever
minimal_publisher.destroy_node() # Destroy the node explicitly
rclpy.shutdown()
if __name__ == '__main__':
main()
run with: python3 publisher.py in the terminal

To stop the programs do ctrl+c
Subscribers
create a file called subscriber.py and paste the following
import rclpy
from rclpy.node import Node
from std_msgs.msg import String
class MinimalSubscriber(Node):
def __init__(self):
super().__init__('minimal_subscriber')
self.subscription = self.create_subscription(String, 'my_topic', self.listener_callback, 10)
self.subscription # prevent unused variable warning
def listener_callback(self, msg):
self.get_logger().info('I heard: "%s"' % msg.data)
def main():
rclpy.init() # initializes the rclpy library
minimal_subscriber = MinimalSubscriber()
rclpy.spin(minimal_subscriber)
# Destroy the node explicitly
minimal_subscriber.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
Then while running python3 publisher.pyopen a new terminal and run: python3 subscriber.py

If both of your nodes are running you will see that the publisher and subscriber are communicating

To view all the nodes run rqt_graph in a new terminal

ros2 node list

ros2 topic list

ros2 topic info /my_topic

ros2 topic echo /my_topic

Log ROS Messages:
self.get_logger().info('I heard: "%s"' % 2)
Exercise!!!! ( YAY :D )
- create 2 publishers and 1 subscriber where the 2 publishers are sending 1 number over each and the subscriber just adds together the result