Lab 1: Introduction and ROS tutorials - ece545au20/catkin_ws GitHub Wiki

Intro to ROS

Beginner Tutorial | Expect 60 minutes to finish

This blog serves as a cheat sheet of publisher & subscriber, service & client, it shows you the very basic pattern of these ROS Nodes. For line by line explanation, visit the following website:

Create beginner_tutorials package

$ cd ~/catkin_ws
$ catkin create pkg beginner_tutorials --catkin-deps roscpp rospy std_msgs
$ catkin build

Don't forget to

$ source ~/catkin_ws/devel/setup.bash

However, doing this repeatly could be annoying. Let’s add it to ~/.bashrc which will be executed in every newly opened terminal, so you don’t have to do it manually.

$ echo 'source ~/catkin_ws/devel/setup.bash' >> ~/.bashrc

Create Publisher & Subscriber

Publisher

$ roscd beginner_tutorials
$ mkdir scripts
$ cd scripts
$ touch talker.py # create a python file named 'talker.py'
$ chmod +x talker.py # make it executable
$ code talker.py # we assume you're using VSCode editor
#!/usr/bin/env python2
# license removed for brevity
import rospy
from std_msgs.msg import String

def talker():
    pub = rospy.Publisher('chatter', String, queue_size=10)
    rospy.init_node('talker', anonymous=True)
    rate = rospy.Rate(10) # 10hz
    while not rospy.is_shutdown():
        hello_str = "hello world %s" % rospy.get_time()
        rospy.loginfo(hello_str)
        pub.publish(hello_str)
        rate.sleep()

if __name__ == '__main__':
    try:
        talker()
    except rospy.ROSInterruptException:
        pass

Subscriber

$ roscd beginner_tutorials/scripts/
$ touch listener.py
$ chmod +x listener.py
#!/usr/bin/env python
import rospy
from std_msgs.msg import String

def callback(data):
    rospy.loginfo(rospy.get_caller_id() + "I heard %s", data.data)
    
def listener():

    # In ROS, nodes are uniquely named. If two nodes with the same
    # name are launched, the previous one is kicked off. The
    # anonymous=True flag means that rospy will choose a unique
    # name for our 'listener' node so that multiple listeners can
    # run simultaneously.
    rospy.init_node('listener', anonymous=True)

    rospy.Subscriber("chatter", String, callback)

    # spin() simply keeps python from exiting until this node is stopped
    rospy.spin()

if __name__ == '__main__':
    listener()

Then, edit the catkin_install_python() call in your CMakeLists.txt so it looks like the following:

