[ROS in 5 mins] 018 – What is a ROS message? Part#1

ROS-in-5-mins-018-–-What-is-a-ROS-message-Part1

Written by Bayode Aderinola

08/07/2018

In this post, we will see what a ROS message is all about! We’ll see how it relates to ROS nodes and topics.

Let’s go!

Step 1: Create a Project (ROSject) on ROSDS

Head to http://rosds.online and create a project named “ros_message” or whatever you like. Please ensure you select “Ubuntu 16.04 + ROS Kinetic + Gazebo 7” under “Configuration”.

Step 2: Create source files

Pick a Shell from the Tools menu and run the following commands:

user:~$ cd catkin_ws/src
user:~/catkin_ws/src$ touch obiwan.py obiwan_pub.py obiwan_sub.py #create the files
user:~/catkin_ws/src$ chmod +x obiwan.py obiwan_pub.py obiwan_sub.py # make them executable

Pick the IDE from the Tools menu. Locate the folder catkin_ws/src in the IDE’s file navigator, locate the corresponding files and paste the following code into them.

 obiwan.py

#! /usr/bin/env python

import rospy

rospy.init_node("sos_1")
rate = rospy.Rate(2)
while not rospy.is_shutdown():
    print "Help me Obi-Wan Kenobi, you're my only hope"
    rate.sleep()

obiwan_pub.py

#! /usr/bin/env python

import rospy
from std_msgs.msg import String

rospy.init_node("sos_2")
rate = rospy.Rate(2)
help_msg = String()
help_msg.data = "help me Obi-Wan Kenobi, you're my only hope"
pub = rospy.Publisher('/help_msg', String, queue_size = 1)
while not rospy.is_shutdown():
    pub.publish(help_msg)
    rate.sleep()

obiwan_sub.py

#! /usr/bin/env python

import rospy
from std_msgs.msg import String

def callback(msg):
    print "SOS received: '%s'!" %(msg.data)
    
rospy.init_node('help_desk')
sub = rospy.Subscriber('/help_msg', String, callback)
rospy.spin()

Step 3: Execute the files and observe…

First, start the ROS master in the background. Then check the ROS topics currently available:

user:~/catkin_ws/src$ nohup roscore &
user:~/catkin_ws/src$ rostopic list
/rosout
/rosout_agg

 obiwan.py

Run this command in the current terminal. You should see the following output:

ser:~/catkin_ws/src$ ./obiwan.py
Help me Obi-Wan Kenobi, you're my only hope
Help me Obi-Wan Kenobi, you're my only hope
...

Pick another Shell from the Tools menu and run the following command. You should see that no additional topic has been created:

user:~$ rostopic list
/rosout
/rosout_agg

obiwan_pub.py

Stop the obiwan.py program in the first terminal by pressing Ctrl + C. Then run the obiwan_pub.py program:

user:~/catkin_ws/src$ ./obiwan_pub.py

Program is doing nothing? Nah, we shall see shortly. In the second terminal, rerun the last command:

user:~$ rostopic list
/help_msg
/rosout
/rosout_agg

Ah, now we have a new topic: help_msg! But where’s the help message? We’ll see that in the third program.

obiwan_sub.py

In the second terminal, run the obiwan_sub program:

user:~$ cd catkin_ws/src
user:~/catkin_ws/src$ ./obiwan_sub.py
SOS received: 'Help me Obi-Wan Kenobi, you're my only hope'!
SOS received: 'Help me Obi-Wan Kenobi, you're my only hope'!

That’s the message being generated by the obiwan_pub.py program.

Now, let’s put everything together.

Step 4: Master the Concept: What is a ROS message?

The obiwan.py and obiwan_pub.py create similar messages. However, the message created by obiwan.py is NOT a ROS message because:

  1. It didn’t use a recognized ROS message type.
  2. It was not sent over a ROS channel (topic).

obiwan_pub.py publishes a message on the /help_msg topic while obiwan_sub subscribes to that topic and therefore gets the message.

In summary,

  1. ROS nodes communicate with one another through messages.
  2. They communicate over channels called topics.
  3. There are different types of messages for different tasks. For example, a node controlling a drone will tell the drone to take off using a ROS message type Empty over a topic that might be something like /drone/takeoff.
  4. Extra: when you send a message to a robot via the command line, you are a n*** …or at least behaving like one 🙂 .

If you are interested in how this works in detail or even you want to create your own messages, please check our ROS Basics In 5 Days (Python) course!

Extra 1: ROSject link

Get the ROSject containing all code used in the post in the following link: http://www.rosject.io/l/18f83296-0e7e-4c5c-95a7-2d3e3d6430d4/

Extra 2: Video

Prefer to watch a video demonstrating the steps above? We have one for you below!

Related Resources

If you are a ROS beginner and want to learn ROS basics fast, we recommend you take any of the following courses on Robot Ignite Academy:

Feedback

Did you like this post? Whatever the case, please leave a comment in the comments section below, so we can interact and learn from each other.

If you want to learn about other ROS topics, please let us know in the comments area and we will do a post or video about it.

Thank you!

Masterclass 2023 batch2 blog banner

Check Out These Related Posts

129. ros2ai

129. ros2ai

I would like to dedicate this episode to all the ROS Developers who believe that ChatGPT or...

read more

0 Comments

Trackbacks/Pingbacks

  1. [ROS in 5 mins] 020 - What is a ROS message? Part#2 | The Construct - […] https://www.theconstruct.ai/ros-5-mins-018-ros-message-part1/ […]

Submit a Comment

Your email address will not be published.

This site uses Akismet to reduce spam. Learn how your comment data is processed.

Pin It on Pinterest

Share This