Sensors

The Roomba’s sensor packet is 26 bytes long, and is divided into three groups:

  • External: Sensors that get information about the external environment.
    • Bumper: The bumper is the movable part on the front of the Roomba.  It has a pressure sensor on each side of the machine, so it can tell if the Roomba bumped into something on the left or right side.
    • Wheeldrops: Each of the Roomba’s wheels has a drop sensor that detects if the wheel has dropped off the ground (e.g. if the Roomba drives over a cliff).
    • Wall: The wall sensor is an infrared proximity sensor that detects whether the Roomba is driving next to a wall.  It is located in a little hole on the right side of the bumper unit.
    • Cliff: There are four cliff sensors spread around the underside of the bumper.  If you turn the Roomba over you can see the infrared LEDs recessed into the plastic, far enough in that the beam has some space to bounce off the ground into the nearby infrared sensor.
    • Virtual Wall: The little round sensor with clear plastic sides on top of the bumper unit is an omnidirectional infrared sensor.  The virtual wall unit outputs a modulated infrared signal, and if the Roomba receives that signal it detects the virtual wall.
    • Motor Overcurrents: There are five motors (left wheel, right wheel, main brush, vacuum, and side brush).  If one of the motors can’t turn (e.g. if it’s seized by external conditions) then it will draw excessive current that the Roomba can detect.
    • Dirt Detect: I think the DD sensor is the little brass disc that you can see when you take out the vacuum brush, but I’m not sure.
  • Chassis: Sensors that get information about the Roomba’s position and interface.
    • Remote Opcode: Holds the current signal being sent by the Roomba remote control (or 255 if there’s no command).
    • Buttons: Binary state of the power, spot, clean, and max buttons (pressed or not pressed).
    • Distance: Number of mm travelled since the last time the chassis sensor packet was read.  This number isn’t very precise, because the Roomba’s drive system slips unpredictably.  The distance is the average distance travelled by the two wheels.  This value is reset to 0 on the Roomba every time the Chassis group is read.
    • Angle: The difference in orientation between the Roomba’s position at the time the chassis sensor packet was read and the previous reading.  The formulas for converting this value to radians or degrees are in the Roomba SCI spec.  The angle sensor is imprecise for the same reason as the Distance sensor.  I recommend not using floating point arithmetic for angle calculations, because the AVR has to simulate it; it’s better to work in integers (but watch out for overflow and truncation).  This value is reset to 0 on the Roomba every time the Chassis group is read.
  • Internal: Sensors that get information about the Romba’s internal state.
    • Charging State: Indicates whether the Roomba is not charging, recovery charging, charging normally, trickle charging, waiting or has a charging error.
    • Voltage: The voltage across the Roomba’s battery terminals, measured in millivolts.  This is nominally between 15000 and 17000.
    • Current: The current flowing into the Roomba’s battery (positive when charging, negative when discharging).
    • Temperature: The temperature of the Roomba’s battery, in degrees Celsius.
    • Charge: The current amount of charge left in mAh.  This value, divided by the value of the Current sensor, gives an estimate of the remaining time before the battery is depleted (in hours).
    • Capacity: An estimate of the maximum charge the battery can hold.  The battery is 100% charged when the Charge reading equals Capacity.

The following table summarizes the sizes of the three sensor packets:

Packet Group Data Size Serial Transmission Size Transmission Time at 38400 bps
External 10 bytes 100 bits 2.6 ms
Chassis 6 bytes 60 bits 1.6 ms
Internal 10 bytes 100 bits 2.6 ms

The Roomba can be commanded to send each group individually or all three groups at once, but sending all three groups takes 6.8 ms.  When using the RTOS, a task will be interrupted by the kernel every 5 ms.  If the UART module receives two bytes while the kernel is running (i.e. while interrupts are disabled) then it will miss the first byte.  The Roomba_UpdateSensorPacket() function will enter an infinite loop if it misses a byte.

For that reason, I don’t provide a way to update all three groups in a sensor packet simultaneously, which is an option that the Roomba provides.  It’s nice for RTOS tasks to update only one packet group per time slice, to reduce the likelihood that the update is interrupted by the kernel.  (The same warning applies to all interrupts, but if your interrupts are running for long enough to miss a UART byte then you’ve got other problems.)  Here is a sample RTOS task to update a sensor packet structure.

roomba_sensor_data_t sensors;
uint16_t distance_accumulator;
void roomba_sensor_task()
{
    ROOMBA_SENSOR_GROUP last_group = INTERNAL;
    for (;;)
    {
        switch (last_group)
        {
        case EXTERNAL:
            last_group = CHASSIS;
            Roomba_UpdateSensorPacket(CHASSIS, &sensors);
            break;
        case CHASSIS:
            last_group = INTERNAL;
            Roomba_UpdateSensorPacket(INTERNAL, &sensors);
            distance_accumulator += sensors.distance.value;
            break;
        case INTERNAL:
            last_group = EXTERNAL;
            Roomba_UpdateSensorPacket(EXTERNAL, &sensors);
            break;
        default:
            last_group = INTERNAL;
            break;
        }
        Task_Next();
    }
}

The task moves through a finite state machine with one state for each sensor group.  Each time the task runs it retrieves one of the groups.  When the task updates the Chassis group, it reads the distance sensor and keeps a running total of the distance that the Roomba has travelled.  The task can run as a periodic or round-robin task.

It could also be useful to modify the above example to skip a group that contains data that aren’t used.  Another idea is to build in a command queue that sends one or two commands every time the task runs, which would allow the application to schedule commands tied to the periodic task schedule.  Combining the Roomba’s commands and sensor updates in a single task is good design anyway, and will probably give a boost to your marks.

There’s another problem though: there is a delay between the end of the sensor packet request and the start of the response, and that latency is variable depending on your polling frequency and what group you request.  The following table gives some examples:

Polling Frequency Latency (External) Latency (Chassis) Latency (Internal)
10 Hz 1 ms 2.5 ms 1 ms
2 Hz 5 ms 6 ms 5 ms
1 Hz 13 ms 15 ms 13 ms

I have no explanation for why any of this happens.  It’s probably updating the sensor data or something.  I haven’t done a rigorous investigation of this problem, the values above are rough averages of several samples over a couple tests per condition, all taken while the Roomba was driving at 100 mm/s.  This screenshot shows the latency between transmitting a Chassis packet request and receiving the data back, with a polling frequency of 10 Hz:

Be especially wary of this problem when using periodic tasks, because the unexpected delay might cause the task to exceed its scheduled length.

This is terrible, because it means there’s no elegant way to guarantee that a sensor group will be received in a single timeslice.  The best solution to the problem is to run the UART at 9600 Bd instead of 38400 Bd.  The UART receiver is double-buffered, so the last byte to be received is available while the next byte is coming in.  At 9600 Bd, each byte takes about 1 ms to be fully received, so as long as the UART interrupt is able to execute and copy the received byte at least once every millisecond, there is no risk of overrun errors.  Running the UART so slow will not have a negative impact on performance.  Each sensor group will take a maximum of 10 ms to arrive (not including the transmission latency), and hopefully the sensor polling period is much larger than that.

Polling the distance and angle sensors too frequently can lead to inaccurate results (I mean, even more inaccurate than usual).  The sensor’s resolution is 1 mm, so every time you read the Chassis group the distance measurement is truncated.  If you poll too frequently then the error builds up.  On the other hand, polling too infrequently will often result in overshooting the distance/angle goal.  Slowing down the Roomba will add some leeway in the balance of these two factors, but you will have to accept that the sensors just aren’t super-accurate.