catkin_install_python(
	PROGRAMS 
	scripts/talker.py 
	scripts/listener.py
  DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

Examining the Publisher and Subscriber

Open 3 terminal and run the following 3 cmd respectively.

$ roscore
$ rosrun beginner_tutorials talker.py 

You will see something similar to:

[INFO] [WallTime: 1314931831.774057] hello world 1314931831.77
[INFO] [WallTime: 1314931832.775497] hello world 1314931832.77
[INFO] [WallTime: 1314931833.778937] hello world 1314931833.78
[INFO] [WallTime: 1314931834.782059] hello world 1314931834.78
[INFO] [WallTime: 1314931835.784853] hello world 1314931835.78
[INFO] [WallTime: 1314931836.788106] hello world 1314931836.79
$ rosrun beginner_tutorials listener.py
[INFO] [WallTime: 1314931969.258941] /listener_17657_1314931968795I heard hello world 1314931969.26
[INFO] [WallTime: 1314931970.262246] /listener_17657_1314931968795I heard hello world 1314931970.26
[INFO] [WallTime: 1314931971.266348] /listener_17657_1314931968795I heard hello world 1314931971.26
[INFO] [WallTime: 1314931972.270429] /listener_17657_1314931968795I heard hello world 1314931972.27
[INFO] [WallTime: 1314931973.274382] /listener_17657_1314931968795I heard hello world 1314931973.27
[INFO] [WallTime: 1314931974.277694] /listener_17657_1314931968795I heard hello world 1314931974.28
[INFO] [WallTime: 1314931975.283708] /listener_17657_1314931968795I heard hello world 1314931975.28

Service and Client

Create a srv

$ roscd beginner_tutorials
$ mkdir srv

copy a service from the rospy_tutorials package:

$ roscp rospy_tutorials AddTwoInts.srv srv/AddTwoInts.srv

Unless you have done so already, open package.xml in beginner_tutorials package, and make sure these two lines are in it and uncommented.

  <build_depend>message_generation</build_depend>
  <exec_depend>message_runtime</exec_depend>

Unless you have done so already for messages in the previous step, add the message_generation dependency to generate messages in CMakeLists.txt:

# Do not just add this line to your CMakeLists.txt, modify the existing line
find_package(catkin REQUIRED COMPONENTS
  roscpp
  rospy
  std_msgs
  message_generation
)

And replace the placeholder Service*.srv files for your service files:

add_service_files(
  FILES
  AddTwoInts.srv
)

Service Node

Create the scripts/add_two_ints_server.py file within the beginner_tutorials package and paste the following inside it:

#!/usr/bin/env python

from __future__ import print_function

from beginner_tutorials.srv import AddTwoInts,AddTwoIntsResponse
import rospy

def handle_add_two_ints(req):
    print("Returning [%s + %s = %s]"%(req.a, req.b, (req.a + req.b)))
    return AddTwoIntsResponse(req.a + req.b)

def add_two_ints_server():
    rospy.init_node('add_two_ints_server')
    s = rospy.Service('add_two_ints', AddTwoInts, handle_add_two_ints)
    print("Ready to add two ints.")
    rospy.spin()

if __name__ == "__main__":
    add_two_ints_server()

Client Node

Create the scripts/add_two_ints_client.py file within the beginner_tutorials package and paste the following inside it:

from __future__ import print_function

import sys
import rospy
from beginner_tutorials.srv import *

def add_two_ints_client(x, y):
    rospy.wait_for_service('add_two_ints')
    try:
        add_two_ints = rospy.ServiceProxy('add_two_ints', AddTwoInts)
        resp1 = add_two_ints(x, y)
        return resp1.sum
    except rospy.ServiceException as e:
        print("Service call failed: %s"%e)

def usage():
    return "%s [x y]"%sys.argv[0]

if __name__ == "__main__":
    if len(sys.argv) == 3:
        x = int(sys.argv[1])
        y = int(sys.argv[2])
    else:
        print(usage())
        sys.exit(1)
    print("Requesting %s+%s"%(x, y))
    print("%s + %s = %s"%(x, y, add_two_ints_client(x, y)))

Don't forget to make both Service and Client node executable:

$ chmod +x scripts/add_two_ints_client.py
$ chmod +x scripts/add_two_ints_server.py

Then, edit the catkin_install_python() call in your CMakeLists.txt so it looks like the following:

catkin_install_python(
	PROGRAMS 
	scripts/add_two_ints_server.py
	scripts/add_two_ints_client.py
	DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

Examining the Service and Client

Make sure roscore is running.

$ rosrun beginner_tutorials add_two_ints_server.py  (Python) 

You should see something similar to:

Ready to add two ints.
$ rosrun beginner_tutorials add_two_ints_client.py 1 3  (Python) 

You should see something similar to:

Requesting 1+3
1 + 3 = 4

ROSBag

Run turtles teleop

Terminal 1:

$ roscore

Terminal 2:

$ rosrun turtlesim turtlesim_node

Terminal 3:

$ rosrun turtlesim turtle_teleop_key

Recording all published topics

First lets examine the full list of topics that are currently being published in the running system. To do this, open a new terminal and execute the command:

rostopic list --verbose

This should yield the following output:

Published topics:
 * /turtle1/color_sensor [turtlesim/Color] 1 publisher
 * /turtle1/cmd_vel [geometry_msgs/Twist] 1 publisher
 * /rosout [rosgraph_msgs/Log] 2 publishers
 * /rosout_agg [rosgraph_msgs/Log] 1 publisher
 * /turtle1/pose [turtlesim/Pose] 1 publisher

Subscribed topics:
 * /turtle1/cmd_vel [geometry_msgs/Twist] 1 subscriber
 * /rosout [rosgraph_msgs/Log] 1 subscriber

We now will record the published data. Open a new terminal window. In this window run the following commands:

$ mkdir ~/bagfiles
$ cd ~/bagfiles
$ rosbag record -a # -a means all 

If you just want to record the topics of your interests (the listed two topics):

  • /turtle1/cmd_vel
  • /turtle1/pose
$ rosbag record -O subset /turtle1/cmd_vel /turtle1/pose

The -O argument tells rosbag record to log to a file named subset.bag

Examining and playing the bag file

rosbag info <your bagfile>

You should see something like:

path:        2014-12-10-20-08-34.bag
version:     2.0
duration:    1:38s (98s)
start:       Dec 10 2014 20:08:35.83 (1418270915.83)
end:         Dec 10 2014 20:10:14.38 (1418271014.38)
size:        865.0 KB
messages:    12471
compression: none [1/1 chunks]
types:       geometry_msgs/Twist [9f195f881246fdfa2798d1d3eebca84a]
             rosgraph_msgs/Log   [acffd30cd6b6de30f120938c17c593fb]
             turtlesim/Color     [353891e354491c51aabe32df673fb446]
             turtlesim/Pose      [863b248d5016ca62ea2e895ae5265cf9]
topics:      /rosout                    4 msgs    : rosgraph_msgs/Log   (2 connections)
             /turtle1/cmd_vel         169 msgs    : geometry_msgs/Twist
             /turtle1/color_sensor   6149 msgs    : turtlesim/Color
             /turtle1/pose           6149 msgs    : turtlesim/Pose

This cmd will replay(publish) all the messages that you recorded to corresponding topic.

rosbag play <your bagfile>

rosbag API (write and read in a python script)

Example usage for write:

import rosbag
from std_msgs.msg import Int32, String

bag = rosbag.Bag('test.bag', 'w')

try:
    s = String()
    s.data = 'foo'

    i = Int32()
    i.data = 42

    bag.write('chatter', s)
    bag.write('numbers', i)
finally:
    bag.close()

Example usage for read:

import rosbag
bag = rosbag.Bag('test.bag')
for topic, msg, t in bag.read_messages(topics=['chatter', 'numbers']):
    print(msg)
bag.close()