(!) 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.

Roslisp Basic Usage

Description: This tutorial gives a brief intro to roslisp. For more, see the API documentation, and the code in the roslisp_tutorials ROS package.

Tutorial Level: BEGINNER

Next Tutorial: Organizing files for roslisp

This tutorial demonstrates the main features of roslisp without going into detail in the file structure of the roslisp packages or compiling and building such packages. For more info on that check out the next tutorial, Organizing Files.

Setup

To set up roslisp see the installation instructions.

To test that it works, get the sources of roslisp_tutorials into the src directory of your catkin workspace and compile the new packages:

$ catkin_make

or install the corresponding Debians if they're available for your system:

$ sudo apt-get install ros-DISTRO-roslisp-tutorials

(where DISTRO is, e.g., indigo) and then in 3 separate terminals run

$ roscore

$ rosrun roslisp_tutorials_basics talker

$ rosrun roslisp_tutorials_basics listener

The listener should start printing messages received from the talker.

Example for publishing and subscribing

First, we will create a talker node publishing regularly on a topic, and a subscriber node listening to the messages and printing them. Here's the code for the talker, that can also be found within roscd roslisp_tutorials_basics/src/. It shows how to use topics, and the code follows the examples given in the basic ROS tutorials for Python or c++.

https://raw.githubusercontent.com/code-iai/roslisp_tutorials/master/roslisp_tutorials_basics/src/talker.lisp

(in-package :roslisp-tutorials-basics)

(defun talker ()
  "Periodically print a string message on the /chatter topic"
  (with-ros-node ("talker")
    (let ((i 0) (pub (advertise "chatter" "std_msgs/String")))
      (loop-at-most-every .1
         (publish-msg pub :data (format nil "foo ~a" (incf i)))))))

Ros node code will usually be wrapped in a with-ros-node call as shown here, which handles command line arguments, makes sure to close subscriptions after shutdown, etc. The node name "talker" is arbitrary.

To publish on a topic, we need to first advertise the topic with a name and a topic type. The (advertise) function does that and returns a topic client that we can use for publishing.

The talker node then loops forever publishing to the topic. The publish-msg command creates a message (inferring the type from the publication object) and publishes it. Here's the corresponding listener:

https://raw.githubusercontent.com/code-iai/roslisp_tutorials/master/roslisp_tutorials_basics/src/listener.lisp

(in-package :roslisp-tutorials-basics)

