ROS-Thymio: how it works

ROS-Thymio implements a Thymio-specific, ROS-conform interface on-top of the generic interface provided by ROS-Aseba.

It supports single and multiple robots through two different drivers:

  • thymio_driver for single robots: it connects to the first Thymio discovered by asebaros

  • multi_thymio_driver for multiple robots: it connects to any Thymio discovered by asebaros, using the namespace assigned to them by asebaros to separate them.

The two ROS driver share most functionality. In fact, multi_thymio_driver launches (for ROS2), or embed (for ROS1) a copy of thymio_driver for each discovered Thymio. When you want to connect to a single robot, you can pick one of the two driver, as they offer the same interface; to managed multiple Thymio in the same Aseba network with a single ROS driver, you have to use multi_thymio_driver instead.

Discovery

We assume that asebaros is already running and properly configured to connect to Thymios.

thymio_driver

thymio_driver first waits until one Thymio is discovered by asebaros; then, if the Aseba node is not already running a script, it tries to load the specified script. At that point, thymio_driver finalizes the initialization of the ROS node and starts the run-loop.

The image below illustrates the default configuration for single robot defined in main.launch. Three nodes are launched in the same ROS namespace (asebaros, thymio_driver, robot_state_publisher): thymio_driver synchronizes with asebaros waiting for the first connected Thymio.

Figure made with TikZ

single robot ROS-Thymio launched by main.launch with single=True

multi_thymio_driver

The multi-robot ROS driver multi_thymio_driver keeps checking if new Thymio get discovered by asebaros and launches a thymio_driver node, using the namespace passed by asebaros. For ROS1, as there can only be one ROS node per process, multi_thymio_driver does not actually create new nodes but exposes an analogous interface using a shared ROS node. Contrary to thymio_driver, multi_thymio_driver does not load a script to the newly discovered Aseba nodes, leaving this task solely to asebaros.

Figure made with TikZ

multi-robot ROS-Thymio launched by main.launch with single=False

Aseba Script[s]

As introduced in ROS-Aseba with ROS-Thymio, we use Aseba events to share data between Aseba and ROS. The specific ROS functionality implemented by thymio_driver is supported by events defined in a family of four Aseba scripts, which covers all combinations of simulated/real and single/multiple Thymios. The correct script is picked automatically based on the arguments of main.launch.

Robots simulated in Aseba Playground or Enki, do not have some of the Aseba API of real Thymios; in particular the following API are missing

  • _poweroff()

  • prox.comm.rx._payloads

  • prox.comm.rx._intensities

which the Aseba scripts for simulated robots do not use.

To support multiple Thymios, asebaros parameter include_id_in_events should be set to true: the multi* Aseba scripts use the id from the additional payload to filter commands, as explained in Events. All scripts are small variants of the script listed in ROS-Thymio Aseba script.

Functionality

Sensors

Odometry

Wheel odometry is computed onboard from the estimated wheel speed and exposed by asebaros as the event aseba/events/odometry. The parameter motor_deadband defines a deadband to filter out noise from the motor speed estimation.

If highest_acceptable_protocol_version is 1, the Aseba event is emitted once every motor_period update steps of the wheel odometry (which runs 100Hz), and it’s published by asebaros on aseba/events/odometry.

The ROS driver uses a simple [calibrated] quadratic function to map wheel steps r measured onboard in Aseba units to distance d in meters.

\[r \mapsto d = d_0 r + d_1 r |r|\]

Then, it applies forward kinematics and computes the odometry of the chassis (composed by position, orientation, linear and angular velocities) and publishes it as Odometry. The main advantage of this approach is that the accuracy does not depend on the rate at which the Aseba wheel odometry event is published.

Accelerometer

If emit_acc is 1, raw data from the accelerometer is filtered (mean value over a running window at 16Hz); every acc_period steps it is emitted and then exposed on aseba/events/accelerometer, which the ROS driver transforms into SI-units and publishes as IMU. The precision is very low as raw data has just 5-bit resolution.

Tap

When the Thymio detects a large acceleration, it interprets it as somebody tapping on it. The Thymio driver republishes these events on Tap.

Buttons

The robot emits a notification every time each one of the five buttons get pressed or released, which is exposed by asebaros on aseba/events/button_{backward,left,center,forward,right}, which the driver republishes as Individual Buttons.

Moreover, if emit_buttons is 1, the state of all buttons is filtered (mean value over a running window at 20Hz); every buttons_period steps it is emitted and then exposed on aseba/events/buttons, which the driver republishes as All Buttons emulating a joypad.

