Wiki

Only released in EOL distros:  

roomba_robot: roomba_500_series

Package Summary

iRobot Roomba 500 package based on the iRobot Open Interface Specification. There are two nodes available, a light node which exposes odometry and velocity commands, and a full node which exposes all capabilities of the underlying library.

The Roomba Robot

The roomba_500_series package was developed on top of the iRobot Open Interface Specification. The 500 series Roombas communicate over the same protocol that the popular iRobot Creates do, however the same protocol (although similar) is not shared with the older 400 series Roombas. This package was fully tested on the models 530, 555 and 560.

Roomba560_Roomba530_TopView.jpg

The Roomba is a very interesting and robust platform for mobile robot research. Although its performance is not comparable to that of a robot designed with research in mind, the extremely low price is a compelling argument.

Sensors

The Roomba comes equipped with the following sensors:

Actuators

The Roomba has the following actuators:

Accessories

Most Roomba models ship with the following accessories:

ROS API

Action API

The go_dock library present on the roomba560_node and godock_server nodes provides an implementation of the GoDockAction (see actionlib documentation), that automatically docks the Roomba. The GoDockAction is still experimental, it still needs a lot of work until it can be considered stable.

Action Subscribed Topics

godock/goal (roomba_500_series/GoDockActionGoal)

battery (roomba_500_series/Battery) ir_character (roomba_500_series/IRCharacter)

Action Published Topics

godock/result (roomba_500_series/GoDockActionResult)

cmd_vel (geometry_msgs/Twist)

roomba500_light_node

roomba500_light_node is a driver for any Roomba from the 500 series. It solely subscribes to velocity commands and publishes the robot's odometry.

Subscribed Topics

cmd_vel (geometry_msgs/Twist)

Published Topics

odom (nav_msgs/Odometry)

Parameters

roomba/port (string, default: /dev/ttyUSB0)

roomba560_node

roomba560_node is a driver for the Roomba 555 and 560. It exposes all the functionalities that these models have to offer. This node includes the GoDockAction.

Subscribed Topics

cmd_vel (geometry_msgs/Twist) leds (roomba_500_series/Leds) digit_leds (roomba_500_series/DigitLeds) song (roomba_500_series/Song) play_song (roomba_500_series/PlaySong)

Published Topics

odom (nav_msgs/Odometry) battery (roomba_500_series/Battery) bumper (roomba_500_series/Bumper) buttons (roomba_500_series/Buttons) cliff (roomba_500_series/RoombaIR) ir_bumper (roomba_500_series/RoombaIR) ir_character (roomba_500_series/IRCharacter) wheel_drop (roomba_500_series/WheelDrop)

Parameters

roomba/port (string, default: /dev/ttyUSB0)

godock_server

godock_server is a wrapper node for the GoDockAction created for testing and debugging.

godock_client

godock_client is a client implementation for the GoDockAction created for testing and debugging.

Custom Nodes

The iRobot Open Interface protocol for the 500 series Roomba is also available as a library on the roomba_500_series package. This can be used to make custom nodes with any desired combination of Roomba features. To start your own node check the Code API page.

Tutorials

Coming soon...

iRobot Open Interface Specification

The iRobot Open Interface Specification document used for developing this package can be found here.

Wiki: roomba_500_series (last edited 2010-12-14 11:43:13 by Gonçalo Cabrita)