(defun listener ()
  (with-ros-node ("listener" :spin t)
    (subscribe "chatter" "std_msgs/String" #'print)))

This node subscribes to the chatter topic, then spins. The callback to print just prints the data field of any received message. Note that the Lisp pretty printer works for ROS messages.

To modify this code, checkout the sources from http://www.ros.org/wiki/roslisp_tutorials into your catkin workspace first.

Example for service and client

These examples can also be found in the roslisp_tutorials_basics package. They use the service definitions from ROS/Tutorials/CreatingMsgAndSrv

Based on the service definitinos, a service provider can be created like this:

https://raw.githubusercontent.com/code-iai/roslisp_tutorials/master/roslisp_tutorials_basics/src/add-two-ints-server.lisp

(in-package :roslisp-tutorials-basics)

(def-service-callback AddTwoInts (a b)
  (ros-info (roslisp-tutorials) "Returning [~a + ~a = ~a]" a b (+ a b))
  (make-response :sum (+ a b)))


(defun add-two-ints-server ()
  (with-ros-node ("two_ints_server" :spin t)
    (register-service "add_two_ints" 'AddTwoInts)
    (ros-info (roslisp-tutorials) "Ready to add two ints.")))

AddTwoInts is the service type, declared in a .srv file. The callback should be named with that type. "add_two_ints" is the service name clients need to use.

As long as the node stays alive, requests to the service will be handled by calling the callback function. Its return value must be of the message response type of the service.

The code for a client looks like this:

https://raw.githubusercontent.com/code-iai/roslisp_tutorials/master/roslisp_tutorials_basics/src/add-two-ints-client.lisp

(in-package :roslisp-tutorials-basics)

(defun add-two-ints-client (a b)
  "adds by calling ros service"
  (with-ros-node ("two_ints_client")
    (if (not (wait-for-service "add_two_ints" 10))
      (ros-warn nil "Timed out waiting for service add_two_ints")
      (format t "~a + ~a = ~a~&"
              a b (sum (call-service "add_two_ints" 'AddTwoInts :a a :b b))))))


(defun add-two-ints-client-main ()
  ;; parse command line args
  (let ((args (cdr sb-ext:*posix-argv*)))
    (if (not (= 2 (length args)))
      (ros-info (roslisp-tutorials) "Error ~a~%usage: add_two_ints_client X Y" args)
      ;; else
      (add-two-ints-client (parse-integer (first args))
           (parse-integer (second args))))))

In case the service is provided by a different ROS package, you would need to load the autogenerated Lisp bindings for the services, and specify the service type with the according Lisp package namespace. E.g.:

;; in .asd file
:depends-on (:roslisp_tutorials_basics-srv)
;; in REPL
(ros-load:load-system "roslisp_tutorials_basics" "roslisp_tutorials_basics-srv")
;; in code
'roslisp_tutorials_basics-srv:AddTwoInts ; instead of just AddTwoInts

Interactive use

Lisp is most fun when used interactively. It is recommended to use Emacs with Slime and rosemacs Slime support.

If you do not want to setup your own Emacs copy with Slime, there is a ROS package roslisp_repl provided for that. Start a configured Emacs instance with an interactive Lisp session open by calling

$ rosrun roslisp_repl roslisp_repl

or simply

$ roslisp_repl

Otherwise, after starting Emacs, run M-x slime to start a Lisp REPL. (In Emacs, "M-x" means pressing the Meta Key usually labelled "Alt" and while keeping it pressed pressing the "x" key. Then enter "slime" in the minibuffer at the bottom of the emacs window.) This will only work if you have slime installed as a Debian on your system.

Starting a Lisp shell (REPL) instead of using rosemacs

You can run roslisp nodes interactively from within Lisp. To start sbcl:

$ sbcl

This starts a Lisp REPL. This has a prompt looking like this: "*", whereas the slime REPL in emacs has a prompt like this "CL-USER>". The latter will be used in tutorials.

Also note that if you have rlwrap installed (sudo aptitude install rlwrap), using this primitive shell will be more tolerable, e.g.

$ rlwrap sbcl

Outside rosemacs, the first step for using roslisp is to load the roslisp init file:

* (load #P"/PATH/TO/ROSLISP/scripts/roslisp-sbcl-init")

You can find out your path to roslip using rospack find roslisp. By default this is:

* (load #P"/opt/ros/YOUR_ROS_DISTRO/share/roslisp/scripts/roslisp-sbcl-init")

Note that the sbcl REPL can be quit by pressing Ctrl+d at the prompt.

See the installation instructions for details.

Running the installed tutorial examples

Once Lisp is started and the init script has been loaded, you can use specific ROS packages by loading the ASDF system found in that package's root directory. For example, to load roslisp_tutorials_basics,

CL-USER> (ros-load:load-system "roslisp_tutorials_basics" "roslisp-tutorials-basics")

This will take care of locating the roslisp_tutorials_basics package and all its dependencies as well as loading the corresponding .asd files.

The (talker) and (listener) functions shown above can be invoked using

CL-USER> (in-package :roslisp-tutorials-basics)
#<PACKAGE "ROSLISP-TUTORIALS-BASICS">
ROSLISP-TUTORIALS-BASICS> (talker)

and

CL-USER> (in-package :roslisp-tutorials-basics)
#<PACKAGE "ROSLISP-TUTORIALS-BASICS">
ROSLISP-TUTORIALS-BASICS>  (listener)

in two separate Lisp REPLs. You will need two terminals or two running Emacs (REPL) instances to run both the talker and the listener interactively.

Calling a service interactively

Let's start a ROS node. Make sure a roscore is running in a terminal.

$ roscore

In the REPL, do

;; load roslisp unless already done
CL-USER> (ros-load:load-system "roslisp_tutorials_basics" "roslisp-tutorials-basics")
CL-USER> (in-package :roslisp-tutorials-basics)
#<PACKAGE "ROSLISP-TUTORIALS-BASICS">

ROSLISP-TUTORIALS-BASICS> (start-ros-node "my_node")

Calling (start-ros-node) sets up a ros node in the context, this is good for interactive use, but else (with-ros-node) as used above is more comfortable, as it closes the node when not used anymore.

You can now call the various ROS commands, set up callbacks (which will run in the background), etc. For example, start up add_two_ints_server in a shell, one of those developed in the ROS tutorials on services

(LISP)
$ rosrun roslisp_tutorials_basics add-two-ints-server
(C++)
$ rosrun beginner_tutorials add_two_ints_server     
(Python)
$ rosrun beginner_tutorials add_two_ints_server.py  

Then, in the Lisp REPL type

;; start a node in case it's not running yet
ROSLISP-TUTORIALS-BASICS> (start-ros-node "server_client_node")
;; load srv system for message format
ROSLISP-TUTORIALS-BASICS> (ros-load:load-system "roslisp_tutorials_basics" "roslisp_tutorials_basics-srv")
;; create client node and call service
ROSLISP-TUTORIALS-BASICS> (roslisp:call-service 
                              "add_two_ints" ; name of service 
                              'roslisp_tutorials_basics-srv:AddTwoInts ; message type 
                              :a 42
                              :b 24)

If all goes well, this should print out a message containing the answer 66.

Shutting down a running ros node

Remember we started a ROS node earlier with (start-ros-node)? When done, remember to shut the ROS node down using

ROSLISP-TUTORIALS-BASICS> (shutdown-ros-node)

Logging

For Debugging purposes it is useful to add logging to certain functions. To use the ROS logging, it is possible to use

  (roslisp:ros-debug ...)
  (roslisp:ros-info ...)
  (roslisp:ros-warn ...)
  (roslisp:ros-error ...)

If roscore is running and there is a node launched in Lisp, the messages will go to /rosout and can be seen in rqt_console.

Try it. In a terminal start rqt_console:

$ rqt_console

Then in the REPL, type

ROSLISP-TUTORIALS-BASICS> (ros-warn my-debug-topic "Hello world")
[(MY-DEBUG-TOPIC) WARN] 1296084013.543: world
1

In the rqt_console, you should see the message appearing as well. The name my-debug-topic specifies a logging topic, whose log level can be higher or lower than warn, by default warn should be enabled, but debug not.

Log levels cannot currently be set by rxloggerlevel, but must be set within Lisp using (roslisp:set-debug-level <logger> <level>), or via a service interface (see the doxygen documentation).

Working with ROS messages

For the examples, we shall use geometry messages. In order for roslisp to have access to their structure, first load the ros package:

CL-USER> (ros-load:load-system "geometry_msgs" "geometry_msgs-msg")

To create a ros message for publishing on a topic, use (roslisp:make-message ...) or its alias (make-msg ...) The first argument is the name of the message type, then an even list of message slots and message contents are expected.

E.g.

CL-USER> (roslisp:make-msg "geometry_msgs/Point" (y) 2 (x) 1)

[GEOMETRY_MSGS-MSG:<POINT>
   X:
     1
   Y:
     2
   Z:
     0.0]

Note how the order of arguments is arbitrary, and how arguments not given are still filled according to the message structure. The '(x)' notation uses a list because that's how we can set values deeper in a hierarchy.

It's also easy to create and access nested message types, e.g. Pose contains a Point and a quaternion, the hard way looks like this:

(roslisp:make-message "geometry_msgs/Pose" 
  (position) (roslisp:make-msg "geometry_msgs/Point" (x) 3))
  (orientation) (roslisp:make-msg "geometry_msgs/Quaternion" (w) 1))

However, we can also directly create the hierarchy. Try, for example,

(defvar pose-message (roslisp:make-msg "geometry_msgs/Pose" 
  (x position) 3 
  (w orientation) 1))

This creates a Pose message.

You can get at the fields of a message you received (or the one we just created above) using calls like

(roslisp:with-fields ((x (x position)) orientation) pose-message
   (format t "~&X is ~a and orientation is ~a" x orientation))

X is 3 and orientation is [<QUATERNION>
                             X:
                               0.0
                             Y:
                               0.0
                             Z:
                               0.0
                             W:
                               1]

Modified objects can be created using

CL-USER> (defvar pose2 (roslisp:modify-message-copy pose-message (z position) 1.0))

Messages are actually CLOS objects, and to maximize efficiency, you can also access that representation directly: see the API for details.

Accessing the parameter server

Use

(roslisp:get-param ...)
(roslisp:set-param ...)
(roslisp:has-param ...)

etc.

See also

To continue your learning of roslisp, try out the following tutorials:

  • Actionlib Tutorial contains a tutorial explaining how to use the ros actionlib package from lisp

  • CL_TF Tutorial contains a tutorial explaining how to use the ros TF package from lisp

Wiki: roslisp/Tutorials/BasicUsage (last edited 2014-09-05 19:30:34 by GayaneKazhoyan)