Proximity

Proximity sensors are read onboard at 10 Hz. If the parameter emit_proximity is 1, they are send to asebaros and published as aseba/events/proximity. The Thymio driver uses a calibration function to map reading r to distance d in meters.

\[\begin{split}r \mapsto d = \left\{ \begin{array}{lr} d_\inf, & \text{for } r = 0\\ d_0 + \sqrt{(d_0^ 2 - r_0) (1 - \frac{r_\max}{r})}, & \text{for } 0 < r < r_\max \\ d_\sup, & \text{for } r \geq r_\max \\ \end{array}\right\}\end{split}\]

Ground

Like proximity sensors, ground sensors are updated at 10 Hz if parameter emit_proximity is 1, and published by asebaros on aseba/events/ground. They are republished by thymio_driver as Ground Sensors with a binary resolution (i.e., with range: 0.0 or range: 1.0 depending if the reading is above or below the threshold defined by parameter ground.threshold).

If emit_ground_raw is 1, raw readings on ambient and reflected light is published on aseba/events/ground_{ambient,reflected} too.

Sound

Any sounds detected by the microphone with an high enough volume are republished as Sound. The threshold can be set publishing a message on Set sound threshold.

Temperature

The robot temperature (updated at 1Hz) is republished on Temperature.

Actuators

Wheels

As common for mobile robots in ROS, you control the robot velocity using a geometry_msgs/Twist (with linear and angular velocities) on Velocity command, where only forward speed `linear.x and angular speed angular.z need to be specified and will be considered. The mapping between a twist in SI-units and the target value of the motor speed uses the inverse of the calibration functions described in Odometry.

Sound

You can play a sound by sending a message

Alarm

We also expose a simple high-level interface to start/stop an alarm on Alarm.

LED

You set the color of the three large RGB LED using the topics Body LED,

You control the intensities of the other monochromatic small LED by sending a message to the topic LED, specifying:

  • the group of LED you target

  • a mask for individual LED in the group

  • the intensity value

Any LED not targeted by the group and mask, will keep the previous state.

Gestures

We also expose an interface to trigger LED gestures (or animations) on topic LED Gestures. Animations are implemented as travelling waves and are specified by

  • the group of LED

  • a mask for individual LED in the group

  • the type of the wave (rectangular or sinusoidal)

  • the period of the wave (with possible static waves)

  • the length of the wave (in number of LED)

  • bouncing back or not once the wave reaches the boundary.

We also define higher-level interfaces with predefined gestures, such as

  • switching off

  • blinking

  • circling

  • “I’m alive” pattern

Communication

Remote

Raw IR remote events are exposed on aseba/events/remote and republished by the driver as Remote Controller.

Proximity communication

The Thymio provides a local communication service through its proximity sensors. At the same 10 Hz frequency used to update proximity sensors, the robot, after the pulse used for the proximity sensing, can send an additional IR pulse, encoding a 11-bit payload in the interval between the two pulses. The Aseba API let you enable this communication interface, specify the payload to be transmitted, and query payloads received from the neighboring robots.

Using the Thymio driver, you can enable/disable proximity communication with the topic Proximity Communication Enable. You can also specify the default state for all robots using parameter enable_prox_comm.

When proximity communication is enabled, the Thymio will broadcast the payload set on topic Proximity Communication Transmit. Any message received, will be forwarded to topic Proximity Communication Received, which contains the payloads and intensities received by the seven individual sensors too that you can use to roughly estimate the position of the robot sending the message.

Note

The real Thymio firmware exposes the payload received by the individual sensors as prox.{_intensities,_payloads}. The Thymio simulated by the distributed and upstream versions of Aseba Playground does not implement proximity communication and in particular does not have the internal variables prox.{_intensities,_payloads}. The version available at https://github.com/jeguzzi/enki/tree/ir_comm does support proximity communication.

Robot Model

The robot model provided by thymio_description contains the complete description of the robot geometry, with realistic visual meshes (from original specifications) and simplified collision shapes. The model is needed to work with TF and visualize the robot in rviz.

Gazebo Simulation

You can use the model to simulate the robot in Gazebo where a subset of sensor and actuators are exposed:

  • odometry and velocity commands

  • proximity sensors

  • accelerometer

Note

Other simulators provide a more complete simulation of a Thymio running Aseba: Enki, Aseba Playground (based on Enki), Webots and CoppeliaSim.