[Documentation] [TitleIndex] [WordIndex

Interfacing ROS with Scratch

Scratch is the programming language from MIT [http://scratch.mit.edu/], aimed at helping introduce young people to programming.

In Scratch 3.0

The new extension system in Scratch 3.0 provides the user both full access to the Scratch core system (including variables, blocks, sprites) and full liberty to communicate with external interfaces though an JavaScript interface. This allows communications with ROS to be established the same way as in any other browser application, for instance by using roslibjs and rosbridge_server.

An experimental extension for integrating the newest Scratch interface with ROS, providing blocks for subscribing and publishing to topics, calling services and dealing with rosparams, can be found at [https://github.com/Affonso-Gui/scratch3-ros-vm].

In Scratch 2.0 and 1.4

The key to communicating with Scratch in older versions is the remote sensor connections [http://wiki.scratch.mit.edu/wiki/Remote_Sensor_Connections]. Any Scratch "broadcast" command or variable change is published to port 42001. Some simple example python code is also found here: [http://wiki.scratch.mit.edu/wiki/Communicating_to_Scratch_via_Python_with_a_GUI]. A library that simplifies communication between Python and Scratch can be found here: [https://github.com/pilliq/scratchpy].

There is also a "ROS from Scratch" project from Brown University [http://code.google.com/p/brown-ros-pkg/wiki/ROSScratch]. It seems like it may be a fairly complete solution, but also seems to take some time to set up.

The example ROS node below will listen on port 42001. If any Scratch variable "servo1" to "servo10" is changed, the value of the variable will be published on ROS topic "servo1_cmd" to "servo10_cmd".

Make sure to enable remote sensor connections in Scratch:

scratch_enable_sensor.png

Note that you must run scratch, and enable sensing before running this ROS node.

   1 #!/usr/bin/env python
   2 #   2012 Jon Stephan
   3 #   jfstepha@gmail.com
   4 
   5 from array import array
   6 import socket
   7 import time
   8 import sys
   9 import rospy
  10 import roslib
  11 import re
  12 from std_msgs.msg import Int16
  13 # roslib.load_manifest('knex_ros')
  14 
  15 ############################################################
  16 def sendScratchCommand(cmd):
  17 ############################################################
  18     n = len(cmd)
  19     a = array('c')
  20     a.append(chr((n >> 24) & 0xFF))
  21     a.append(chr((n >> 16) & 0xFF))
  22     a.append(chr((n >>  8) & 0xFF))
  23     a.append(chr(n & 0xFF))
  24     scratchSock.send(a.tostring() + cmd)
  25     
  26 ############################################################
  27 def rangeCallback(msg):
  28 ############################################################
  29     sendScratchCommand("sensor-update \"range\" %d" % msg.data)
  30     
  31 ############################################################
  32 if __name__ == '__main__':
  33 ############################################################
  34     rospy.loginfo("-I- knex_scratch_connector started")
  35     rospy.init_node('knex_scratch_connector')
  36     PORT = 42001
  37     HOST = 'localhost'
  38 
  39     rospy.loginfo("-D- Connecting...")
  40     scratchSock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
  41     scratchSock.connect((HOST, PORT))
  42     rospy.loginfo("-D- Connected!")
  43    
  44     pub_servo = [] 
  45     pub_servo.append(rospy.Publisher("servo1_cmd", Int16))
  46     pub_servo.append(rospy.Publisher("servo2_cmd", Int16))
  47     pub_servo.append(rospy.Publisher("servo3_cmd", Int16))
  48     pub_servo.append(rospy.Publisher("servo4_cmd", Int16))
  49     pub_servo.append(rospy.Publisher("servo5_cmd", Int16))
  50     pub_servo.append(rospy.Publisher("servo6_cmd", Int16))
  51     pub_servo.append(rospy.Publisher("servo7_cmd", Int16))
  52     pub_servo.append(rospy.Publisher("servo8_cmd", Int16))
  53     pub_servo.append(rospy.Publisher("servo9_cmd", Int16))
  54     pub_servo.append(rospy.Publisher("servo10_cmd", Int16))
  55     
  56     rospy.Subscriber("range", Int16, rangeCallback)
  57 
  58     while True:
  59         data = scratchSock.recv(1024)
  60         if not data: break
  61         l = list(data)
  62         msg_len = (ord(l[0]) << 24) + (ord(l[1]) << 16) + (ord(l[2]) << 8) + ord(l[3])
  63         l2 = l[4:]
  64         msg_str = ''.join(l2)
  65         rospy.loginfo("received %d bytes:%s" % (msg_len, msg_str))
  66         if(len(msg_str) != msg_len):
  67             rospy.logerr("-E- ERROR - message length differs from sent length.  (%d vs %d)" % (msg_len, len(msg_str)))
  68             
  69         print("find: %d" % msg_str.find('sensor-update "servo'))
  70         if(msg_str.find('sensor-update "servo') == 0):
  71             rospy.loginfo('-D- found sensor update')
  72             r = re.compile('servo(\d+)"\s+(\d+)')
  73             m = r.search(msg_str)
  74             servo_no = int(m.group(1))
  75             servo_val = int(m.group(2))
  76             if(servo_no > 0 and servo_no <= 10):
  77                 pub_servo[servo_no-1].publish(servo_val)
  78             else:
  79                 rospy.logerr("-E- servo %s out of range" % servo_no)
  80             

A simple scratch program to make use of this connector would look like this:

sshot_scratch_prog.png

This simply uses the arrow keys to control servo1 variable. When the value of the variable is changed, Scratch broadcasts this on port 42001. The ROS Python node recieves the messages and republishes them on ROS topic servo1_cmd).

When a message is published on ROS topic range, the ROS Python node rebroadcasts it to port 42001. Scratch picks this up as a sensor value, and this Scratch program sets the sprite's x position to the value of range.

Note that this code contains almost no error checking so use with caution.


2024-11-23 17:54