Note: This tutorial assumes that you have completed the previous tutorials: creating a ROS msg and srv.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Writing a Simple Publisher and Subscriber (Euslisp)

Description: This tutorial covers how to write a publisher and subscriber node in euslisp.

Tutorial Level: BEGINNER

Next Tutorial: Writing a Simple Service and Client (Euslisp)

Writing a Simple Publisher and Subscriber (Euslisp)

"Node" is the ROS term for an executable that is connected to the ROS network. Here we'll create the publisher ("talker") node which will continually broadcast a message.

Change directory into the beginner_tutorials package, you created in the earlier tutorial, creating a package:

roscd beginner_tutorials

The Code

First lets create a 'euslisp' folder to store our EusLisp scripts in:

$ mkdir euslisp

Then, create talker.l file under your new euslisp directly.

#!/usr/bin/env roseus
;;;
;;; euslisp version of ros_tutorials/rospy_tutorials/001_talker_listener
;;;

(ros::load-ros-manifest "roseus")

;;;
(ros::roseus "talker")
(ros::advertise "chatter" std_msgs::string 1)
(ros::rate 100)
(while (ros::ok)
  (setq msg (instance std_msgs::string :init))
  (send msg :data (format nil "hello world ~a" (send (ros::time-now) :sec-nsec)))
  (ros::ros-info "msg [~A]" (send msg :data))
  (ros::publish "chatter" msg)
  (ros::sleep)
  )
(ros::roseus "shutdown")
(exit)

Don't forget to make the node executable:

$ chmod +x euslisp/talker.l

The Code Explained

Now, let's break the code down.

#!/usr/bin/env roseus

Every ROSNodeNode will have this declaration at the top. The first line makes sure your script is executed as a roseus script.

(ros::load-ros-manifest "roseus")

Thisline reads roseus's manifest.xml to import all dependent files. You need to import roseus if you are writing a ROS Node. This will enable users to use std_msgs.msg so that we can reuse the std_msgs/String message type (a simple string container) for publishing.

(ros::roseus "talker")

The next line, (ros::roseus "talker"), is very important as it tells roseus the name of your node -- until roseus has this information, it cannot start communicating with the ROS Master. In this case, your node will take on the name talker.

NOTE: the name must be a base name, i.e. it cannot contain any slashes "/"

(ros::advertise "chatter" std_msgs::string 1)

This section of code defines the talker's interface to the rest of ROS. (ros::advertise "chatter" std_msgs::string 1) declares that your node is publishing to the chatter topic using the message type std_msgs::string.

(ros::rate 100)

This line creates a Rate object r. With the help of its method sleep(), it offers a convenient way for looping at the desired rate. With its argument of 100, we should expect to go through the loop 100 times per second (as long as our processing time does not exceed 1/100th of a second!)

(while (ros::ok)
  (setq msg (instance std_msgs::string :init))
  (send msg :data (format nil "hello world ~a" (send (ros::time-now) :sec-nsec)))
  (ros::ros-info "msg [~A]" (send msg :data))
  (ros::publish "chatter" msg)
  (ros::sleep)
  )

This loop is a fairly standard roseus construct: checking the (ros::ok) flag and then doing work. You have to check (ros::ok) to check if your program should exit (e.g. if there is a Ctrl-C or otherwise). In this case, the "work" is a call to   (ros::publish "chatter" msg) that publishes to our chatter topic using a newly created String message. The loop calls time.sleep(), which sleeps just long enough to maintain the desired rate through the loop.

This loop also calls   (ros::ros-info "msg [~A]" (send msg :data)), which performs triple-duty: the messages get printed to screen, it gets written to the Node's log file, and it gets written to rosout. [rosout] is a handy for debugging: you can pull up messages using [rqt_console] instead of having to find the console window with your Node's output.

(ros::roseus "shutdown")
(exit)

Finally we'll stop the node.

Writing the Subscriber Node

The Code

Next, let's create listener.l file under your new euslisp directly.

   1 #!/usr/bin/env roseus
   2 ;;;
   3 ;;; euslisp version of ros_tutorials/rospy_tutorials/001_talker_listener
   4 ;;;
   5 
   6 (ros::load-ros-manifest "roseus")
   7 ;;;
   8 
   9 ;;;
  10 ;;;
  11 (ros::roseus "listener" :anonymous t)
  12 ;;(setq sys::*gc-hook* #'(lambda (a b) (format t ";; gc ~A ~A~%" a b)))
  13 
  14 ;; callback function
  15 ;(defun string-cb (msg) (print (list 'cb (sys::thread-self) (send msg :data))))
  16 ;(ros::subscribe "chatter" std_msgs::string #'string-cb)
  17 
  18 ; lambda function
  19 ;(ros::subscribe "chatter" std_msgs::string
  20 ;                #'(lambda (msg) (ros::rosinfo 
  21 ;                                 (format nil "I heard ~A" (send msg :data)))))
  22 
  23 ;; method call
  24 (defclass string-cb-class
  25   :super propertied-object
  26   :slots ())
  27 (defmethod string-cb-class
  28   (:init () (ros::subscribe "chatter" std_msgs::string #'send self :string-cb))
  29   (:string-cb (msg) (print (list 'cb self (send msg :data)))))
  30 (setq m (instance string-cb-class :init))
  31 
  32 (do-until-key
  33  (ros::spin-once)
  34  ;;(sys::gc)
  35 )
  36 ;(ros::spin)

Don't forget to make the node executable:

$ chmod +x euslisp/listener.l

The Code Explained

The code for listener.l is similar to talker.l, except we've introduced a new callback-based mechanism for subscribing to messages.

  12 ;;(setq sys::*gc-hook* #'(lambda (a b) (format t ";; gc ~A ~A~%" a b)))
  13 
  14 ;; callback function

This declares that your node subscribes to the chatter topic which is of type std_msgs::String. When new messages are received, callback is invoked with the message as the first argument.

We also changed up the call to (ros::roseus ) somewhat. We've added the :anonymous t keyword argument. ROS requires that each node have a unique name. If a node with the same name comes up, it bumps the previous one. This is so that malfunctioning nodes can easily be kicked off the network. The :anonymous t flag tells roseus to generate a unique name for the node so that you can have multiple listener.l nodes run easily.

The final addition, (ros::spin) simply keeps your node from exiting until the node has been shutdown.

Building your nodes

We use CMake as our build system and, yes, you have to use it even for EusLisp nodes. This is to make sure that the autogenerated EusLisp code for messages and services is created.

Go to your catkin workspace and run catkin_make:

$ cd ~/catkin_ws
$ catkin_make

Running Nodes

Make sure that a roscore is up and running:

$ roscore

You will see something similar to:

... logging to /u/nkoenig/ros-jaunty/ros/log/d92b213a-90d4-11de-9344-00301b8246bf/roslaunch-ncq-11315.log
... loading XML file [/u/nkoenig/ros-jaunty/ros/tools/roslaunch/roscore.xml]
Added core node of type [rosout/rosout] in namespace [/]
started roslaunch server http://ncq:60287/

SUMMARY
========

NODES

starting new master (master configured for auto start)
process[master]: started with pid [11338]
ROS_MASTER_URI=http://ncq:11311/
setting /run_id to d92b213a-90d4-11de-9344-00301b8246bf
+PARAM [/run_id] by /roslaunch
+PARAM [/roslaunch/uris/ncq:60287] by /roslaunch
process[rosout-1]: started with pid [11353]
started core service [/rosout]
+SERVICE [/rosout/get_loggers] /rosout http://ncq:36277/
+SERVICE [/rosout/set_logger_level] /rosout http://ncq:36277/
+SUB [/time] /rosout http://ncq:36277/
+PUB [/rosout_agg] /rosout http://ncq:36277/
+SUB [/rosout] /rosout http://ncq:36277/

Now, we're ready to run talker/listener node. Open a new terminal and type follwings:

$ rosrun beginner_tutorials talker.l

Then, open another terminal and type:

$ rosrun beginner_tutorials listener.l

rosrun is a simple script to run any node under pacakge, you can directly run the node by typing ./talker.l.

Talker will outputs something like:

Registered [/talker-9224-1233892469.83] with master node http://localhost:11311
hello world 1233892469.86
hello world 1233892470.86
hello world 1233892471.86
hello world 1233892472.86
hello world 1233892473.86
...

And listener will show:

/listener-7457-1233891102.92: I heard hello world 1233892470.86
/listener-7457-1233891102.92: I heard hello world 1233892471.86
/listener-7457-1233891102.92: I heard hello world 1233892472.86
/listener-7457-1233891102.92: I heard hello world 1233892473.86
/listener-7457-1233891102.92: I heard hello world 1233892474.86
...

Now you write your first listener node, you also able to use rostopic that listens any type rof topic. If you run rostopic echo topic_name, you'll see outputs limilar to listener.l.

$ rostopic echo chatter

rostopic: topic is [/chatter]
topic type is [std_msgs/String]
---
data: hello world 1241463489.67
---
data: hello world 1241463490.67
---

Congratulations! You now use an EusLisp communicating with your ROS nodes!

For more depth information, please check roseus package or move to a next tutorial.


Wiki: ROS/Tutorials/WritingPublisherSubscriber(euslisp) (last edited 2014-12-17 05:28:20 by Kei Okada)